Dear Dr. Labbé,
I am posting again since my thread moved down.
I have the following RTAB-Map setup on my robot:
2x D435 (one is placed lower and one on top of the robot, 90° rotated and there is a TF between these two) and 1x 2D LiDAR LDS-01 (was included on TB3). I am using wheel odometry coming from OpenCR board.
Here is my launch file:
<launch> <group ns="d435_bottom"> <node pkg="nodelet" type="nodelet" name="nodelet_manager1" args="manager"/> <node pkg="nodelet" type="nodelet" name="rgbd_sync1" args="load rtabmap_ros/rgbd_sync nodelet_manager1"> <remap from="rgb/image" to="color/image_raw"/> <remap from="depth/image" to="aligned_depth_to_color/image_raw"/> <remap from="rgb/camera_info" to="color/camera_info"/> <param name="approx" value="false"/> </node> </group> <group ns="d435_top"> <node pkg="nodelet" type="nodelet" name="nodelet_manager2" args="manager"/> <node pkg="nodelet" type="nodelet" name="rgbd_sync2" args="load rtabmap_ros/rgbd_sync nodelet_manager2"> <remap from="rgb/image" to="color/image_raw"/> <remap from="depth/image" to="aligned_depth_to_color/image_raw"/> <remap from="rgb/camera_info" to="color/camera_info"/> <param name="approx" value="false"/> </node> </group> <group ns="rtabmap"> <!-- Visual SLAM (robot side) --> <!-- args: "delete_db_on_start" and "udebug" --> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start"> <param name="subscribe_depth" type="bool" value="false"/> <param name="subscribe_rgbd" type="bool" value="true"/> <param name="subscribe_scan" type="bool" value="true"/> <param name="rgbd_cameras" type="int" value="2"/> <param name="frame_id" type="string" value="base_footprint"/> <!-- <param name="gen_scan" type="bool" value="true"/> --> <param name="map_negative_poses_ignored" type="bool" value="false"/> <!-- refresh grid map even if we are not moving--> <param name="map_negative_scan_empty_ray_tracing" type="bool" value="false"/> <!-- don't fill empty space between the generated scans--> <remap from="odom" to="/odom"/> <remap from="rgbd_image0" to="/d435_bottom/rgbd_image"/> <remap from="rgbd_image1" to="/d435_top/rgbd_image"/> <remap from="scan" to="/scan_filtered"/> <param name="RGBD/NeighborLinkRefining" type="string" value="true"/> <param name="RGBD/ProximityBySpace" type="string" value="true"/> <param name="RGBD/AngularUpdate" type="string" value="0.01"/> <param name="RGBD/LinearUpdate" type="string" value="0.01"/> <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/> <param name="Grid/FromDepth" type="string" value="false"/> <param name="Grid/CellSize" type="string" value="0.02"/> <param name="Vis/EstimationType" type="string" value="0"/> <!-- should be 0 for multi-cameras --> <param name="Reg/Force3DoF" type="string" value="true"/> <param name="Reg/Strategy" type="string" value="1"/> <param name="Icp/VoxelSize" type="string" value="0.05"/> <param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/> </node> </group> </launch> roslaunch realsense2_camera rs_camera.launch align_depth:=true roslaunch rtabmap_ros rtabmap.launch \ rtabmap_args:="--delete_db_on_start" \ depth_topic:=/camera/aligned_depth_to_color/image_raw \ rgb_topic:=/camera/color/image_raw \ camera_info_topic:=/camera/color/camera_info \ approx_sync:=false |
Administrator
|
It could, but the problem is that the robot may never localize on the map created with hand-held mapping because the point of view of the camera would not be similar.
If you restart the robot in localization mode (Mem/IncrementalMemory=false) and without --delete_db_on_start, you should be able to see the map with Download button, unless there is a problem with ROS_IP between the computers. If you restart in mapping mode (even without --delete_db_on_start), rtabmap creates a new session in the database, and you won't be able to see the previous session until the robot localizes in it. |
Thank you for your answer.
I am using it locally on the same computer - the .db file I generated in hand-held mode is transferred to my the robot computer and the node starts on it. It's the only device in my ROS network. I have posted some videos here as well: https://github.com/introlab/rtabmap_ros/issues/602#issuecomment-886518243 Sorry for double posting on Github I wasn't sure where I can get the answer faster. Cheers. |
Free forum by Nabble | Edit this page |