Juan Miguel Jimeno edited this page Sep 2, 2018 · 7 revisions

TF is ROS's way of determining the robot's location and relationships between coordinate frames. For more comprehensive explanation about TF, click here.

5.1 The robot's transforms

5.1.1 odom -> base_footprint

This transform is the relationship between the robot's current pose from its origin. This transform is published by robot_localization package (EKF).

5.1.2 base_footprint -> base_link

This transform is the static relationship between the center of the robot base and the floor.

5.1.3 base_link -> laser

This transform is the static relationship between the lidar and the robot's base. Basically, this tells ROS the lidar's offset in x, y and z axis from the center of the robot's base. Imagine a lidar (mounted behind a 10cm long base) detects an obstacle 10 cm in front of the robot. The actual distance of the robot from the obstacle would be 5 cm since there's a 5 cm offset from the center of the base to the rear. Without this transform, the robot would have hit the obstacle prematurely as it thinks that the obstacle is still 10 cm away when it's only 5cm away from the obstacle.

5.2 Configuring Robot Base's TF

Open bringup.launch:

roscd linorobot/launch
nano bringup.launch

Measure the distance between the floor and the center of the robot base. Define the measured distance on the third value found in "args" param.

     <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link" args="0 0 0.098 0 0 0  /base_footprint /base_link  100"/>

5.3 Configuring Laser's TF

Open laser.launch:

roscd linorobot/launch/include
nano laser.launch

Determine the lidar's location from the center of the base and change the first three numbers in "args" to your measured offsets. What these values mean is that the lidar is 6.5 cm forward and 9.8 cm from the center of the base. You can Click here to know more about configuring your transforms.

<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser"
args="0.065 0 0.098 0 0 0  /base_link /laser  100"/>

5.3 Checking Laser's TF

Open two terminals on the robot's computer. Run bringup.launch:

roslaunch linorobot bringup.launch

Run laser.launch:

roslaunch linorobot laser.launch

On your development computer, run rviz:

roscd lino_visualize/rviz
rviz -d laser.rviz

Place the robot 1 m away from a wall. Check on rviz if the wall detected is~1m. Each square in rviz is 1 square meter.

Screenshot from 2016-02-29 00:11:03

5.4 Troubleshooting

If the wall detected on rviz doesn't match with the actual distance between the wall and the robot, confirm that your x, y, and z offsets defined at laser.launch are correct.

6. Creating a map

The robot is all set. Continue to creating a map for SLAM.

You can’t perform that action at this time.
You signed in with another tab or window. Reload to refresh your session. You signed out in another tab or window. Reload to refresh your session.
Press h to open a hovercard with more details.