How to align Cloud_Map and Vector_Map - AD-EYE/AD-EYE_Core GitHub Wiki
Aligning the Cloud_Map and the road of the Vector_Map
The issue
An frequent issue you might encounter is that the Cloud_Map and Vector_Map aren't properly aligned when launching a simulation and visualing it with Rviz.
How to align them
This solution involves loading the cloud map frame into a specific new frame (to be used as an intermediate) and then using a node with the ros_tf functionality to modify the position and rotation parameters of the point cloud map. This new frame is then provided to the points map loader instead of the initial frame.
You can solve it by adding the “static_transform_publisher” node in your manager.launch file
<node
pkg="tf"
type="static_transform_publisher"
name="link1_broadcaster"
args="23 58 0 0 0 -0.679 0.734 map map_temp 100"
/>
-
The arguments (“args”) are the parameters you need to change to move the point cloud map under vector_map
-
The three first one are X Y Z axis (in Meters)
-
The four next one are the rotation (so : X Y Z W) (in Quaternion)
-
map is the parent frame
-
map_temp is the new child frame
-
and 100 is the frame rate (in milliseconds)
-
-
Also , you need to change the “points_map_loader.cpp” file in autoware to get (at line 351):
pcd.header.frame_id = "map_temp";
instead ofpcd.header.frame_id = "map";
-
And recompile Autoware with :
AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --continue-on-error --cmake-args -DCMAKE_BUILD_TYPE=Release
-
And see your modification of the "args" by launching the simulation with Rivz :
-
roslaunch adeye manager_performance_testing.launch
-
roslaunch adeye my_rviz.launch
-
Usefull Websites
About Ros_TF : https://wiki.ros.org/tf#static_transform_publisher
For rotation conversion https://quaternions.online/