pycram.datastructures.pose

Module Contents

Classes

Pose

Pose representation for PyCRAM, this class extends the PoseStamped ROS message from geometry_msgs. Thus making it

Transform

Represents a Transformation from one TF frame to another in PyCRAM. Like with Poses this class inherits from the ROS

Functions

get_normalized_quaternion(→ geometry_msgs.msg.Quaternion)

Normalizes a given quaternion such that it has a magnitude of 1.

pycram.datastructures.pose.get_normalized_quaternion(quaternion: numpy.ndarray) geometry_msgs.msg.Quaternion

Normalizes a given quaternion such that it has a magnitude of 1.

Parameters:

quaternion – The quaternion that should be normalized

Returns:

The normalized quaternion

class pycram.datastructures.pose.Pose(position: typing_extensions.Optional[typing_extensions.List[float]] = None, orientation: typing_extensions.Optional[typing_extensions.List[float]] = None, frame: str = 'map', time: rospy.Time = None)

Bases: geometry_msgs.msg.PoseStamped

Pose representation for PyCRAM, this class extends the PoseStamped ROS message from geometry_msgs. Thus making it compatible with every ROS service and message expecting a PoseStamped message.

Naming convention for Poses:

Pose: Instances of this class, representing a cartesian position and a quaternion for orientation

Position: Only the cartesian position in xyz

Orientation: Only the quaternion as xyzw

Poses can be initialized by a position and orientation given as lists, this is optional. By default, Poses are initialized with the position being [0, 0, 0], the orientation being [0, 0, 0, 1] and the frame being ‘map’.

Parameters:
  • position – An optional position of this Pose

  • orientation – An optional orientation of this Pose

  • frame – An optional frame in which this pose is

  • time – The time at which this Pose is valid, as ROS time

property frame: str

Property for the frame_id such that it is easier accessible. Instead of Pose.header.frame_id it is Pose.frame

Returns:

The TF frame of this Pose

property position: geometry_msgs.msg.Point

Property that points to the position of this pose

property orientation: geometry_msgs.msg.Quaternion

Property that points to the orientation of this pose

static from_pose_stamped(pose_stamped: geometry_msgs.msg.PoseStamped) Pose

Converts a geometry_msgs/PoseStamped message to a Pose object. Should be used for compatability with ROS.

Parameters:

pose_stamped – The pose stamped message which should be converted

Returns:

A Pose object with the same information as the given message

to_list() typing_extensions.List[typing_extensions.List[float]]

Returns the position and orientation of this pose as a list containing two list.

Returns:

The position and orientation as lists

to_transform(child_frame: str) Transform

Converts this pose to a Transform from the TF frame of the pose to the given child_frame

Parameters:

child_frame – Child frame id to which the Transform points

Returns:

A new Transform

copy() Pose

Creates a deep copy of this pose.

Returns:

A copy of this pose

position_as_list() typing_extensions.List[float]

Returns only the position as a list of xyz.

Returns:

The position as a list

orientation_as_list() typing_extensions.List[float]

Returns only the orientation as a list of a quaternion

Returns:

The orientation as a quaternion with xyzw

dist(other_pose: Pose) float

Calculates the euclidian distance between this Pose and the given one. For distance calculation only the position is used.

Parameters:

other_pose – Pose to which the distance should be calculated

Returns:

The distance between the Poses

__eq__(other: Pose) bool

Overloads the ‘==’ operator to check for equality between two Poses. Only compares the position, orientation and frame. Timestamps of Poses are not takes into account.

Parameters:

other – Other pose which should be compared

Returns:

True if both Poses have the same position, orientation and frame. False otherwise

set_position(new_position: typing_extensions.List[float]) None

Sets the position of this Pose to the given position. Position has to be given as a vector in cartesian space.

Parameters:

new_position – New position as a vector of xyz

set_orientation(new_orientation: typing_extensions.List[float]) None

Sets the orientation to the given quaternion. The new orientation has to be given as a quaternion.

Parameters:

new_orientation – New orientation as a quaternion with xyzw

to_sql() pycram.orm.base.Pose
insert(session: sqlalchemy.orm.Session) pycram.orm.base.Pose
class pycram.datastructures.pose.Transform(translation: typing_extensions.Optional[typing_extensions.List[float]] = None, rotation: typing_extensions.Optional[typing_extensions.List[float]] = None, frame: typing_extensions.Optional[str] = 'map', child_frame: typing_extensions.Optional[str] = '', time: rospy.Time = None)

Bases: geometry_msgs.msg.TransformStamped

Represents a Transformation from one TF frame to another in PyCRAM. Like with Poses this class inherits from the ROS message TransformStamped form geometry_msgs and is therefore compatible with ROS services and messages that require a TransformStamped message.

Naming Convention for Transforms:

Transform: Instances of this class, representing a translation and rotation from frame_id to child_frame_id

Translation: A vector representing the conversion in cartesian space

Rotation: A quaternion representing the conversion of rotation between both frames

Transforms take a translation, rotation, frame and child_frame as optional arguments. If nothing is given the Transform will be initialized with [0, 0, 0] for translation, [0, 0, 0, 1] for rotation, ‘map’ for frame and an empty string for child_frame

Parameters:
  • translation – Optional translation from frame to child_frame in cartesian space

  • rotation – Optional rotation from frame to child frame given as quaternion

  • frame – Origin TF frame of this Transform

  • child_frame – Target frame for this Transform

  • time – The time at which this Transform is valid, as ROS time

property frame: str

Property for the frame_id such that it is easier accessible. Instead of Pose.header.frame_id it is Pose.frame

Returns:

The TF frame of this Pose

property translation: None

Property that points to the translation of this Transform

property rotation: None

Property that points to the rotation of this Transform

classmethod from_pose_and_child_frame(pose: Pose, child_frame_name: str) Transform
static from_transform_stamped(transform_stamped: geometry_msgs.msg.TransformStamped) Transform

Creates a Transform instance from a geometry_msgs/TransformStamped message. Should be used for compatibility with ROS.

Parameters:

transform_stamped – The transform stamped message that should be converted

Returns:

An Transform with the same information as the transform stamped message

copy() Transform

Creates a deep copy of this pose.

Returns:

A copy of this pose

translation_as_list() typing_extensions.List[float]

Returns the translation of this Transform as a list.

Returns:

The translation as a list of xyz

rotation_as_list() typing_extensions.List[float]

Returns the rotation of this Transform as a list representing a quaternion.

Returns:

The rotation of this Transform as a list with xyzw

to_pose() Pose

Converts this Transform to a Pose, in this process the child_frame_id is lost.

Returns:

A new pose with same translation as position and rotation as orientation

invert() Transform

Inverts this Transform, the new Transform points from the child_frame_id to the frame_id

Returns:

A new inverted Transform

__mul__(other: Transform) typing_extensions.Union[Transform, None]

Multiplies this Transform with another one. The resulting Transform points from the frame_id of this Transform to the child_frame_id of the other Transform.

Parameters:

other – The Transform which should be multiplied with this one.

Returns:

The resulting Transform from the multiplication

inverse_times(other_transform: Transform) Transform

Like a ‘minus’ for Transforms, subtracts the other_transform from this one.

Parameters:

other_transform – Transform which should be subtracted from this one

Returns:

The resulting Transform form the calculation

__eq__(other: Transform) bool

Overloads the ‘==’ operator to check for equality between two Transforms. Only compares the translation, rotation, frame and child frame. Timestamps of Poses are not takes into account.

Parameters:

other – Other pose which should be compared

Returns:

True if both Transforms have the same translation, rotation, frame and child frame. False otherwise

set_translation(new_translation: typing_extensions.List[float]) None

Sets the translation of this Transform to the newly given one. Translation has to be a vector in cartesian space

Parameters:

new_translation – The new translation as a vector with xyz.

set_rotation(new_rotation: typing_extensions.List[float]) None

Sets the rotation of this Transform to the newly given one. Rotation has to be a quaternion.

Parameters:

new_rotation – The new rotation as a quaternion with xyzw