carlosmccosta / dynamic_robot_localization

Point cloud registration pipeline for robot localization and 3D perception
BSD 3-Clause "New" or "Revised" License
808 stars 196 forks source link

How do you get the correct TF? #15

Open stevemartinov opened 4 years ago

stevemartinov commented 4 years ago

Whenvever you find the TF from the lidar frame using the ICP: icp.getFinalTransformation() , getting the matrix and converting to ROS TF, how do you then proceed on publishing the Map to Odom TF? Is it like this?

  1. final_transformation_as_tf = final_transformation_as_tf (the one you got from the matrix) * map_to_base_tf2 (from listening the TF);
  2. Then getting the relative TF relative_tf2 = sensor_to_base_TF.inverseTimes(odom_to_base_TF)
  3. Finally final_transformation_as_tf = final_transformation_as_tf * relative_tf2;

Is that correct?

carlosmccosta commented 4 years ago

Good morning :)

I do not perform point cloud registration in the lidar frame. Instead I do it in the map frame and then apply the ICP corrections on top of: new_base_link_to_map_transformation = icp_corrections_transformation * last_odom_to_map_transformation * base_link_to_odom_transformation

This is equivalent to perform the ICP registration on the sensor frame while providing an initial alignment / guess: https://github.com/PointCloudLibrary/pcl/blob/master/registration/include/pcl/registration/registration.h#L425 using the transformation: alignment_guess_sensor_to_map_transformation = last_odom_to_map_transformation * base_link_to_odom_transformation * sensor_to_base_link_transformation

This way ICP will only correct small errors of the odometry that occur since the last lidar scan that was processed, allowing it to converge much faster.

After having the new_base_link_to_map_transformation, I compute the TF [odom -> map] using pose_to_tf_publisher. new_odom_to_map_transformation = new_base_link_to_map_transformation * odom_to_base_link_transformation

I usually provide the robot pose in the base_link or base_footprint frame: https://www.ros.org/reps/rep-0105.html http://wiki.ros.org/navigation/Tutorials/RobotSetup/TF

In drl, the main steps that involve transforming the sensor data are:

Have a nice day :)