transform

transform is a ROS node that subscribes to a topic, or a topic field, and publishes incoming data to another topic, after applying a given Python expression. It's mainly useful for simple message transformation, like computing the norm of a vector or quaternion, or even converting a quaternion to Euler angles. It can work with any message type.

transform is part of topic_tools.

transform

transform <input> <output_topic> <output_type> [<expression>] [--import <module> [<module> ...]]

  • Transform messages from <input> topic (or topic field) using a Python <expression> and publishes them in <output_topic> topic (of type <output_type>).

    • input: Incoming topic (or topic field) to subscribe to.

    • output_topic: Output topic to publish on.

    • output_type: Message type of output_topic.

    • expression: Python expression that transform the input messages, which are given in the variable m. The default expression is m, which results in forwarding input (which can be a topic field) into output_topic.

    • --import <module>: List of Python modules to import and use in the expression. For commodity numpy module is imported by default.

    e.g. compute the norm of the orientation quaternion given by a IMU:
    rosrun topic_tools transform /imu/orientation /norm std_msgs/Float64 'numpy.linalg.norm([m.x, m.y, m.z, m.w])'
    e.g. convert an orientation quaternion to Euler angles:
    rosrun topic_tools transform /imu/orientation /euler geometry_msgs/Vector3 'tf.transformations.euler_from_quaternion([m.x, m.y, m.z, m.w])' --import tf

    e.g. change the sign of a scalar message (note that because of the - sign, we need to escape the args with --):

    rosrun topic_tools transform /signal_level /positive_signal_level std_msgs/Float64 -- '-m.data'

    e.g. change the frame_id of a PoseStamped message:

    rosrun topic_tools transform /in_topic /out_topic geometry_msgs/PoseStamped 'geometry_msgs.msg.PoseStamped(header=std_msgs.msg.Header(seq=m.header.seq,stamp=m.header.stamp,frame_id="my_new_frame"),pose=m.pose)' --import geometry_msgs std_msgs

Wiki: topic_tools/transform (last edited 2019-10-17 21:39:42 by NicolasVaras)