introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
974 stars 557 forks source link

[pcl::VoxelGrid::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow. #86

Closed willdzeng closed 8 years ago

willdzeng commented 8 years ago

Hi Mathieu,

This is Di from Transcend Robotics.

I am successfully able to launch your code and run the hand held mapping with a ZED camera. But It keep giving me this warning, is this a problem of PCL libary? should I update the PCL from source?

My system is Ubuntu 14.04. ROS Jade is installed. Build from source. Here is my launch file.

<launch>
   <!-- Your camera should be calibrated and publishing rectified left and right 
        images + corresponding camera_info msgs. You can use stereo_image_proc for image rectification.
        Example:
           $ roslaunch rtabmap_ros bumblebee.launch -->

  <!-- Choose visualization -->
  <arg name="rtabmapviz"              default="true" /> 
  <arg name="rviz"                    default="true" />

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

  <!-- Corresponding config files -->
  <arg name="rtabmapviz_cfg"          default="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" />
  <arg name="rviz_cfg"                default="-d $(find rtabmap_ros)/launch/config/rgbd.rviz" />

  <arg name="frame_id"                default="camera_link"/>     <!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published -->
  <arg name="time_threshold"          default="0"/>             <!-- (ms) If not 0 ms, memory management is used to keep processing time on this fixed limit. -->
  <arg name="optimize_from_last_node" default="false"/>         <!-- Optimize the map from the last node. Should be true on multi-session mapping and when time threshold is set -->
  <arg name="database_path"           default="~/.ros/rtabmap.db"/>
  <arg name="rtabmap_args"            default="--Vis/CorFlowMaxLevel 5 --Stereo/MaxDisparity 200"/>              <!-- delete_db_on_start, udebug -->
  <arg name="launch_prefix"           default=""/>

  <arg name="stereo_namespace"        default="/camera"/>
  <arg name="left_image_topic"        default="$(arg stereo_namespace)/left/image_rect_color" />
  <arg name="right_image_topic"       default="$(arg stereo_namespace)/right/image_rect_color" />      <!-- using grayscale image for efficiency -->
  <arg name="left_camera_info_topic"  default="$(arg stereo_namespace)/left/camera_info" />
  <arg name="right_camera_info_topic" default="$(arg stereo_namespace)/right/camera_info" />
  <arg name="approximate_sync"        default="false"/>         <!-- if timestamps of the stereo images are not synchronized -->
  <arg name="compressed"              default="false"/>
  <arg name="convert_depth_to_mm"     default="true"/>

  <arg name="subscribe_scan"          default="false"/>         <!-- Assuming 2D scan if set, rtabmap will do 3DoF mapping instead of 6DoF -->
  <arg name="scan_topic"              default="/scan"/>

  <arg name="subscribe_scan_cloud"    default="false"/>         <!-- Assuming 3D scan if set -->
  <arg name="scan_cloud_topic"        default="/scan_cloud"/>

  <arg name="visual_odometry"         default="true"/>          <!-- Generate visual odometry -->
  <arg name="odom_topic"              default="/odom"/>         <!-- Odometry topic used if visual_odometry is false -->

  <arg name="namespace"               default="rtabmap"/>
  <arg name="wait_for_transform"      default="0.2"/>

  <!-- Nodes -->
  <group ns="$(arg namespace)">

    <node if="$(arg compressed)" name="republish_left"  type="republish" pkg="image_transport" args="compressed in:=$(arg left_image_topic) raw out:=$(arg left_image_topic)" />
    <node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="compressed in:=$(arg right_image_topic) raw out:=$(arg right_image_topic)" />

    <!-- Odometry -->
    <node if="$(arg visual_odometry)" pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)">
      <remap from="left/image_rect"        to="$(arg left_image_topic)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>

      <param name="frame_id"                 type="string" value="$(arg frame_id)"/>
      <param name="wait_for_transform_duration"       type="double"   value="$(arg wait_for_transform)"/>
      <param name="approx_sync"              type="bool"   value="$(arg approximate_sync)"/>

      <param name="Odom/FillInfoData"        type="string" value="true"/> 
    </node>

    <!-- Visual SLAM (robot side) -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)">
      <param name="subscribe_depth"              type="bool"   value="false"/>
      <param name="subscribe_stereo"             type="bool"   value="true"/>
      <param name="subscribe_scan"               type="bool"   value="$(arg subscribe_scan)"/>
      <param name="subscribe_scan_cloud"         type="bool"   value="$(arg subscribe_scan_cloud)"/>
      <param name="frame_id"                     type="string" value="$(arg frame_id)"/>
      <param name="wait_for_transform_duration"  type="double"   value="$(arg wait_for_transform)"/>
      <param name="database_path"                type="string" value="$(arg database_path)"/>
      <param name="stereo_approx_sync"           type="bool"   value="$(arg approximate_sync)"/>

      <remap from="left/image_rect"        to="$(arg left_image_topic)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="scan_cloud"      to="$(arg scan_cloud_topic)"/>
      <remap unless="$(arg visual_odometry)" from="odom"  to="$(arg odom_topic)"/>

      <param name="Rtabmap/TimeThr"              type="string" value="$(arg time_threshold)"/>
      <param name="RGBD/OptimizeFromGraphEnd"    type="string" value="$(arg optimize_from_last_node)"/>
      <param name="Mem/SaveDepth16Format"        type="string" value="$(arg convert_depth_to_mm)"/>

      <!-- localization mode -->
      <param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
      <param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
      <param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>

        <!-- when 2D scan is set -->
      <param if="$(arg subscribe_scan)" name="Optimizer/Slam2D"        type="string" value="true"/>
      <param if="$(arg subscribe_scan)" name="Icp/CorrespondenceRatio" type="string" value="0.25"/>
      <param if="$(arg subscribe_scan)" name="Reg/Strategy"            type="string" value="1"/> 
      <param if="$(arg subscribe_scan)" name="Reg/Force3DoF"           type="string" value="true"/>

      <!-- when 3D scan is set -->
      <param if="$(arg subscribe_scan_cloud)" name="Reg/Strategy"      type="string" value="1"/>
    </node>

    <!-- Visualisation RTAB-Map -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="$(arg rtabmapviz_cfg)" output="screen" launch-prefix="$(arg launch_prefix)">
      <param name="subscribe_depth"           type="bool"   value="false"/>
      <param name="subscribe_stereo"          type="bool"   value="true"/>
      <param name="subscribe_scan"            type="bool"   value="$(arg subscribe_scan)"/>
      <param name="subscribe_scan_cloud"      type="bool"   value="$(arg subscribe_scan_cloud)"/>
      <param name="subscribe_odom_info"       type="bool"   value="$(arg visual_odometry)"/>
      <param name="frame_id"                  type="string" value="$(arg frame_id)"/>
      <param name="wait_for_transform_duration"   type="double"   value="$(arg wait_for_transform)"/>

      <remap from="left/image_rect"        to="$(arg left_image_topic)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="scan_cloud"             to="$(arg scan_cloud_topic)"/>
      <remap unless="$(arg visual_odometry)" from="odom"  to="$(arg odom_topic)"/>
    </node>

  </group>

  <!-- Visualization RVIZ -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="$(arg rviz_cfg)"/>
  <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb">
    <remap from="left/image"        to="$(arg left_image_topic)"/>
    <remap from="right/image"       to="$(arg right_image_topic)"/>
    <remap from="left/camera_info"  to="$(arg left_camera_info_topic)"/>
    <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>
    <remap from="cloud"             to="voxel_cloud" />

    <param name="decimation"  type="double" value="2"/>
    <param name="voxel_size"  type="double" value="0.02"/>
    <param name="approx_sync" type="bool"   value="$(arg approximate_sync)"/>
  </node>

</launch>
matlabbe commented 8 years ago

Hi Di,

The warning is coming from the points_xyzrgb plugin. To avoid this warning, you can set this instead in that nodelet (disabling voxel filtering):

<param name="decimation"  type="double" value="4"/>
<param name="voxel_size"  type="double" value="0.0"/>

The following command gives the same results as your modified launch file:

$ roslaunch rtabmap_ros stereo_mapping.launch stereo_namespace:=/camera right_image_topic:=/camera/right/image_rect_color frame_id:=camera_link rtabmap_args:="--Vis/CorFlowMaxLevel 5 --Stereo/MaxDisparity 200 rviz:=true"

However, even if the camera doesn't move, sometime the odometry gets lost (inliers drop from 300 to under 20):

[ INFO] [1466090354.718997697]: Odom: quality=315, std dev=0.010495m, update time=0.073979s
[ INFO] [1466090354.796440017]: Odom: quality=319, std dev=0.013374m, update time=0.073643s
[ WARN] (2016-06-16 11:19:14.866) OdometryF2M.cpp:227::computeTransform() Registration failed: "Not enough inliers 13/20 (matches=339) between -1 and 0"
[ INFO] [1466090354.867368030]: Odom: quality=13, std dev=0.000000m, update time=0.068204s
[ WARN] (2016-06-16 11:19:14.934) OdometryF2M.cpp:227::computeTransform() Registration failed: "Not enough inliers 10/20 (matches=342) between -1 and 0"
[ INFO] [1466090354.935537317]: Odom: quality=10, std dev=0.000000m, update time=0.065454s
[ INFO] [1466090355.003787475]: Odom: quality=306, std dev=0.010724m, update time=0.065558s

This problem comes from cv::solvePnPRansac, maybe because of a not so good calibration or that RANSAC failed to find good correspondences for transformation estimation. You can try with --Vis/EstimationType 0 to use 3D->3D motion estimation instead of PnP.

As you are using the Zed camera, they provide already a depth image that can be used (so no need for rtabmap to re-compute stereo correspondences). So like in the RGB-D tutorial, we can do:

$ roslaunch rtabmap_ros rgbd_mapping.launch depth_registered_topic:=/camera/depth/image_rect_color rviz:=true

The odometry is far more stable with more inliers.

cheers, Mathieu

willdzeng commented 8 years ago

Hi Mathieu,

Thanks.

I found out I increase the nodelet decimation from 2 to 4 it works without change the voxel_size.

<param name="decimation" type="double" value="4"/>

This fixed the issue.

Is this because the desktop I am using has more computation power so that it needs more image to process at a time? because I never had this problem on my laptop.

matlabbe commented 8 years ago

The warning seems related to a large point cloud to voxelize: https://github.com/PointCloudLibrary/pcl/issues/585

I think setting max_depth would also fix that problem (the point cloud area will be bounded). With stereo, sometimes disparity for a pixel can be very small (~0), thus generating very long distance (~inf).

<param name="max_depth" type="double" value="15.0"/>