rtabmap with octomap and hector slam

classic Classic list List threaded Threaded
17 messages Options
Reply | Threaded
Open this post in threaded view
|

rtabmap with octomap and hector slam

boon
I am trying to create a mapping as seen in this video, Autonomous Flight of a simulated Quadrotor using moveit . I am just simulation and don't have any hardware setup. I ran hector indoor SLAM demo with kinect and then used rtabmap and then octomap. But I could not see any 3D maps being generated.

This is what I did,

$ roslaunch hector_quadrotor_demo indoor_slam_gazebo.launch

$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmapviz:=false rviz:=true

$ rosrun octomap_server octomap_server_node cloud_in:=/rtabmap/cloud_map

What should I be doing to reproduce the mapping that was done in the video?

my rqtgraph,

Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
I tried the octomap with spiri_simulator which uses ground truth and nav. There is no other localization module but even with this I could not generate a 3D map.

$ roslaunch spiri_description move_it_spiri.launch

$ roslaunch rtabmap_ros demo_robot_localization.launch rtabmapviz:=false rviz:=false

$ rosrun octomap_server octomap_server_node cloud_in:=/rtabmap/cloud_map


Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
Hi,

You can't use the demo launch file directly, they are very specific to rosbag used for the demo.

When you launch rgbd_mapping.launch, you may have to remap some input topics to those used in your simulator. For example:

# No visualization, delete previous database, remap image topics
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmapviz:=false rtabmap_args:="--delete_db_on_start" rgb_topic:=/camera/rgb/image_color_rect depth_registered_topic:=/camera/depth_registration/image_raw camera_info_topic:=/camera/rgb/camera_info

You would also see on the terminal the required topics. If one of these topics is not published, rtabmap won't work.
[...]
/rtabmap/rgbd_odometry subscribed to:
   /camera/rgb/image_color_rect,
   /camera/depth_registration/image_raw,
   /camera/rgb/camera_info
[ INFO] [1443097665.201129476]: RTAB-Map rate detection = 1.000000 Hz
[ INFO] [1443097665.203129619]: rtabmap: Deleted database "/home/mathieu/.ros/rtabmap.db" (--delete_db_on_start is set).
[ INFO] [1443097665.203204240]: rtabmap: Using database from "/home/mathieu/.ros/rtabmap.db".
[ INFO] [1443097665.411523036]: rtabmap: Database version = "0.10.6".
[ INFO] [1443097665.724782616]: Registering Depth callback...
[ INFO] [1443097665.727396510]: 
/rtabmap/rtabmap subscribed to:
   /camera/rgb/image_color_rect,
   /camera/depth_registration/image_raw,
   /camera/rgb/camera_info,
   /rtabmap/odom
[...]


cheers
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
This post was updated on .
In reply to this post by boon
I remapped two topics that rtabmap required and I tried,

$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmapviz:=false rtabmap_args:="--delete_db_on_start" rgb_topic:=/camera/rgb/image_raw depth_registered_topic:=/camera/depth/image_raw camera_info_topic:=/camera/rgb/camera_info

I am getting messages on these topics. But when I try,

$ rostopic hz /rtabmap/cloud_map

no pointclould2 messages are being sent  in this topic and I cannot see anything in visualization too.

I get a warning,
Input depth type is 32FC1, please use type 16UC1 or mono16 for depth. The depth images will be processed anyway but with a conversion. This warning is only be printed once...

Could not get transform from camera_link to camera_depth_optical_frame after 1 second!

I also get this error:
[rtabmap/rgbd_odometry-1] process has died [pid 29438, exit code -11, cmd /opt/ros/indigo/lib/rtabmap_ros/rgbd_odometry rgb/image:=/camera/rgb/image_raw depth/image:=/camera/depth/image_raw rgb/camera_info:=/camera/rgb/camera_info __name:=rgbd_odometry __log:=/home/boon/.ros/log/6537fdcc-633a-11e5-abfd-678f0acc617a/rtabmap-rgbd_odometry-1.log].
log file: /home/boon/.ros/log/6537fdcc-633a-11e5-abfd-678f0acc617a/rtabmap-rgbd_odometry-1*.log

But when I look for the 'rtabmap-rgbd_odometry-1.log' file, it does not exist

My frames and rqt_graph


Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
rtabmap node is missing the odometry input. If you are using hector_mapping in parallel, you can use it like the Kinect+Laser setup with rtabmap to provide odometry (note the TF parameters):
  <node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

  <!-- Odometry from laser scans -->
  <!-- We use Hector mapping to generate odometry for us -->
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping">
    
    <!-- Frame names -->
    <param name="map_frame" value="hector_map" />
    <param name="base_frame" value="base_footprint" />
    <param name="odom_frame" value="odom" />
    
    <!-- Tf use -->
    <param name="pub_map_odom_transform" value="false"/>
    <param name="pub_map_scanmatch_transform" value="true"/>
    <param name="pub_odometry" value="true"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.050"/>
    <param name="map_size" value="2048"/>
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="map_update_angle_thresh" value="0.06" />
    
    <!-- Advertising config --> 
    <param name="scan_topic" value="/scan"/>
  </node>

Then when you call rgbd_mapping.launch, you can add these parameters too:
visual_odometry:=false odom_topic:=/scanmatch_odom subscribe_scan:=true scan_topic:=/scan 

Regarding your tf tree, you should have /world -> /map -> /scanmatch_odom -> /base_footprint. The transform /world -> /base_footprint should not exist.

cheers
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
This post was updated on .
In reply to this post by boon
I added the following to the quadrotor launch file,

<node pkg="tf" type="static_transform_publisher" name="world_to_map"
    args="0.0 0.0 0.0 0.0 0.0 0.0 /world /hector_map 100" />
 

  <node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint"
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

 
 
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping">
   
   
   
   
   
   
   
   
   
   
   
   
   
   
   
   
   
   
   
     
   
  </node>
 
Is this the correct way to add world to map transform?

I launched rtabmap by,

roslaunch rtabmap_ros rgbd_mapping.launch rtabmapviz:=false rtabmap_args:="--delete_db_on_start" rgb_topic:=/camera/rgb/image_raw depth_registered_topic:=/camera/depth/image_raw camera_info_topic:=/camera/rgb/camera_info visual_odometry:=false odom_topic:=/scanmatch_odom subscribe_scan:=true scan_topic:=/scan

But I found that rtabmap is not subscribing to the /scanmatch_odom published by hector_mapping.

And there is not argument called, 'odom_topic' in 'rgbd_mapping.launch'. Does 'odom_topic' argument is given a different name within rgbd_mapping.launch file?

I get this warning,
 Input depth type is 32FC1, please use type 16UC1 or mono16 for depth. The depth images will be processed anyway but with a conversion. This warning is only be printed once...
[ WARN] [1443295482.259304131, 1256.605000000]: Could not get transform from camera_link to camera_depth_optical_frame after 1 second!

My tf frame and rosgraph


Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
Sorry, I forgot to mention to download the latest version of rgbd_mapping.launch. You will have "odom_topic" and "visual_odometry" arguments.

The warning is okay.

Use "raw text" to show your launch file, I can't see what is in the hector_mapping node. You should not have to use "scanmatcher_to_base_footprint" node. Normally with these hector_mapping parameters:
<param name="pub_map_odom_transform" value="false"/>
<param name="pub_map_scanmatch_transform" value="true"/>
<param name="pub_odometry" value="true"/>
odometry frame from hector_mapping should be published, as well as the odometry topic required by rtabmap. In your graph, the /scan topic is not connected to rtabmap node, which is strange since you used "subscribe_scan:=true scan_topic:=/scan" arguments. Are you on ROS Hydro?



Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
I am working on ROS Indigo. I downloaded the latest version of rgbd_mapping.launch.

My launch file is as shown below,

 
  
  <!-- Start Gazebo with wg world running in (max) realtime -->
    <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">    
    <arg name="world_name" value="$(find chefbot_gazebo)/worlds/complete_hotel.sdf"/>
  </include>
   
  <!-- Spawn simulated quadrotor uav -->
  <include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch" >
    <arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_hokuyo_utm30lx_kinect.gazebo.xacro"/>
    
  </include>
   
  <node pkg="tf" type="static_transform_publisher" name="world_to_map" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /world /hector_map 100" />
  

  <node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

  <!-- Odometry from laser scans -->
  <!-- We use Hector mapping to generate odometry for us -->
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping">
    
    <!-- Frame names -->
    <param name="map_frame" value="hector_map" />
    <param name="base_frame" value="base_footprint" />
    <param name="odom_frame" value="odom" />
    
    <!-- Tf use -->
    <param name="pub_map_odom_transform" value="false"/>
    <param name="pub_map_scanmatch_transform" value="true"/>
    <param name="pub_odometry" value="true"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.050"/>
    <param name="map_size" value="2048"/>
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="map_update_angle_thresh" value="0.06" />
    
    <!-- Advertising config --> 
    <param name="scan_topic" value="/scan"/>
  </node>
 
   
  <!-- Start rviz visualization with preset config -->
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find hector_quadrotor_demo)/rviz_cfg/indoor_slam.rviz"/>
 

I tried to remove,
<node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

but the tf changes to,


without removing the scanmatcher_to_base_footprint, I tried

$ roslaunch hector_quadrotor_demo indoor_kinect_slam_gazebo_hector_mapping.launch

$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmapviz:=false rtabmap_args:="--delete_db_on_start" rgb_topic:=/camera/rgb/image_raw depth_registered_topic:=/camera/depth/image_raw camera_info_topic:=/camera/rgb/camera_info visual_odometry:=false odom_topic:=/scanmatch_odom subscribe_scan:=true scan_topic:=/scan


The rosgraph and tf,




rtabmap is not subscribing to /scan topic.

You asked me to change the tf tree to,
you should have /world -> /map -> /scanmatch_odom -> /base_footprint.

where you refering to /scanmatcher_frame when you mentioned, /scanmatch_odom frame?
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
Hi boon,

I checked again the demo_hector_mapping.launch file, and the TF tree is:



I was wrong, you need "scanmatcher_to_base_footprint" node. However, the "world_to_map" would be:
<node pkg="tf" type="static_transform_publisher" name="world_to_map" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /world /map 100" />
as rtabmap will publish /map -> /hector_map transform.

For the /scan topic, there is maybe an error in rgbd_mapping.launch. I suggest to launch rtabmap in your launch file like that (inspired from demo_hector_mapping.launch):
<group ns="rtabmap">
    <!-- args: "delete_db_on_start" parameter deletes database on start -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
	  <param name="frame_id"            type="string" value="base_footprint"/>
	  <param name="subscribe_depth"     type="bool"   value="true"/>
	  <param name="subscribe_laserScan" type="bool"   value="true"/>
	
          <!-- Inputs -->
	  <remap from="odom"            to="/scanmatch_odom"/>
	  <remap from="scan"            to="/scan"/>
	  <remap from="rgb/image"       to="/camera/rgb/image_raw"/>
  	  <remap from="depth/image"     to="/camera/depth/image_raw"/>
  	  <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>

	  <!-- RTAB-Map's parameters -->
	  <param name="LccIcp/Type"                  type="string" value="2"/> 
          <param name="RGBD/OptimizeSlam2D"          type="string" value="true"/>
          <param name="RGBD/LocalLoopDetectionSpace" type="string" value="true"/>
	  <param name="LccIcp2/CorrespondenceRatio"  type="string" value="0.25"/>
	  <param name="LccBow/MaxDepth"              type="string" value="10.0"/>      
	  <param name="LccBow/InlierDistance"        type="string" value="0.1"/>
          <param name="LccBow/MinInliers"            type="string" value="10"/> 
    </node>
</group>

cheers
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
This post was updated on .
I updated the launch file as follows,
<?xml version="1.0"?>

<launch>
   
  <!-- Start Gazebo with wg world running in (max) realtime -->
    <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">    
    <arg name="world_name" value="$(find chefbot_gazebo)/worlds/complete_hotel.sdf"/>
  </include>
   
  <!-- Spawn simulated quadrotor uav -->
  <include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch" >
    <arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_hokuyo_utm30lx_kinect.gazebo.xacro"/>
    
  </include>
   
  <node pkg="tf" type="static_transform_publisher" name="world_to_map" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /world /map 100" />

  <node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

  <!-- Odometry from laser scans -->
  <!-- We use Hector mapping to generate odometry for us -->
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping">
    
    <!-- Frame names -->
    <param name="map_frame" value="hector_map" />
    <param name="base_frame" value="base_footprint" />
    <param name="odom_frame" value="odom" />
    
    <!-- Tf use -->
    <param name="pub_map_odom_transform" value="false"/>
    <param name="pub_map_scanmatch_transform" value="true"/>
    <param name="pub_odometry" value="true"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.050"/>
    <param name="map_size" value="2048"/>
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="map_update_angle_thresh" value="0.06" />
    
    <!-- Advertising config --> 
    <param name="scan_topic" value="/scan"/>
  </node>
 
   <group ns="rtabmap">
    <!-- args: "delete_db_on_start" parameter deletes database on start -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
	  <param name="frame_id"            type="string" value="base_footprint"/>
	  <param name="subscribe_depth"     type="bool"   value="true"/>
	  <param name="subscribe_laserScan" type="bool"   value="true"/>
	
          <!-- Inputs -->
	  <remap from="odom"            to="/scanmatch_odom"/>
	  <remap from="scan"            to="/scan"/>
	  <remap from="rgb/image"       to="/camera/rgb/image_raw"/>
  	  <remap from="depth/image"     to="/camera/depth/image_raw"/>
  	  <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>

	  <!-- RTAB-Map's parameters -->
	  <param name="LccIcp/Type"                  type="string" value="2"/> 
          <param name="RGBD/OptimizeSlam2D"          type="string" value="true"/>
          <param name="RGBD/LocalLoopDetectionSpace" type="string" value="true"/>
	  <param name="LccIcp2/CorrespondenceRatio"  type="string" value="0.25"/>
	  <param name="LccBow/MaxDepth"              type="string" value="10.0"/>      
	  <param name="LccBow/InlierDistance"        type="string" value="0.1"/>
          <param name="LccBow/MinInliers"            type="string" value="10"/> 
    </node>
</group>


  <!-- Start rviz visualization with preset config -->
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find hector_quadrotor_demo)/rviz_cfg/indoor_slam.rviz"/>
   
   
</launch>

The tf and rosgraph,




Now, the rtabmap subscribes to /scan topic but no message is received in /rtabmap/cloud_map topic.
rtabmap is not publishing /map -> /hector_map transform and I get the warning,

Parameter name changed: LccBow/MaxDepth -> LccReextract/MaxDepth. Please update your launch file accordingly.

Since there is no transform between world and hector_map frame, I also get status error in rviz


I installed rtabmap_ros with apt-get,
$ sudo apt-get install ros-indigo-rtabmap-ros
would it be required to build the package manually to include latest changes?
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
Well, we are close to have something working! The frame /map -> /hector_map is not published because rtabmap is waiting for some input topics. Do you see some rtabmap updates at 1 Hz in the console? If no, verify that all input topics are published:
$rostopic hz /scanmatch_odom
$rostopic hz /scan
$rostopic hz /camera/rgb/image_raw
$rostopic hz /camera/depth/image_raw
$rostopic hz /camera/rgb/camera_info

The indigo binaries should be fine. The warning is just informative, you can replace "LccBow/MaxDepth" by "LccReextract/MaxDepth".
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
All the input topic are being published,
$rostopic hz /scanmatch_odom
$rostopic hz /scan
$rostopic hz /camera/rgb/image_raw
$rostopic hz /camera/depth/image_raw
$rostopic hz /camera/rgb/camera_info

But no messages in rtabmap topics,
$ rostopic hz /rtabmap/proj_map
$ rostopic hz /rtabmap/grid_map
$ rostopic hz /rtabmap/cloud_map
$ rostopic hz /rtabamap/info
$ rostopic hz /rtabmap/mapData

and so the frame /map -> /hector_map is not being published
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
This post was updated on .
I tried your launch file and it works (I used "quadrotor_with_asus_with_hokuyo_utm30lx.gazebo.xacro" though). I don't know how to move the quadrotor (I tried pr2_keyboard on /cmd_vel but nothing happened), so I couldn't test more than this screenshot, but we can see the point cloud. To avoid the map increasing when not moving, I also added in the launch under rtabmap node the parameters "RGBD/AngularUpdate" and "RGBD/LinearUpdate". Note that this simulated environment has poor visual features (see next image, only four features! normally it should have at least 400 features), rtabmap would not find any loop closure in this environment.



Here is my launch file:
UPDATE: Added laser scan filter to remove obstacles "on" the robot.
<launch>
   
  <!-- Start Gazebo with wg world running in (max) realtime -->
    <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">    
    <arg name="world_name" value="$(find chefbot_gazebo)/worlds/complete_hotel.sdf"/>
  </include>
   
  <!-- Spawn simulated quadrotor uav -->
  <include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch" >
    <arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_asus_with_hokuyo_utm30lx.gazebo.xacro"/>
    
  </include>
   
  <node pkg="tf" type="static_transform_publisher" name="world_to_map" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /world /map 100" />

  <node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

  <node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter">
        <rosparam>
            scan_filter_chain:
            - name: range
              type: LaserScanRangeFilter
              params:
                lower_threshold: 0.3
                upper_threshold: .inf
        </rosparam>
        <remap from="scan" to="/scan" />
        <remap from="scan_filtered" to="/scan_filtered" />
  </node>

  <!-- Odometry from laser scans -->
  <!-- We use Hector mapping to generate odometry for us -->
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping">
    
    <!-- Frame names -->
    <param name="map_frame" value="hector_map" />
    <param name="base_frame" value="base_footprint" />
    <param name="odom_frame" value="odom" />
    
    <!-- Tf use -->
    <param name="pub_map_odom_transform" value="false"/>
    <param name="pub_map_scanmatch_transform" value="true"/>
    <param name="pub_odometry" value="true"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.050"/>
    <param name="map_size" value="2048"/>
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="map_update_angle_thresh" value="0.06" />
    
    <!-- Advertising config --> 
    <param name="scan_topic" value="/scan_filtered"/>
  </node>
 
   <group ns="rtabmap">
    <!-- args: "delete_db_on_start" parameter deletes database on start -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
	  <param name="frame_id"            type="string" value="base_footprint"/>
	  <param name="subscribe_depth"     type="bool"   value="true"/>
	  <param name="subscribe_laserScan" type="bool"   value="true"/>
	
          <!-- Inputs -->
	  <remap from="odom"            to="/scanmatch_odom"/>
	  <remap from="scan"            to="/scan_filtered"/>
	  <remap from="rgb/image"       to="/camera/rgb/image_raw"/>
  	  <remap from="depth/image"     to="/camera/depth/image_raw"/>
  	  <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>

	  <!-- RTAB-Map's parameters -->
	  <param name="LccIcp/Type"                  type="string" value="2"/> 
          <param name="RGBD/OptimizeSlam2D"          type="string" value="true"/>
          <param name="RGBD/LocalLoopDetectionSpace" type="string" value="true"/>
	  <param name="LccIcp2/CorrespondenceRatio"  type="string" value="0.25"/>
	  <param name="LccBow/MaxDepth"              type="string" value="10.0"/>      
	  <param name="LccBow/InlierDistance"        type="string" value="0.1"/>
          <param name="LccBow/MinInliers"            type="string" value="10"/> 
          <param name="RGBD/AngularUpdate"           type="string" value="0.1"/>
          <param name="RGBD/LinearUpdate"            type="string" value="0.1"/>
    </node>
</group>


  <!-- Start rviz visualization with preset config -->
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find hector_quadrotor_demo)/rviz_cfg/indoor_slam.rviz"/>
   
   
</launch>

Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
I tried your launch file too, but without success. I could n't understand where the problem could be.


Meanwhile I came across, creating octomaps with moveIt. In that when I launch motion planning plugin I could see octomap in the beginning, but when I try to move the quadrotor, the octomap is not updating. So failure on that side too.


Green quadrotor - initial position(octomap exists), Red quadrotor - position after motion(octomap is not generated along the motion path)

Can it be that the laptop doesn't have enough processing power because it hangs a bit while I launch the simulations?
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
It is strange, you could try with the rtabmap version from source (see here for instructions). I tried again and this is what I get (finally moving with teleop_pr2_keyboard... a vertical twist was required to take off):
rostopic pub /cmd_vel geometry_msgs/Twist "linear:
  x: 0.0
  y: 0.0
  z: 0.5
angular:
  x: 0.0
  y: 0.0
  z: 0.0"

Note the high CPU usage from gazebo. My computer is at 100% CPU on every core. I couldn't test octomap as my laptop is lagging too much wih Gazebo.



Then, if I open the generated database in rtabmap standalone. Note that there is no loop closures detected, it is pure odometry computed by hector_mapping.



Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

boon
I successfully installed rtabmap from source by following the instructions in,
https://github.com/introlab/rtabmap_ros

But when I try to install the 'rtabmap_ros' package in '~/catkin_ws', I get the error

CMake Error at /opt/ros/indigo/share/catkin/cmake/catkin_workspace.cmake:89 (message):
  This workspace contains non-catkin packages in it, and catkin cannot build
  a non-homogeneous workspace without isolation.  Try the
  'catkin_make_isolated' command instead.

I tried to install it in '~/catkin_ws/src' then I get an error,

CMake Error at rtabmap_ros/CMakeLists.txt:21 (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.10.9) 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.


Reply | Threaded
Open this post in threaded view
|

Re: rtabmap with octomap and hector slam

matlabbe
Administrator
Hi,

You have to follow exactly the instructions from https://github.com/introlab/rtabmap_ros#build-from-source

Especially 2) where "rtabmap" libraries are cloned in a directory outside the catkin workspace. It uses plain cmake to build so if you clone in catkin_ws, you will have "catkin_make_isolated" error. Then install in your "devel" folder of your catkin_ws.

For rtabmap_ros, you should clone it in the "src" folder of your catkin workspace. Then "catkin_make" at the catkin workspace root should work. The "FindRTABMap.cmake" should be found by cmake if the "rtabmap" libraries are correctly installed in ~/catkin_ws/devel.

Well, the installation instructions assume that you have setup your ROS workspace using this tutorial. The workspace path is ~/catkin_ws and your ~/.bashrc contains:
source /opt/ros/indigo/setup.bash
source ~/catkin_ws/devel/setup.bash

The "source ~/catkin_ws/devel/setup.bash" will make able catkin_make to find RTAB-Map libraries installed in "~/catkin_ws/devel".

cheers