Coordinates Module
C++ source code: C++ code
Python Binding (pybind11) : pybind11 code
class cnoid.IRSLCoords.coordinates
- class cnoid.IRSLCoords.coordinates
Bases:
pybind11_object
coordinates for choreonoid Referring to https://github.com/euslisp/EusLisp/blob/master/doc/jlatex/jmanual.pdf
Usage and description, see Coordinates
- property RPY
Rotation part of transformation ( RPY angle, real vector with 3 elements, roll [radian], pitch [radian], yaw [radian] )
- Returns:
1x3 vector
- Return type:
numpy.array
- __init__(*args, **kwargs)
Overloaded function.
__init__(self: cnoid.IRSLCoords.coordinates) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[4, 1]]) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: numpy.ndarray[numpy.float64[3, 1]]) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: numpy.ndarray[numpy.float64[4, 1]]) -> None
__init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous]) -> None
- property angleAxis
Rotation part of transformation ( Angle axis, real vector with 4 elements, ax, ay, az, rotation-angle [radian] )
- Returns:
1x4 vector
- Return type:
numpy.array
- property cnoidPosition
Transformation matrix ( 4x4 homogeneous transformation matrix, using in Choreonoid )
- Returns:
4x4 matrix
- Return type:
numpy.array
- copy(self: cnoid.IRSLCoords.coordinates) cnoid.IRSLCoords.coordinates
Creating new instance with the same value of this instance
- Returns:
copy of this instance (created new instance)
- Return type:
- difference_position(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates) numpy.ndarray[numpy.float64[3, 1]]
- difference_rotation(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates) numpy.ndarray[numpy.float64[3, 1]]
- equal(self: cnoid.IRSLCoords.coordinates, cds: cnoid.IRSLCoords.coordinates, eps: float = 1e-05) bool
- getRPY(self: cnoid.IRSLCoords.coordinates) numpy.ndarray[numpy.float64[3, 1]]
- getRotationAngle(self: cnoid.IRSLCoords.coordinates) numpy.ndarray[numpy.float64[4, 1]]
- get_transformed(*args, **kwargs)
Overloaded function.
get_transformed(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
get_transformed(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates, arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
- static init2D(arg0: float, arg1: float, arg2: float) cnoid.IRSLCoords.coordinates
- inverse(self: cnoid.IRSLCoords.coordinates) cnoid.IRSLCoords.coordinates
Updating self transformation as an inverse transformation
- Returns:
identical instance which was called with this method
- Return type:
- inverseRotateVector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1], flags.writeable]) numpy.ndarray[numpy.float64[3, 1], flags.writeable]
- inverseTransformVector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1], flags.writeable]) numpy.ndarray[numpy.float64[3, 1], flags.writeable]
- inverse_rotate_vector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) numpy.ndarray[numpy.float64[3, 1]]
- inverse_transform_vector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) numpy.ndarray[numpy.float64[3, 1]]
- inverse_transformation(self: cnoid.IRSLCoords.coordinates) cnoid.IRSLCoords.coordinates
- locate(*args, **kwargs)
Overloaded function.
locate(self: cnoid.IRSLCoords.coordinates, vector: numpy.ndarray[numpy.float64[3, 1]], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
locate(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
- mid_coords(self: cnoid.IRSLCoords.coordinates, p: float, c2: cnoid.IRSLCoords.coordinates, eps: float = 1e-05) cnoid.IRSLCoords.coordinates
Calculating interpolated coordinates
- Parameters:
p (float) – parameter 0.0 to 1.0, if p == 0.0, coords euqal to self is return. If p == 1.0, coords equal to c2 is return.
c2 (cnoid.IRSLCoords.coordinates) – target coordinates
eps (float, default = 0.00001) – precision
- Returns:
Interpolated coordinates
- Return type:
- move_to(*args, **kwargs)
Overloaded function.
move_to(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
move_to(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates, arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
- newcoords(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates) cnoid.IRSLCoords.coordinates
- static normalizeVector(*args, **kwargs)
Overloaded function.
normalizeVector(arg0: numpy.ndarray[numpy.float64[3, 1], flags.writeable]) -> numpy.ndarray[numpy.float64[3, 1], flags.writeable]
normalizeVector(arg0: numpy.ndarray[numpy.float64[4, 1], flags.writeable]) -> numpy.ndarray[numpy.float64[4, 1], flags.writeable]
- static normalized(*args, **kwargs)
Overloaded function.
normalized(arg0: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[3, 1]]
normalized(arg0: numpy.ndarray[numpy.float64[4, 1]]) -> numpy.ndarray[numpy.float64[4, 1]]
- orient(*args, **kwargs)
Overloaded function.
orient(self: cnoid.IRSLCoords.coordinates, theta: float, axis: numpy.ndarray[numpy.float64[3, 1]], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
orient(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]], arg2: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
orient(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]], arg2: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> cnoid.IRSLCoords.coordinates
- orient_with_matrix(*args, **kwargs)
Overloaded function.
orient_with_matrix(self: cnoid.IRSLCoords.coordinates, mat: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
orient_with_matrix(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
orient_with_matrix(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> cnoid.IRSLCoords.coordinates
- property pos
Translation part ( real vector with 3 elements, x, y, z ) of transformation matrix
- Returns:
1x3 vector
- Return type:
numpy.array
- property quaternion
Rotation part of transformation ( quaternion, real vector with 4 elements, x, y, z, w )
- Returns:
1x4 vector
- Return type:
numpy.array
- property rot
Rotation part of transformation ( Rotation matrix, 3x3 real matrix)
- Returns:
3x3 matrix
- Return type:
numpy.array
- rotNormalize(self: cnoid.IRSLCoords.coordinates) None
- rotate(*args, **kwargs)
Overloaded function.
rotate(self: cnoid.IRSLCoords.coordinates, theta: float, axis: numpy.ndarray[numpy.float64[3, 1]], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
rotate(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]], arg2: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
rotate(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]], arg2: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> cnoid.IRSLCoords.coordinates
- rotateVector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1], flags.writeable]) numpy.ndarray[numpy.float64[3, 1], flags.writeable]
- rotate_vector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) numpy.ndarray[numpy.float64[3, 1]]
- rotate_with_matrix(*args, **kwargs)
Overloaded function.
rotate_with_matrix(self: cnoid.IRSLCoords.coordinates, mat: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
rotate_with_matrix(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
rotate_with_matrix(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> cnoid.IRSLCoords.coordinates
- setCoordsToPosition(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[4, 4], flags.writeable, flags.c_contiguous]) None
Set transformation matrix (changing value of argument)
- Parameters:
position_to_be_set (numpy.array) – 4x4 homogeneous transformation matrix, using in Choreonoid
- setRPY(*args, **kwargs)
Overloaded function.
setRPY(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) -> None
setRPY(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: float, arg2: float) -> None
- setRotationAngle(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[4, 1]]) cnoid.IRSLCoords.coordinates
- toPosition(self: cnoid.IRSLCoords.coordinates) numpy.ndarray[numpy.float64[4, 4]]
- transform(*args, **kwargs)
Overloaded function.
transform(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
transform(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates, arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
- transformVector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1], flags.writeable]) numpy.ndarray[numpy.float64[3, 1], flags.writeable]
- transform_vector(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) numpy.ndarray[numpy.float64[3, 1]]
- transformation(*args, **kwargs)
Overloaded function.
transformation(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
transformation(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates, arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
- translate(*args, **kwargs)
Overloaded function.
translate(self: cnoid.IRSLCoords.coordinates, vector: numpy.ndarray[numpy.float64[3, 1]], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates
translate(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates
- class wrt
Bases:
pybind11_object
Members:
local
world
parent
- __init__(self: cnoid.IRSLCoords.coordinates.wrt, value: int) None
- property name
- property x_axis
Extracting x-axis of rotation matrix (1st column vector)
- Returns:
1x3 vector, x-axis of rotation matrix (1st column vector)
- Return type:
numpy.array
- property y_axis
Extracting y-axis of rotation matrix (2nd column vector)
- Returns:
1x3 vector, y-axis of rotation matrix (2nd column vector)
- Return type:
numpy.array
- property z_axis
Extracting z-axis of rotation matrix (3rd column vector)
- Returns:
1x3 vector, z-axis of rotation matrix (3rd column vector)
- Return type:
numpy.array
module cnoid.IRSLCoords
Functions for manipulating 4x4 matrix as homogeneous transformation matrix
- cnoid.IRSLCoords.PositionInverse(arg0: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous]) numpy.ndarray[numpy.float64[4, 4]]
Generating inverse transformation matrix
- Parameters:
_position (numpy.array) – 4x4 homogeneous transformation matrix, using in Choreonoid
- Returns:
4x4 matrix, inverse matrix of _position
- Return type:
numpy.array
- cnoid.IRSLCoords.Position_mid_coords(p: float, c1: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], c2: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], eps: float = 1e-05) numpy.ndarray[numpy.float64[4, 4]]
- cnoid.IRSLCoords.Position_quaternion(arg0: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous]) numpy.ndarray[numpy.float64[4, 1]]
Extracting rotation part of transformation matrix
- Parameters:
_position (numpy.array) – 4x4 homogeneous transformation matrix, using in Choreonoid
- Returns:
1x4 vector, quaternion(x,y,z,w), rotation part of _position
- Return type:
numpy.array
- cnoid.IRSLCoords.Position_rotate(cds: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], theta: float, axis: numpy.ndarray[numpy.float64[3, 1]], wrt: str = 'local') numpy.ndarray[numpy.float64[4, 4]]
- cnoid.IRSLCoords.Position_rotate_with_matrix(cds: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], mat: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], wrt: str = 'local') numpy.ndarray[numpy.float64[4, 4]]
- cnoid.IRSLCoords.Position_rotation(arg0: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous]) numpy.ndarray[numpy.float64[3, 3]]
Extracting rotation part of transformation matrix
- Parameters:
_position (numpy.array) – 4x4 homogeneous transformation matrix, using in Choreonoid
- Returns:
3x3 matrix, rotation matrix, rotation part of _position
- Return type:
numpy.array
- cnoid.IRSLCoords.Position_transform(cds: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], c: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], wrt: str = 'local') numpy.ndarray[numpy.float64[4, 4]]
- cnoid.IRSLCoords.Position_transformation(cds: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], c: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], wrt: str = 'local') numpy.ndarray[numpy.float64[4, 4]]
- cnoid.IRSLCoords.Position_translation(arg0: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous]) numpy.ndarray[numpy.float64[3, 1]]
Extracting translation part of transformation matrix
- Parameters:
_position (numpy.array) – 4x4 homogeneous transformation matrix, using in Choreonoid
- Returns:
1x3 vector, translation part of _position
- Return type:
numpy.array
- cnoid.IRSLCoords.angleAxisNormalized(arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]]) numpy.ndarray[numpy.float64[3, 3]]
Converting AngleAxis to rotation matrix, axis is normalized
- Parameters:
angle (float) – rotation angle [radian]
axis (numpy.array) – 1x3 vector, rotation axis
- Returns:
3x3, rotation matrix
- Return type:
numpy.array
- cnoid.IRSLCoords.angleVector(*args, **kwargs)
Overloaded function.
angleVector(arg0: cnoid.Body.Body) -> numpy.ndarray[numpy.float64[m, 1]]
angleVector(arg0: cnoid.Body.Body, arg1: numpy.ndarray[numpy.float64[m, 1]]) -> None
- cnoid.IRSLCoords.cnoidPosition(*args, **kwargs)
Overloaded function.
cnoidPosition(arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]
cnoidPosition(arg0: numpy.ndarray[numpy.float64[4, 1]], arg1: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]
cnoidPosition(arg0: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]
cnoidPosition(arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> numpy.ndarray[numpy.float64[4, 4]]
cnoidPosition(arg0: numpy.ndarray[numpy.float64[4, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]
- cnoid.IRSLCoords.eps_eq(*args, **kwargs)
Overloaded function.
eps_eq(a: float, b: float, eps: float = 1e-05) -> bool
eps_eq(a: numpy.ndarray[numpy.float64[3, 1]], b: numpy.ndarray[numpy.float64[3, 1]], eps: float = 1e-05) -> bool
eps_eq(a: numpy.ndarray[numpy.float64[4, 1]], b: numpy.ndarray[numpy.float64[4, 1]], eps: float = 1e-05) -> bool
eps_eq(a: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], b: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], eps: float = 1e-05) -> bool
eps_eq(a: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], b: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous], eps: float = 1e-05) -> bool
- cnoid.IRSLCoords.getCoords(arg0: cnoid.Body.Link) cnoid.IRSLCoords.coordinates
- cnoid.IRSLCoords.getOffsetCoords(arg0: cnoid.Body.Link) cnoid.IRSLCoords.coordinates
- cnoid.IRSLCoords.normalizeVector(*args, **kwargs)
Overloaded function.
normalizeVector(arg0: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[3, 1]]
normalizeVector(arg0: numpy.ndarray[numpy.float64[4, 1]]) -> numpy.ndarray[numpy.float64[4, 1]]
- cnoid.IRSLCoords.quaternionToRotation(arg0: numpy.ndarray[numpy.float64[4, 1]]) numpy.ndarray[numpy.float64[3, 3]]
Converting quaternion to rotation matrix
- Parameters:
rot (numpy.array) – 1x4 vector, quaternion(x,y,z,w)
- Returns:
3x3, rotation matrix
- Return type:
numpy.array
- cnoid.IRSLCoords.rotationToQuaternion(arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) numpy.ndarray[numpy.float64[4, 1]]
Converting rotation matrix to quaternion
- Parameters:
rot (numpy.array) – 3x3, rotation matrix
- Returns:
1x4 vector, quaternion(x,y,z,w)
- Return type:
numpy.array
- cnoid.IRSLCoords.setCoords(arg0: cnoid.Body.Link, arg1: cnoid.IRSLCoords.coordinates) None
- cnoid.IRSLCoords.setOffsetCoords(arg0: cnoid.Body.Link, arg1: cnoid.IRSLCoords.coordinates) None