Transforms in ROS
-
-
Coordinate transformations
- First we need to assign coordinate systems, or frames, to the components of our system
- Then we define transforms to tell us the translations and rotations required to go from one frame to another
- Each frame is defined by only one transform from a parent frame, creating a tree structure
Broadcasting Single Frames
- Use a
static_transform_publisher
to broadcast a static transform from parent_frame to child_frame
ros2 run tf2_ros static_transform_publisher x y z yaw pitch roll parent_frame child_frame
- Transform from world frame to robot1 frame is 2m in x, 1m in y, 45 degrees yaw rotation
ros2 run tf2_ros static_transform_publisher 2 1 0 0.785 0 0 world robot_1
[INFO] [1736063840.417270047] [static_transform_publisher_zTFbM6lzvgTIEWJz]: Spinning until stopped - publishing transform
translation: ('2.000000', '1.000000', '0.000000')
rotation: ('0.000000', '0.000000', '0.382499', '0.923956')
from 'world' to 'robot_1'
- Transform from robot1 frame to robot2 frame is 1m in x direction
ros2 run tf2_ros static_transform_publisher 1 0 0 0 0 0 robot_1 robot_2
- View the frames and tranforms in RViz
rviz2
- Rerun the first command with larger rotation of 90 deg (1.57 rad)
- robot_2 will move to since it’s a child of robot_1 (its frame is defined relative to robot_1)
ros2 run tf2_ros static_transform_publisher 2 1 0 1.57 0 0 world robot_1
Broadcasting a Moving Robot
- In a URDF file, each joint can be defined as
- fixed:
robot_state_publisher
can just publish a static transform - movable:
robot_state_publisher
must publish a dynamic transform using external values (angles, linear distances, etc) in order to calculate what the transform needs to be at each point in time- It gets these values (position, velocity, or effort of a joint) from
/joint_states
- It gets these values (position, velocity, or effort of a joint) from
- fixed:
- JointState messages will normally come from (real or simulated) actuator feedback sensors on the robot (encoders, potentiometers, etc)
- We can fake this with
joint_state_publisher_gui
- We can fake this with
example_robot.urdf.xacro
<?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot"> <material name="grey"> <color rgba="0.2 0.2 0.2 1"/> </material> <material name="white"> <color rgba="1 1 1 1"/> </material> <material name="orange"> <color rgba="1 0.3 0.1 1"/> </material> <material name="blue"> <color rgba="0 0 1 1"/> </material> <link name="world"></link> <joint name="world_to_base" type="fixed"> <parent link="world" /> <child link="base" /> <origin rpy="1.57 0 0" xyz="0 0 0" /> </joint> <link name="base"> <visual> <origin xyz="2 0 0" rpy="0 0 0"/> <geometry> <box size="5 0.1 3" /> </geometry> <material name="grey" /> </visual> </link> <joint name="base_to_l3" type="revolute"> <parent link="base" /> <child link="l3" /> <origin rpy="0 0 0" xyz="0 0.25 0" /> <axis rpy="0 0 0" xyz="0 0 1" /> <limit effort="0.1" lower="-3.1" upper="3.1" velocity="0.2"/> </joint> <link name="l3"> <visual> <origin xyz="0.75 0 0" rpy="0 1.57 0"/> <geometry> <cylinder length="1.5" radius="0.04" /> </geometry> <material name="orange" /> </visual> </link> <joint name="l3_to_l2" type="revolute"> <parent link="l3" /> <child link="l2" /> <!-- <origin xyz="1 0 0" /> --> <origin rpy="0 0 0" xyz="1.5 0 0" /> <axis rpy="0 0 0" xyz="0 0 1" /> <limit effort="0.1" lower="-3.1" upper="3.1" velocity="0.2"/> </joint> <link name="l2"> <visual> <origin xyz="0.75 0 0" rpy="0 1.57 0"/> <geometry> <cylinder length="1.5" radius="0.04" /> </geometry> <material name="orange" /> </visual> </link> <joint name="l2_to_l1" type="revolute"> <parent link="l2" /> <child link="l1" /> <origin rpy="0 0 0" xyz="1.5 0 0" /> <axis rpy="0 0 0" xyz="0 0 1" /> <limit effort="0.1" lower="-3.1" upper="3.1" velocity="0.2"/> </joint> <link name="l1"> <visual> <origin xyz="0.5 0 0" rpy="0 1.57 0"/> <geometry> <cylinder length="1" radius="0.04" /> </geometry> <material name="orange" /> </visual> </link> <joint name="l1_to_grip" type="revolute"> <parent link="l1" /> <child link="grip" /> <origin rpy="0 0 0" xyz="1 0 0" /> <axis rpy="0 0 0" xyz="0 0 1" /> <limit effort="0.1" lower="-3.1" upper="3.1" velocity="0.2"/> </joint> <link name="grip"> <visual> <origin xyz="0.25 0 0"/> <geometry> <box size="0.5 0.5 0.05" /> </geometry> <material name="white" /> </visual> </link> <joint name="world_to_camera" type="fixed"> <parent link="world" /> <child link="camera" /> <origin rpy="-2 0 2.5" xyz="4 1 2" /> </joint> <link name="camera"> <visual> <origin xyz="0 0 -0.2"/> <geometry> <box size="0.2 0.2 0.4" /> </geometry> <material name="blue" /> </visual> </link> </robot>
- Install packages if needed
sudo apt install ros-humble-xacro ros-humble-joint-state-publisher-gui
- Run the
robot_state_publisher
passing in the URDF file preprocessed byxacro
to therobot_description
parameter
ros2 run robot_state_publisher robot_state_publisher --ros-args -p robot_description:="$(xacro example_robot.urdf.xacro)"
- Publish the joint states
ros2 run joint_state_publisher_gui joint_state_publisher_gui
- Run RViz
rviz2 -d articubot-tf.rviz
- Add RobotModel and select
/robot_description
in RViz to view the 3D model of the robot
- Use
view_frames
fromtf2_tools
package to visualize the transform tree along with information about how it is being broadcast- This is easier than using
ros2 topic echo
to listen to/tf
and/tf_static
directly
- This is easier than using
ros2 run tf2_tools view_frames
[INFO] [1736068659.429880586] [view_frames]: Listening to tf data for 5.0 seconds...
[INFO] [1736068664.497444195] [view_frames]: Generating graph in frames.pdf file...
[INFO] [1736068664.502413522] [view_frames]: Result:tf2_msgs.srv.FrameGraph_Response(frame_yaml="base: \n parent: 'world'\n broadcaster: 'default_authority'\n rate: 10000.000\n most_recent_transform: 0.000000\n oldest_transform: 0.000000\n buffer_length: 0.000\ncamera: \n parent: 'world'\n broadcaster: 'default_authority'\n rate: 10000.000\n most_recent_transform: 0.000000\n oldest_transform: 0.000000\n buffer_length: 0.000\nl3: \n parent: 'base'\n broadcaster: 'default_authority'\n rate: 10.198\n most_recent_transform: 1736068664.496014\n oldest_transform: 1736068659.494837\n buffer_length: 5.001\ngrip: \n parent: 'l1'\n broadcaster: 'default_authority'\n rate: 10.198\n most_recent_transform: 1736068664.496014\n oldest_transform: 1736068659.494837\n buffer_length: 5.001\nl1: \n parent: 'l2'\n broadcaster: 'default_authority'\n rate: 10.198\n most_recent_transform: 1736068664.496014\n oldest_transform: 1736068659.494837\n buffer_length: 5.001\nl2: \n parent: 'l3'\n broadcaster: 'default_authority'\n rate: 10.198\n most_recent_transform: 1736068664.496014\n oldest_transform: 1736068659.494837\n buffer_length: 5.001\n")