ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Rtabmap_ros does not show octo map but points clouds are good

asked 2018-08-21 02:55:31 -0500

Astronaut gravatar image

updated 2018-09-10 02:54:38 -0500

Hi Im using two point Grey Chameleon3 mono camera set up as Master Salve and synchronized so can work as stereo camera. I have a installed ROS driver and able to publish the camera topics . Im using this ROS driver https://github.com/KumarRobotics/flea3. And with roslaunch flea3 stereo_node.launch left:=18081067 right:=17496474 camera:=stereo_camera

can launch the driver. Im hand holding the cameras so for that case using this tutorial http://wiki.ros.org/rtabmap_ros/Tutorials/StereoHandHeldMapping about hand-held stereo mapping.

This is my launch file that Im launching with rtabmap$ roslaunch rtabmap_ros stereo_mapping.launch rtabmap_args:="--delete_db_on_start --Vis/CorFlowMaxLevel 9000 --Stereo/MaxDisparity 80000 --Odom/Strategy 1 --Odom/GuessMotion true --Vis/EstimationType 1 --Vis/CorType 1 --Odom/ResetCountdown 1" left_image_topic:=/stereo_camera/left/image_rect_color queue_size:=40 stereo:=true rviz:=true rtabmapviz:=false

  <launch>

  <arg name="pi/2" value="1.5707963267948966" />
  <arg name="optical_rotate" value=" 0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />
  <node pkg="tf" type="static_transform_publisher" name="camera_base_link_rtabmap"
  args="$(arg optical_rotate) base_link stereo_camera/left 100" />  

 <group ns="/stereo_camera" >   
  <node pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc"/>
!-- Odometry -->
  </group>
  <!-- Choose between RGB-D and stereo -->      
  <arg name="stereo"          default="true"/>
  <!-- Choose visualization -->
  <arg name="rtabmapviz"              default="true" /> 
  <arg name="rviz"                    default="false" />
  <!-- Localization-only mode -->
  <arg name="localization"            default="false"/>

  <!-- sim time for convenience, if playing a rosbag -->
  <arg name="use_sim_time"            default="false"/>
  <param if="$(arg use_sim_time)" name="use_sim_time" value="true"/>

  <!-- Corresponding config files -->
  <arg name="cfg"                     default="" /> <!-- To change RTAB-Map's parameters, set the path of config file (*.ini) generated by the standalone app -->
  <arg name="gui_cfg"                 default="~/.ros/rtabmap_gui.ini" />
  <arg name="rviz_cfg"                default="$(find rtabmap_ros)/launch/config/rgbd.rviz" />
  <arg name="frame_id"                default="base_link"/>     <!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published -->
  <arg name="odom_frame_id"           default=""/>                <!-- If set, TF is used to get odometry instead of the topic -->
  <arg name="map_frame_id"            default="map"/>
  <arg name="ground_truth_frame_id"   default=""/>     <!-- e.g., "world" -->
  <arg name="ground_truth_base_frame_id" default=""/>  <!-- e.g., "tracker", a fake frame matching the frame "frame_id" (but on different TF tree) -->
  <arg name="namespace"               default="rtabmap"/>
  <arg name="database_path"           default="~/.ros/rtabmap.db"/>
  <arg name="queue_size"              default="10"/>
  <arg name="wait_for_transform"      default="0.2"/>
  <arg name="args"                    default=""/>              <!-- delete_db_on_start, udebug -->
  <arg name="rtabmap_args"            default="$(arg args)"/>   <!-- deprecated, use "args" argument -->
  <arg name="launch_prefix"           default=""/>              <!-- for debugging purpose, it fills launch-prefix tag of the nodes -->
  <arg name="output"                  default="screen"/>        <!-- Control node output (screen or log) -->

  <!-- if timestamps of the input topics are synchronized using approximate or exact time policy-->
  <arg     if="$(arg stereo)" name="approx_sync"  default="false"/>
  <arg unless="$(arg stereo)" name="approx_sync"  default="true"/>         

  <!-- RGB-D related topics -->
  <arg name="rgb_topic"               default="/camera/rgb/image_rect_color" />
  <arg name="depth_topic"             default="/camera/depth_registered/image_raw" />
  <arg name="camera_info_topic"       default="/camera/rgb/camera_info" />
  <arg name="depth_camera_info_topic" default="$(arg camera_info_topic)" />

  <!-- stereo related topics -->
  <arg name="stereo_namespace"        default="/stereo_camera"/>
  <arg name="left_image_topic"        default="$(arg stereo_namespace)/left/image_rect" />
  <arg name="right_image_topic"       default="$(arg stereo_namespace)/right/image_rect" />      <!-- using grayscale image for efficiency -->
  <arg name="left_camera_info_topic"  default="$(arg stereo_namespace)/left/camera_info" />
  <arg name ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-08-22 10:14:34 -0500

matlabbe gravatar image

updated 2018-08-29 12:43:25 -0500

From this warning:

[ WARN] (2018-08-21 15:29:10.585) Memory.cpp:749::update() The working memory is empty and the memory is not incremental (Mem/IncrementalMemory=False), no loop closure can be detected! Please set Mem/IncrementalMemory=true to increase the memory with new images or decrease the STM size (which is 1 including the new one added).

caused by this argument in the launch file:

<!-- Localization-only mode -->
  <arg name="localization"            default="true"/>

Set to false to do SLAM, otherwise there is no map constructed, thus no octomap. This should be only used when there is already a map constructed. When setting localization to true, it sets Mem/IncrementalMemory=False.

Also, don't include rtabmap.launch if you explicitly start stereo_odometry and rtabmap nodes, or use only rtabmap.launch (which starts stereo_odometry and rtabmap nodes, see original stereo_mapping.launch). You may have two stereo_odometry nodes and two rtabmap nodes started.

EDIT

I am not sure what you are expecting from the OctoMap and stereo, but the result you have seems okay. I took your launch file and tested on the dataset of this tutorial. I added the following at the top of your launch file to stream images from that dataset:

   <!-- stereo_20Hz directory -->
   <arg name="dir"        default="$(env HOME)/Downloads/stereo_20Hz" />
   <!-- Run stereo_sequence_publisher to publish synchronized images -->
   <node name="stereo_pub" pkg="bag_tools" type="stereo_sequence_publisher.py" output="screen">
      <param name="image_dir_left"         value="$(arg dir)/left"/>
      <param name="image_dir_right"        value="$(arg dir)/right"/>
      <param name="file_pattern"           value="*.jpg"/>
      <param name="camera_info_file_left"  value="$(arg dir)/stereo_20Hz_ros_left.yaml"/>
      <param name="camera_info_file_right" value="$(arg dir)/stereo_20Hz_ros_right.yaml"/>
      <param name="frequency"              value="20"/>
      <remap from="/stereo_camera/left/image_color"  to="/stereo_camera/left/image_raw" />
      <remap from="/stereo_camera/right/image_color" to="/stereo_camera/right/image_raw" />
      <remap from="/stereo_camera/left/camera_info"  to="/stereo_camera/left/camera_info" />
      <remap from="/stereo_camera/right/camera_info" to="/stereo_camera/right/camera_info" />
   </node>
   <node pkg="tf" type="static_transform_publisher" name="dummy_transform"
      args="0 0 0 0 0 0 stereo_camera/left stereo_20Hz_left 100" />

image description

Note that in this dataset, the ground is textured, so stereo can actually see the ground.

edit flag offensive delete link more

Comments

I edit the question. change the launch file and edit that in the question. No more warnings, can get the octo map but the quality is not so good. Any help how to improve the map?

Astronaut gravatar image Astronaut  ( 2018-08-24 03:29:29 -0500 )edit

Updated answer

matlabbe gravatar image matlabbe  ( 2018-08-29 12:43:42 -0500 )edit

Ok. Thanks. Only one question. Why in your launch file the transform is stereo_camera/left stereo_20Hz_left? And when set up rviz what should be reference frame and what should be fixed in my case when have handhold camera? My transform is base_link stereo_camera/left 100. Thanks

Astronaut gravatar image Astronaut  ( 2018-09-02 22:08:40 -0500 )edit

The global frame in RVIz is map. The frame stereo_20Hz_left is the one published by the stereo_sequence_publisher, I didn't want to modify your launch file, so I just added a new transform. You don't need it in your setup.

matlabbe gravatar image matlabbe  ( 2018-09-03 08:23:45 -0500 )edit

I run again with same settings same launch file and now no map. I got this: Odometry.cpp:559::process() Null stamp detected Why no odometry now? same launch file

Astronaut gravatar image Astronaut  ( 2018-09-07 00:28:47 -0500 )edit

What is the header of your image messages? Is the stamp always set?

matlabbe gravatar image matlabbe  ( 2018-09-07 06:14:36 -0500 )edit

how to check that?

Astronaut gravatar image Astronaut  ( 2018-09-09 22:48:41 -0500 )edit

rostopic hz /stereo_camera/left/image_rect the average rate: 5.145 min: 0.125s max: 15.334s std dev: 0.96139s window: 250

Astronaut gravatar image Astronaut  ( 2018-09-10 00:28:22 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-08-21 02:55:31 -0500

Seen: 1,197 times

Last updated: Sep 10 '18