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

Revision history [back]

click to hide/show revision 1
initial version

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.

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.