introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.69k stars 773 forks source link

2D Lidar only? #390

Open void-robotics opened 5 years ago

void-robotics commented 5 years ago

Hello,

Is it possible to use rtabmap with only a 2D lidar, like rplidar? I remember seeing some answers talking about rtabmap needing visual features to loop close, but is there a way to simulate this via only publishing to /scan or even with a 3D lidar to /scan_cloud?

Thanks, Nathan

matlabbe commented 5 years ago

Yes, since version 0.19. We can do only 2D scan or only 3D scan.

For 2D lidar, see this example for "Odom+2D Lidar" configuration and this example (minor the kinect input) to provide lidar odometry to rtabmap.

For 3D lidar, see these examples: test_ouster.launch and test_velodyne.launch

void-robotics commented 5 years ago

I tried install v0.19 from source (ROS answers), but I get

CMake Warning at nm_dependencies/rtabmap_ros-master/CMakeLists.txt:28 (find_package):
  By not providing "Findapriltags2_ros.cmake" in CMAKE_MODULE_PATH this
  project has asked CMake to find a package configuration file provided by
  "apriltags2_ros", but CMake did not find one.

  Could not find a package configuration file provided by "apriltags2_ros"
  with any of the following names:

    apriltags2_rosConfig.cmake
    apriltags2_ros-config.cmake

  Add the installation prefix of "apriltags2_ros" to CMAKE_PREFIX_PATH or set
  "apriltags2_ros_DIR" to a directory containing one of the above files.  If
  "apriltags2_ros" provides a separate development package or SDK, be sure it
  has been installed.

CMake Error at nm_dependencies/rtabmap_ros-master/CMakeLists.txt:34 (find_package):
  By not providing "FindRTABMap.cmake" in CMAKE_MODULE_PATH this project has
  asked CMake to find a package configuration file provided by "RTABMap", but
  CMake did not find one.

  Could not find a package configuration file provided by "RTABMap"
  (requested version 0.19.1) with any of the following names:

    RTABMapConfig.cmake
    rtabmap-config.cmake

  Add the installation prefix of "RTABMap" to CMAKE_PREFIX_PATH or set
  "RTABMap_DIR" to a directory containing one of the above files.  If
  "RTABMap" provides a separate development package or SDK, be sure it has
  been installed.

I was able to successfully install apriltags locally for Kinetic, but nothing changed.

matlabbe commented 5 years ago

The apriltags2_ros dependency is optional, above it is just a warning (no need to install it). The real problem is the CMake Error about RTABMap version required that should be >=0.19.1. Make sure you built rtabmap lib from source too (EDIT and installed!), and the binaries are uninstalled to avoid confusion:

$ sudo apt-get remove ros-kinetic-rtabmap

Installation example from source can be found on this page: https://github.com/introlab/rtabmap_ros#build-from-source

cheers, Mathieu

void-robotics commented 5 years ago

ok I see I missed step 2a; because of poor internet connection, I'll update in about a month

EDIT: actually I'm going to come back to this later

void-robotics commented 5 years ago

@matlabbe,

Using the launch file, I was able to get the rplidar to run on /scan, the /odom created from icp_odometry, rtabmap running correctly, but the map is not being created.

nathan@nathan-vm:~/newmind$ rosversion rtabmap_ros
0.19.3

I'm getting

[N=/rtabmap/rtabmap,F=publishMaps-1096]: Assembled 0 obstacle and 0 ground clouds (782 points, 0.000025s)
[N=/rtabmap/rtabmap,F=CoreWrapper::process-1935]: rtabmap (77): Rate=1.00s, Limit=0.000s, RTAB-Map=0.0089s, Maps update=0.0008s pub=0.0004s (local map=6, WM=6)
[N=/rtabmap/rtabmap,F=publishMaps-1096]: Assembled 0 obstacle and 0 ground clouds (782 points, 0.000030s)
[N=/rtabmap/rtabmap,F=CoreWrapper::process-1935]: rtabmap (78): Rate=1.00s, Limit=0.000s, RTAB-Map=0.0083s, Maps update=0.0007s pub=0.0002s (local map=6, WM=6)
[N=/rtabmap/rtabmap,F=publishMaps-1096]: Assembled 0 obstacle and 0 ground clouds (782 points, 0.000034s)
[N=/rtabmap/rtabmap,F=CoreWrapper::process-1935]: rtabmap (79): Rate=1.00s, Limit=0.000s, RTAB-Map=0.0289s, Maps update=0.0059s pub=0.0004s (local map=6, WM=6)
[N=/rtabmap/rtabmap,F=publishMaps-1096]: Assembled 0 obstacle and 0 ground clouds (782 points, 0.000061s)

In RViz, I can't see any point cloud or map. In rtabmapviz, though, Graph View is showing Lidar data.

Some questions I had:

  1. Am I missing something in my launch file?
  2. What should I subscribe to for a 2D Lidar...cloud_map?
  3. Does rtabmap take 2D Lidar data and generates a 3D point cloud if the 2D lidar is translated up/down, similar to laser_geometry and laser_assembler?
  4. After a few seconds or if I touch the lidar, the icp_odometry node gives all 0 values for the /odom; why is that?
<?xml version="1.0"?>

<launch>
    <arg name="positioning_sensor"          default="lidar" />
    <arg name="rtabmap_args"                default="" />
    <arg name="database_path"               default="" />

    <arg name="rgb_topic"                   default="/zed/zed_node/rgb/image_rect_color" />
    <arg name="depth_topic"                 default="/zed/zed_node/depth/depth_registered" />
    <arg name="camera_info_topic"           default="/zed/zed_node/rgb/camera_info" />
    <arg name="depth_camera_info_topic"     default="/zed/zed_node/depth/camera_info" />

    <arg name="subscribe_scan"              default="true" />
    <arg name="subscribe_rgbd"              default="false" />
    <arg name="rgbd_sync"                   default="false" />

    <!-- Nodes -->

    <node pkg="tf2_ros" type="static_transform_publisher" name="base_to_laser_pub" args="0 0 0 0 0 0 1 base_link laser" />
    <node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" />

    <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
        <param name="serial_port"         type="string" value="/dev/ttyUSB0"/>
        <param name="serial_baudrate"     type="int"    value="115200"/><!--A1/A2 -->

        <param name="frame_id"            type="string" value="laser"/>
        <param name="inverted"            type="bool"   value="false"/>
        <param name="angle_compensate"    type="bool"   value="true"/>
    </node>

    <group ns="rtabmap" if="$(eval positioning_sensor == 'lidar')" >
        <remap from="scan"    to="/scan"/>

        <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d">
            <param name="subscribe_scan"   value="true"/>
            <param name="subscribe_rgb"    value="false"/>
            <param name="subscribe_depth"  value="false"/>
            <param name="frame_id"         value="base_link"/>
            <param name="odom_frame_id"    value="odom"/>
            <param name="wait_for_transform_duration"  value="1"/>
            <param name="odom_tf_linear_variance"  value="0.01"/>
            <param name="odom_tf_angular_variance" value="0.05"/>

            <param name="Reg/Strategy"              value="1"/>    <!-- 1 for lidar -->
            <param name="Reg/Force3DoF"             value="true"/> <!-- 2d slam -->
            <param name="RGBD/NeighborLinkRefining" value="true"/> <!-- odometry correction with scans -->

        </node>
    </group>

    <include if="$(eval positioning_sensor == 'camera')" file="$(find rtabmap_ros)/launch/rtabmap.launch">
        <arg name="rtabmap_args"                value="$(arg rtabmap_args)" />
        <arg name="database_path"               value="$(arg database_path)" />

        <arg name="rgb_topic"                   value="$(arg rgb_topic)" />
        <arg name="depth_topic"                 value="$(arg depth_topic)" />
        <arg name="camera_info_topic"           value="$(arg camera_info_topic)" />
        <arg name="depth_camera_info_topic"     value="$(arg depth_camera_info_topic)" />
        <arg name="frame_id"                    value="base_link" />
        <arg name="approx_sync"                 value="false" />
        <arg name="visual_odometry"             value="false" />
        <arg name="odom_topic"                  value="/odom" />
        <arg name="rviz"                        value="false" />
        <arg name="rtabmapviz"                  value="false" />

        <arg name="subscribe_scan"              value="$(arg subscribe_scan)" />
        <arg name="subscribe_rgbd"              value="$(arg subscribe_rgbd)" />
        <arg name="stereo"                      value="$(arg stereo)" />
        <arg name="rgbd_sync"                   value="$(arg rgbd_sync)" />
    </include>

</launch>
matlabbe commented 5 years ago

Hi,

icp_odometry outputting zeros mean it is lost. It failed at scan matching. Make sure the lidar is always seeing structures in its field of view. Also look at the terminal when it got lost to see why (like not enough correspondences) so we could tune the Icp parameters (see $ rtabmap --params | grep Icp/) to accept more transformations. Other solution is to reset icp_odometry (see $ rosservice call rtabmap/reset_odom or automatically with parameter Odom/ResetCountdown=1).

Do you have a rosbag with only the lidar to test your launch file above?

$ rosbag record /scan

In RVIZ, show the occupancy grid /rtabmap/grid_map with Map display. To see laser scans, you may subscribe to /rtabmap/cloud_obstacles, or with latest MapCloud display version, check the option "Cloud from scan".

If 2D scan is converted to 3D point cloud, we can still use it as input to rtabmap (using subscribe_scan_cloud and scan_cloud topic). However, icp_odometry won't work very well if the consecutive scans don't have any correspondences. If the 2D Lidar is rotated like on the PR2 (see the one on its neck), we may accumulate the scans while it stand still, then give the assembled cloud to icp_odometry. To assemble scans when moving, we would have to use some kind of external odometry to correctly assemble the scans.

cheers, Mathieu

void-robotics commented 5 years ago

Thanks; I will revisit and update.