Coordinates モジュール

C++ source code: C++ code

Python Binding (pybind11) : pybind11 code

cnoid.IRSLCoords.coordinates クラス

class cnoid.IRSLCoords.coordinates

ベースクラス: pybind11_object

choreonoidの座標は以下のURLを参照 https://github.com/euslisp/EusLisp/blob/master/doc/jlatex/jmanual.pdf

使用法と説明は 座標系の説明 を参照

property RPY

座標変換の回転要素 ( RPY角度, 3要素の実数ベクトル, ロール[rad], ピッチ[rad], ヨー[rad])

戻り値:

1x3 vector

戻り値の型:

numpy.array

__init__(*args, **kwargs)

オーバーロードされた関数

  1. __init__(self: cnoid.IRSLCoords.coordinates) -> None

  2. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> None

  3. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) -> None

  4. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> None

  5. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[4, 1]]) -> None

  6. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: numpy.ndarray[numpy.float64[3, 1]]) -> None

  7. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: numpy.ndarray[numpy.float64[4, 1]]) -> None

  8. __init__(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[4, 4], flags.c_contiguous]) -> None

property angleAxis

座標変換の回転部分 (回転軸, 4要素の実数ベクトル, ax, ay, az, rotation-angle[rad])

戻り値:

1x4 vector

戻り値の型:

numpy.array

property cnoidPosition

変換行列(Choreonoidで使っている4x4の同時変換行列)

戻り値:

4x4 matrix

戻り値の型:

numpy.array

copy(self: cnoid.IRSLCoords.coordinates) cnoid.IRSLCoords.coordinates

Creating new instance with the same value of this instance

戻り値:

copy of this instance (created new instance)

戻り値の型:

cnoid.IRSLCoords.coordinates

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)

オーバーロードされた関数

  1. get_transformed(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates

  2. 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

戻り値:

identical instance which was called with this method

戻り値の型:

cnoid.IRSLCoords.coordinates

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)

オーバーロードされた関数

  1. locate(self: cnoid.IRSLCoords.coordinates, vector: numpy.ndarray[numpy.float64[3, 1]], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates

  2. 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

パラメータ:
  • 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

戻り値:

Interpolated coordinates

戻り値の型:

cnoid.IRSLCoords.coordinates

move_to(*args, **kwargs)

オーバーロードされた関数

  1. move_to(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates

  2. 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)

オーバーロードされた関数

  1. normalizeVector(arg0: numpy.ndarray[numpy.float64[3, 1], flags.writeable]) -> numpy.ndarray[numpy.float64[3, 1], flags.writeable]

  2. normalizeVector(arg0: numpy.ndarray[numpy.float64[4, 1], flags.writeable]) -> numpy.ndarray[numpy.float64[4, 1], flags.writeable]

static normalized(*args, **kwargs)

オーバーロードされた関数

  1. normalized(arg0: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[3, 1]]

  2. normalized(arg0: numpy.ndarray[numpy.float64[4, 1]]) -> numpy.ndarray[numpy.float64[4, 1]]

orient(*args, **kwargs)

オーバーロードされた関数

  1. 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

  2. orient(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]], arg2: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates

  3. 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)

オーバーロードされた関数

  1. 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

  2. orient_with_matrix(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates

  3. 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

座標変換の並進部分 ( x, y, zの3要素を持つ実数ベクトル)

戻り値:

1x3 vector

戻り値の型:

numpy.array

property quaternion

Rotation part of transformation ( quaternion, real vector with 4 elements, x, y, z, w )

戻り値:

1x4 vector

戻り値の型:

numpy.array

property rot

Rotation part of transformation ( Rotation matrix, 3x3 real matrix)

戻り値:

3x3 matrix

戻り値の型:

numpy.array

rotNormalize(self: cnoid.IRSLCoords.coordinates) None
rotate(*args, **kwargs)

オーバーロードされた関数

  1. 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

  2. rotate(self: cnoid.IRSLCoords.coordinates, arg0: float, arg1: numpy.ndarray[numpy.float64[3, 1]], arg2: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates

  3. 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)

オーバーロードされた関数

  1. 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

  2. rotate_with_matrix(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates

  3. 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)

パラメータ:

position_to_be_set (numpy.array) -- 4x4 homogeneous transformation matrix, using in Choreonoid

setRPY(*args, **kwargs)

オーバーロードされた関数

  1. setRPY(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]]) -> None

  2. 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)

オーバーロードされた関数

  1. transform(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates

  2. 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)

オーバーロードされた関数

  1. transformation(self: cnoid.IRSLCoords.coordinates, coords: cnoid.IRSLCoords.coordinates, wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates

  2. transformation(self: cnoid.IRSLCoords.coordinates, arg0: cnoid.IRSLCoords.coordinates, arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates

translate(*args, **kwargs)

オーバーロードされた関数

  1. translate(self: cnoid.IRSLCoords.coordinates, vector: numpy.ndarray[numpy.float64[3, 1]], wrt: cnoid.IRSLCoords.coordinates.wrt = <wrt.local: 1>) -> cnoid.IRSLCoords.coordinates

  2. translate(self: cnoid.IRSLCoords.coordinates, arg0: numpy.ndarray[numpy.float64[3, 1]], arg1: cnoid.IRSLCoords.coordinates) -> cnoid.IRSLCoords.coordinates

class wrt

ベースクラス: 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)

戻り値:

1x3 vector, x-axis of rotation matrix (1st column vector)

戻り値の型:

numpy.array

property y_axis

Extracting y-axis of rotation matrix (2nd column vector)

戻り値:

1x3 vector, y-axis of rotation matrix (2nd column vector)

戻り値の型:

numpy.array

property z_axis

Extracting z-axis of rotation matrix (3rd column vector)

戻り値:

1x3 vector, z-axis of rotation matrix (3rd column vector)

戻り値の型:

numpy.array

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

パラメータ:

_position (numpy.array) -- 4x4 homogeneous transformation matrix, using in Choreonoid

戻り値:

4x4 matrix, inverse matrix of _position

戻り値の型:

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

パラメータ:

_position (numpy.array) -- 4x4 homogeneous transformation matrix, using in Choreonoid

戻り値:

1x4 vector, quaternion(x,y,z,w), rotation part of _position

戻り値の型:

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

パラメータ:

_position (numpy.array) -- 4x4 homogeneous transformation matrix, using in Choreonoid

戻り値:

3x3 matrix, rotation matrix, rotation part of _position

戻り値の型:

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

パラメータ:

_position (numpy.array) -- 4x4 homogeneous transformation matrix, using in Choreonoid

戻り値:

1x3 vector, translation part of _position

戻り値の型:

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

パラメータ:
  • angle (float) -- rotation angle [radian]

  • axis (numpy.array) -- 1x3 vector, rotation axis

戻り値:

3x3, rotation matrix

戻り値の型:

numpy.array

cnoid.IRSLCoords.angleVector(*args, **kwargs)

オーバーロードされた関数

  1. angleVector(arg0: cnoid.Body.Body) -> numpy.ndarray[numpy.float64[m, 1]]

  2. angleVector(arg0: cnoid.Body.Body, arg1: numpy.ndarray[numpy.float64[m, 1]]) -> None

cnoid.IRSLCoords.cnoidPosition(*args, **kwargs)

オーバーロードされた関数

  1. cnoidPosition(arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous], arg1: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]

  2. cnoidPosition(arg0: numpy.ndarray[numpy.float64[4, 1]], arg1: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]

  3. cnoidPosition(arg0: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]

  4. cnoidPosition(arg0: numpy.ndarray[numpy.float64[3, 3], flags.c_contiguous]) -> numpy.ndarray[numpy.float64[4, 4]]

  5. cnoidPosition(arg0: numpy.ndarray[numpy.float64[4, 1]]) -> numpy.ndarray[numpy.float64[4, 4]]

cnoid.IRSLCoords.eps_eq(*args, **kwargs)

オーバーロードされた関数

  1. eps_eq(a: float, b: float, eps: float = 1e-05) -> bool

  2. eps_eq(a: numpy.ndarray[numpy.float64[3, 1]], b: numpy.ndarray[numpy.float64[3, 1]], eps: float = 1e-05) -> bool

  3. eps_eq(a: numpy.ndarray[numpy.float64[4, 1]], b: numpy.ndarray[numpy.float64[4, 1]], eps: float = 1e-05) -> bool

  4. 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

  5. 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)

オーバーロードされた関数

  1. normalizeVector(arg0: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[3, 1]]

  2. 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

パラメータ:

rot (numpy.array) -- 1x4 vector, quaternion(x,y,z,w)

戻り値:

3x3, rotation matrix

戻り値の型:

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

パラメータ:

rot (numpy.array) -- 3x3, rotation matrix

戻り値:

1x4 vector, quaternion(x,y,z,w)

戻り値の型:

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