Functions | |
def | change_pose_stamped_frame |
change the frame of a PoseStamped | |
def | change_vector3_stamped_frame |
change the frame of a Vector3Stamped | |
def | create_point_stamped |
create a PointStamped message | |
def | create_pose_stamped |
create a PoseStamped message | |
def | create_vector3_stamped |
create a Vector3Stamped message | |
tf::Matrix3x3 | createMatrix (const tf::Vector3 &X, const tf::Vector3 &Y, const tf::Vector3 &Z) |
def | get_transform |
get the 4x4 transformation matrix from frame1 to frame2 from TF | |
def | get_xyz |
get x, y, and z fields in the form of a list | |
def | get_xyzw |
get x, y, z, and w fields in the form of a list | |
def | lists_to_pose_stamped |
convert pos and rot lists (relative to in_frame) to a PoseStamped (relative to to_frame) | |
def | mat_to_point_cloud |
convert a 4xn scipy matrix (x y z 1) to a PointCloud | |
def | mat_to_pos_and_quat |
convert a 4x4 scipy matrix to position and quaternion lists | |
def | mat_to_pose |
def | mat_to_transform |
def | point_cloud_to_mat |
convert a PointCloud or PointCloud2 to a 4xn scipy matrix (x y z 1) | |
def | point_stamped_to_list |
convert a pointStamped to a pos list in a desired frame | |
def | pose_stamped_to_lists |
convert a PoseStamped to pos and rot (quaternion) lists in a desired frame | |
def | pose_to_mat |
def | pplist |
pretty-print list to string | |
def | ppmat |
pretty-print numpy matrix to string | |
def | quaternion_stamped_to_list |
convert a QuaternionStamped to a quat list in a desired frame | |
def | rethrow_tf_exception |
catch a tf exception, print a message, rethrowing it first to preserve tracebacks | |
def | set_xyz |
set x, y, and z fields with a list | |
def | set_xyzw |
set x, y, z, and w fields with a list | |
void | setMatrix (tf::Matrix3x3 &mat, const tf::Vector3 &X, const tf::Vector3 &Y, const tf::Vector3 &Z) |
def | stamp_msg |
stamp a message by giving it a header with a timestamp of now | |
def | stamp_pose |
make a PoseStamped out of a Pose | |
def | stamp_vector3 |
make a Vector3Stamped out of a Vector3 | |
def | transform_point_cloud |
transform a PointCloud or PointCloud2 to be a 4xn scipy matrix (x y z 1) in a new frame | |
def | transform_pose_stamped |
transform a poseStamped by a 4x4 scipy matrix | |
def | transform_to_mat |
def | vector3_stamped_to_list |
convert a Vector3Stamped to a rot list in a desired frame |
def object_manipulator.convert_functions.change_pose_stamped_frame | ( | tf_listener, | |
pose, | |||
frame | |||
) |
change the frame of a PoseStamped
Definition at line 324 of file convert_functions.py.
def object_manipulator.convert_functions.change_vector3_stamped_frame | ( | tf_listener, | |
vector3_stamped, | |||
frame | |||
) |
change the frame of a Vector3Stamped
Definition at line 307 of file convert_functions.py.
def object_manipulator.convert_functions.create_point_stamped | ( | point, | |
frame_id = 'base_link' |
|||
) |
create a PointStamped message
Definition at line 382 of file convert_functions.py.
def object_manipulator.convert_functions.create_pose_stamped | ( | pose, | |
frame_id = 'base_link' |
|||
) |
create a PoseStamped message
Definition at line 372 of file convert_functions.py.
def object_manipulator.convert_functions.create_vector3_stamped | ( | vector, | |
frame_id = 'base_link' |
|||
) |
create a Vector3Stamped message
Definition at line 392 of file convert_functions.py.
tf::Matrix3x3 object_manipulator::convert_functions::createMatrix | ( | const tf::Vector3 & | X, |
const tf::Vector3 & | Y, | ||
const tf::Vector3 & | Z | ||
) | [inline] |
Definition at line 14 of file convert_functions.h.
def object_manipulator.convert_functions.get_transform | ( | tf_listener, | |
frame1, | |||
frame2 | |||
) |
get the 4x4 transformation matrix from frame1 to frame2 from TF
Definition at line 90 of file convert_functions.py.
def object_manipulator.convert_functions.get_xyz | ( | msg | ) |
get x, y, and z fields in the form of a list
Definition at line 216 of file convert_functions.py.
get x, y, z, and w fields in the form of a list
Definition at line 221 of file convert_functions.py.
def object_manipulator.convert_functions.lists_to_pose_stamped | ( | tf_listener, | |
pos, | |||
rot, | |||
in_frame, | |||
to_frame | |||
) |
convert pos and rot lists (relative to in_frame) to a PoseStamped (relative to to_frame)
Definition at line 356 of file convert_functions.py.
def object_manipulator.convert_functions.mat_to_point_cloud | ( | mat, | |
frame_id | |||
) |
convert a 4xn scipy matrix (x y z 1) to a PointCloud
Definition at line 68 of file convert_functions.py.
convert a 4x4 scipy matrix to position and quaternion lists
Definition at line 174 of file convert_functions.py.
def object_manipulator.convert_functions.mat_to_pose | ( | mat, | |
transform = None |
|||
) |
Convert a homogeneous matrix to a Pose message, optionally premultiply by a transform. Args: mat (numpy.ndarray): 4x4 array (or matrix) representing a homogenous transform. transform (numpy.ndarray): Optional 4x4 array representing additional transform Returns: pose (geometry_msgs.msg.Pose): Pose message representing transform.
Definition at line 118 of file convert_functions.py.
def object_manipulator.convert_functions.mat_to_transform | ( | mat, | |
transform = None |
|||
) |
Convert a 4x5 scipy matrix to a transform message. Args: mat (numpy.matrix): 4x4 numpy matrix transform (numpy.ndarray): Optional 4x4 array representing additional transform Returns: transform (geometry_msgs.msg.Transform): Transform rospy message class.
Definition at line 156 of file convert_functions.py.
def object_manipulator.convert_functions.point_cloud_to_mat | ( | point_cloud | ) |
convert a PointCloud or PointCloud2 to a 4xn scipy matrix (x y z 1)
Definition at line 55 of file convert_functions.py.
def object_manipulator.convert_functions.point_stamped_to_list | ( | tf_listener, | |
point, | |||
frame | |||
) |
convert a pointStamped to a pos list in a desired frame
Definition at line 247 of file convert_functions.py.
def object_manipulator.convert_functions.pose_stamped_to_lists | ( | tf_listener, | |
pose, | |||
frame | |||
) |
convert a PoseStamped to pos and rot (quaternion) lists in a desired frame
Definition at line 341 of file convert_functions.py.
def object_manipulator.convert_functions.pose_to_mat | ( | pose | ) |
Convert a pose message to a 4x4 numpy matrix. Args: pose (geometry_msgs.msg.Pose): Pose rospy message class. Returns: mat (numpy.matrix): 4x4 numpy matrix
Definition at line 102 of file convert_functions.py.
def object_manipulator.convert_functions.pplist | ( | list | ) |
pretty-print list to string
Definition at line 402 of file convert_functions.py.
def object_manipulator.convert_functions.ppmat | ( | mat | ) |
pretty-print numpy matrix to string
Definition at line 407 of file convert_functions.py.
def object_manipulator.convert_functions.quaternion_stamped_to_list | ( | tf_listener, | |
quaternion, | |||
frame | |||
) |
convert a QuaternionStamped to a quat list in a desired frame
Definition at line 287 of file convert_functions.py.
def object_manipulator.convert_functions.rethrow_tf_exception | ( | exception, | |
msg | |||
) |
catch a tf exception, print a message, rethrowing it first to preserve tracebacks
Definition at line 417 of file convert_functions.py.
def object_manipulator.convert_functions.set_xyz | ( | msg, | |
xyz | |||
) |
set x, y, and z fields with a list
Definition at line 203 of file convert_functions.py.
def object_manipulator.convert_functions.set_xyzw | ( | msg, | |
xyzw | |||
) |
set x, y, z, and w fields with a list
Definition at line 210 of file convert_functions.py.
void object_manipulator::convert_functions::setMatrix | ( | tf::Matrix3x3 & | mat, |
const tf::Vector3 & | X, | ||
const tf::Vector3 & | Y, | ||
const tf::Vector3 & | Z | ||
) | [inline] |
Definition at line 22 of file convert_functions.h.
def object_manipulator.convert_functions.stamp_msg | ( | msg, | |
frame_id | |||
) |
stamp a message by giving it a header with a timestamp of now
Definition at line 181 of file convert_functions.py.
def object_manipulator.convert_functions.stamp_pose | ( | pose, | |
frame_id | |||
) |
make a PoseStamped out of a Pose
Definition at line 187 of file convert_functions.py.
def object_manipulator.convert_functions.stamp_vector3 | ( | vector3, | |
frame_id | |||
) |
make a Vector3Stamped out of a Vector3
Definition at line 195 of file convert_functions.py.
def object_manipulator.convert_functions.transform_point_cloud | ( | tf_listener, | |
point_cloud, | |||
frame | |||
) |
transform a PointCloud or PointCloud2 to be a 4xn scipy matrix (x y z 1) in a new frame
Definition at line 80 of file convert_functions.py.
def object_manipulator.convert_functions.transform_pose_stamped | ( | pose_stamped, | |
transform, | |||
pre_or_post = "post" |
|||
) |
transform a poseStamped by a 4x4 scipy matrix
Definition at line 226 of file convert_functions.py.
def object_manipulator.convert_functions.transform_to_mat | ( | transform | ) |
Convert a tf transform to a 4x4 scipy mat. Args: transform (geometry_msgs.msg.Transform): Transform rospy message class. Returns: mat (numpy.matrix): 4x4 numpy matrix
Definition at line 141 of file convert_functions.py.
def object_manipulator.convert_functions.vector3_stamped_to_list | ( | tf_listener, | |
vector3, | |||
frame | |||
) |
convert a Vector3Stamped to a rot list in a desired frame
Definition at line 267 of file convert_functions.py.