navigation using rtab map

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

navigation using rtab map

shashank
i have created two grid map
conf1: zed camera +laser
the screen short below shows the proj_map generated by the rtab map .

conf2: only Zed_camera


The second image there seems to be no ray tracing ( i cannot see white spaces in front of my robot) . So how does i navigate in this map . I mean to say what strategy does rtabmap use to navigate in the map  ? Is it different when there is laser and when there is no laser?

thanks
Reply | Threaded
Open this post in threaded view
|

Re: navigation using rtab map

matlabbe
Administrator
Hi,

if you are on Kinetic (or latest code), proj_map is deprecated (use grid_map). It outputs exactly the same as grid_map. The first map is created only by laser scan. You should have a warning at start telling that as a laser scan is subscribed, the map is created by default from it. With parameter "Grid/FromDepth", you can switch between laser ("false") or zed ("true"). For example with the zed+laser setup, if you set "Grid/FromDepth" to "true", you will get the second map on grid_map.

When the grid_map is created from depth (Grid/FromDepth=true), there is no ray tracing. The camera should see the ground to mark empty cells. With a stereo camera indoor, it generally doesn't work (no point cloud on the ground because there is no texture). To do ray tracing, you should subscribe to /rtabmap/octomap_grid. A 3D octomap will be created from the ZED, then projected on the ground to get the 2D map. Ray tracing in 3D will be done, so a lot more computation power is required.

Using only the ZED, you could use depthimage_to_laserscan or pointcloud_to_laserscan node to create a fake laser scan for rtabmap, then 2D ray tracing will be done like with your laser above.

cheers
Reply | Threaded
Open this post in threaded view
|

Re: navigation using rtab map

shashank
Hi ,
I am tried woring with different map generated by rtabmap . rtabmap/Proj_map doesnot work it doesn't clear of dynamic obstacle( as you mentioned ) .   I have a core i7 (quad) with 16 GB of ram on my robot so i think no compute issues.
So i did subscribe to /rtabmap/octomap_grid it does ray tracing and clear off the dynamic obstacle  .
What topic (point cloud) did you use to  create  /rtabmap/octomap_grid ( projection map ) ? I want to know this because in the  /rtabmap/octomap_grid i think topic ground  plane is indicated as an obstacle in occupancy grid map. Can i do some kind of filtering in Z axis so that it eliminates the ground plane before it create the projected map.
I am currently using laser for local obstacle avoidance/cost map generation . The planning in global cost map become problematic because of presence of obstacle .( Whole global costmap is filled with black colour)

Few more things off the topic
1. If i use odom from other source and just perform mapping from rtabmap will it generate a pose graph and do loop closure and pose graph optimization in it i .Idea being to minimise the drift in odometry when the loop closes .
2.  Can i merge different generated map using rtabmap application without involving ros ??

thanks a lot for support
Reply | Threaded
Open this post in threaded view
|

Re: navigation using rtab map

matlabbe
Administrator
Hi,

I tried with 0.11.13 (rtabmap kinetic version in shadow-fixed repository) with a kinect xbox 360 and here some results. Commands used:
$ rosrun freenect_launch freenect.launch depth_registration:=true
$ roslaunch rtabmap_ros rtabmap.launch rviz:=true rtabmapviz:=false rtabmap_args:="--delete_db_on_start --Odom/AlignWithGround true"

/rtabmap/grid_map with object over ground that the camera can actually see (if the object is not here):


/rtabmap/grid_map without object (cells are cleared):


/rtabmap/grid_map with object over ground that the camera cannot actually see (if the object is not here):


/rtabmap/grid_map without object (cells are not cleared):


Now, same thing but with /rtabmap/octomap_grid:


/rtabmap/octomap_grid without object (cells are cleared!):


Normally (as "Grid/3DGroundIsObstacle" is false by default), the ground should not be an obstacle, as shown in the two last screenshots above. Here for example with Grid/3DGroundIsObstacle to true:
$ roslaunch rtabmap_ros rtabmap.launch rviz:=true rtabmapviz:=false rtabmap_args:="--delete_db_on_start --Odom/AlignWithGround true --Grid/3DGroundIsObstacle true"


You can change the approach to segment the ground. If you just want to label all points below a fixed height as ground, set "Grid/NormalsSegmentation" to false. Example filtering all points below 5 cm:
$ roslaunch rtabmap_ros rtabmap.launch rviz:=true rtabmapviz:=false rtabmap_args:="--delete_db_on_start --Odom/AlignWithGround true --Grid/NormalsSegmentation false --Grid/MaxGroundHeight 0.05 --Grid/MapFrameProjection true"
I needed to set Grid/MapFrameProjection as I am using an hand-held camera (for which the distance to ground varies). Here showing the /rtabmap/cloud_ground and /rtabmap/cloud_obstacles for convenience:


For the last questions:
1. yes, it does it by default
2. With rtabmap standalone, it is not possible.

cheers,
Mathieu