Special Euclidean Groups¶
- class py123d.geometry.PoseSE2[source]¶
Class to represents a 2D pose as SE2 (x, y, yaw).
Examples
>>> from py123d.geometry import PoseSE2 >>> pose = PoseSE2(x=1.0, y=2.0, yaw=0.5) >>> print(pose.x, pose.y, pose.yaw) 1.0 2.0 0.5 >>> print(pose.rotation_matrix) [[ 0.87758256 -0.47942554] [ 0.47942554 0.87758256]]
Public Data Attributes:
xThe x-coordinate of the pose.
yThe y-coordinate of the pose.
yawThe yaw angle of the pose.
arrayPose as numpy array of shape (3,), indexed by
PoseSE2Index.pose_se2Returns self to match interface of other pose classes.
point_2dThe
Point2Dof the pose, i.e. the translation part.vector_2dThe
Vector2Dtranslation component of the SE2 pose.rotation_matrixThe 2x2 rotation matrix representation of the pose.
transformation_matrixThe 3x3 transformation matrix representation of the pose.
shapely_pointThe Shapely point representation of the pose.
Inherited from
ArrayMixinarrayThe array representation of the geometric entity.
shapeReturn the shape of the array.
Public Methods:
from_array(array[, copy])Constructs a PoseSE2 from a numpy array.
from_transformation_matrix(transformation_matrix)Constructs a PoseSE2 from a 3x3 transformation matrix.
from_R_t(rotation, translation)Constructs a
PoseSE2from a rotation and a translation.identity()Constructs an identity PoseSE2.
Inherited from
ArrayMixinfrom_array(array[, copy])Create an instance from a NumPy array.
from_list(values)Create an instance from a list of values.
tolist()Convert the array to a Python list.
to_list()Convert the array to a Python list.
copy()Return a copy of the object with a copied array.
- classmethod from_transformation_matrix(transformation_matrix)[source]¶
Constructs a PoseSE2 from a 3x3 transformation matrix.
- classmethod from_R_t(rotation, translation)[source]¶
Constructs a
PoseSE2from a rotation and a translation.- Parameters:
rotation (
Union[ndarray[tuple[Any,...],dtype[float64]],float]) – Any implemented representation of a SO2 rotation: - (2, 2) rotation matrix as numpy array, - (1,) numpy array representing the yaw angle in radians.translation (
Union[ndarray[tuple[Any,...],dtype[float64]],Point2D,Vector2D]) – The translation component: - (2,) numpy array indexed byVector2DIndex, -Vector2Dinstance, -Point2Dis also accepted for convenience.
- Return type:
- Returns:
A
PoseSE2instance.
- classmethod identity()[source]¶
Constructs an identity PoseSE2.
- Return type:
- Returns:
An identity PoseSE2 instance.
- property array: ndarray[tuple[Any, ...], dtype[float64]]¶
Pose as numpy array of shape (3,), indexed by
PoseSE2Index.
- property rotation_matrix: ndarray[tuple[Any, ...], dtype[float64]]¶
The 2x2 rotation matrix representation of the pose.
- property transformation_matrix: ndarray[tuple[Any, ...], dtype[float64]]¶
The 3x3 transformation matrix representation of the pose.
- property shapely_point: Point¶
The Shapely point representation of the pose.
- copy()¶
Return a copy of the object with a copied array.
- Return type:
ArrayMixin
- class py123d.geometry.PoseSE3[source]¶
Class representing a pose in SE3 space.
Examples
>>> from py123d.geometry import PoseSE3 >>> pose = PoseSE3(x=1.0, y=2.0, z=3.0, qw=1.0, qx=0.0, qy=0.0, qz=0.0) >>> pose.point_3d Point3D(array=[1. 2. 3.]) >>> pose.transformation_matrix array([[1., 0., 0., 1.], [0., 1., 0., 2.], [0., 0., 1., 3.], [0., 0., 0., 1.]]) >>> PoseSE3.from_transformation_matrix(pose.transformation_matrix) == pose True >>> print(pose.yaw, pose.pitch, pose.roll) 0.0 0.0 0.0
Public Data Attributes:
xThe x-coordinate of the pose.
yThe y-coordinate of the pose.
zThe z-coordinate of the pose.
qwThe w-coordinate of the quaternion, representing the scalar part.
qxThe x-coordinate of the quaternion, representing the first component of the vector part.
qyThe y-coordinate of the quaternion, representing the second component of the vector part.
qzThe z-coordinate of the quaternion, representing the third component of the vector part.
arrayThe numpy array representation of the pose with shape (7,), indexed by
PoseSE3Indexpose_se3The
PoseSE3itself.pose_se2The
PoseSE2representation of the SE3 pose.point_3dThe
Point3Drepresentation of the SE3 pose, i.e. the translation part.point_2dThe
Point2Drepresentation of the SE3 pose, i.e. the translation part.vector_3dThe
Vector3Dtranslation component of the SE3 pose.vector_2dThe
Vector2D2D translation component (x, y) of the SE3 pose.shapely_pointThe Shapely point representation, of the translation part of the SE3 pose.
quaternionThe
Quaternionrepresentation of the state's orientation.euler_anglesThe
EulerAnglesrepresentation of the state's orientation.rollThe roll (x-axis rotation) angle in radians.
pitchThe pitch (y-axis rotation) angle in radians.
yawThe yaw (z-axis rotation) angle in radians.
rotation_matrixReturns the 3x3 rotation matrix representation of the state's orientation.
transformation_matrixReturns the 4x4 transformation matrix representation of the state.
inverseReturns the inverse of the SE3 pose.
Inherited from
ArrayMixinarrayThe array representation of the geometric entity.
shapeReturn the shape of the array.
Public Methods:
from_array(array[, copy])Constructs a
PoseSE3from a numpy array of shape (7,), indexed byPoseSE3Index.from_transformation_matrix(transformation_matrix)Constructs a
PoseSE3from a 4x4 transformation matrix.from_R_t(rotation, translation)Constructs a
PoseSE3from arbitrary rotation and translation representations.identity()Constructs an identity
PoseSE3.Inherited from
ArrayMixinfrom_array(array[, copy])Create an instance from a NumPy array.
from_list(values)Create an instance from a list of values.
tolist()Convert the array to a Python list.
to_list()Convert the array to a Python list.
copy()Return a copy of the object with a copied array.
- __init__(x, y, z, qw, qx, qy, qz)[source]¶
Initialize
PoseSE3with x, y, z, qw, qx, qy, qz coordinates.- Parameters:
x (
float) – The x-coordinate.y (
float) – The y-coordinate.z (
float) – The z-coordinate.qw (
float) – The w-coordinate of the quaternion, representing the scalar part.qx (
float) – The x-coordinate of the quaternion, representing the first component of the vector part.qy (
float) – The y-coordinate of the quaternion, representing the second component of the vector part.qz (
float) – The z-coordinate of the quaternion, representing the third component of the vector part.
- classmethod from_array(array, copy=True)[source]¶
Constructs a
PoseSE3from a numpy array of shape (7,), indexed byPoseSE3Index.
- classmethod from_transformation_matrix(transformation_matrix)[source]¶
Constructs a
PoseSE3from a 4x4 transformation matrix.
- classmethod from_R_t(rotation, translation)[source]¶
Constructs a
PoseSE3from arbitrary rotation and translation representations.- Parameters:
rotation (
Union[ndarray[tuple[Any,...],dtype[float64]],Quaternion,EulerAngles]) – Any implemented representation of a SO3 rotation: - (3, 3) rotation matrix as numpy array, - (4,) quaternion array indexed byQuaternionIndex, - (3,) euler angles indexed byEulerAnglesIndex, -Quaternioninstance, -EulerAnglesinstance.translation (
Union[ndarray[tuple[Any,...],dtype[float64]],Point3D,Vector3D]) – The translation component:, - (3,) numpy array indexed byVector3DIndex, -Vector3Dinstance, -Point3Dis also accepted for convenience. :return: APoseSE3instance.
- Return type:
- property qx: float¶
The x-coordinate of the quaternion, representing the first component of the vector part.
- property qy: float¶
The y-coordinate of the quaternion, representing the second component of the vector part.
- property qz: float¶
The z-coordinate of the quaternion, representing the third component of the vector part.
- property array: ndarray[tuple[Any, ...], dtype[float64]]¶
The numpy array representation of the pose with shape (7,), indexed by
PoseSE3Index
- property shapely_point: Point¶
The Shapely point representation, of the translation part of the SE3 pose.
- property quaternion: Quaternion¶
The
Quaternionrepresentation of the state’s orientation.
- property euler_angles: EulerAngles¶
The
EulerAnglesrepresentation of the state’s orientation.
- property rotation_matrix: ndarray[tuple[Any, ...], dtype[float64]]¶
Returns the 3x3 rotation matrix representation of the state’s orientation.
- property transformation_matrix: ndarray[tuple[Any, ...], dtype[float64]]¶
Returns the 4x4 transformation matrix representation of the state.
- copy()¶
Return a copy of the object with a copied array.
- Return type:
ArrayMixin