Closed FlorianMehnert closed 8 months ago
Hi, you could probably use depthai_ros_driver example with some minor changes to the params file to enable outputting spatial detections while mapping. You could also use spatial_bb filter to output bounding boxes as 3D markers while mapping.
Thank you for your quick response :) I forgot to mention that I am using ros-noetic with a OAK-D-Pro-PoE. The depthai_ros_driver example does work for me after some minor adjustments to rtabmap names:
<?xml version="1.0"?>
<launch>
<arg name="name" default="oak" />
<arg name="params_file" default="$(find depthai_ros_driver)/config/rgbd.yaml" />
<include file="$(find depthai_ros_driver)/launch/camera.launch">
<arg name="name" value="$(arg name)"/>
<arg name="params_file" value="$(arg params_file)"/>
</include>
<node type="rgbd_odometry" name="rgbd_odometry" pkg="rtabmap_odom">
<remap from="rgb/image" to="$(arg name)/rgb/image_raw"/>
<remap from="rgb/camera_info" to="$(arg name)/rgb/camera_info"/>
<remap from="depth/image" to="$(arg name)/stereo/image_raw"/>
<param name="frame_id" type="string" value="$(arg name)"/>
<rosparam param="subscribe_depth">True</rosparam>
<rosparam param="approx_sync">True</rosparam>
<rosparam param="approx_sync_max_interval">0.02</rosparam>
</node>
<node type="rtabmap" name="rtabmap" pkg="rtabmap_slam">
<remap from="rgb/image" to="$(arg name)/rgb/image_raw"/>
<remap from="rgb/camera_info" to="$(arg name)/rgb/camera_info"/>
<remap from="depth/image" to="$(arg name)/stereo/image_raw"/>
<rosparam param="Rtabmap/DetectionRate">3.5</rosparam>
<param name="frame_id" type="string" value="$(arg name)"/>
</node>
<node type="rtabmap_viz" name="rtabmap_viz" pkg="rtabmap_viz">
<remap from="rgb/image" to="$(arg name)/rgb/image_raw"/>
<remap from="rgb/camera_info" to="$(arg name)/rgb/camera_info"/>
<remap from="depth/image" to="$(arg name)/stereo/image_raw"/>
</node>
</launch>
Additionally I had to change the Transport Hint of the oak/rgb/image_raw
topic from raw
to theora
to enable rtabmap for some reason
@Serafadam I think it would make sense to update the rtabmap.launch
in the noetic branch as described above by @FlorianMehnert so futurte users who are still bound to ROS 1 don't run into the same issue.
Current issue when starting from noetic
branch without changes:
roslaunch depthai_ros_driver rtabmap.launch
...
ERROR: cannot launch node of type [rtabmap_ros/rgbd_odometry]: Cannot locate node of type [rgbd_odometry] in package [rtabmap_ros]. Make sure file exists in package path and permission is set to executable (chmod +x)
ERROR: cannot launch node of type [rtabmap_ros/rtabmap]: Cannot locate node of type [rtabmap] in package [rtabmap_ros]. Make sure file exists in package path and permission is set to executable (chmod +x)
ERROR: cannot launch node of type [rtabmap_ros/rtabmapviz]: Cannot locate node of type [rtabmapviz] in package [rtabmap_ros]. Make sure file exists in package path and permission is set to executable (chmod +x)
...
Reference to rtabmap_ros
documentation: http://wiki.ros.org/rtabmap_ros#rtabmap_ros.2Fnoetic_and_newer.Migration_Guide_New_Interface_Noetic.2FROS2
Is it possible to use the spatial detections while simultaneously using the handheld mapping approach from rtabmap? It seems like the
stereo_inertial_node
used for rtabmap either supports SLAM withdepth_alinged=true
or object detection withdepth_alinged=false