0
$\begingroup$

Rosanswers logo

I've been trying to get RTAB-Map going in simulation using a depth camera plugin. I've been able to get it all working, however it seems that RTAB-Map uses its default parameters, rather than the ones loaded in my launch file. For example, I want to simulate the ZED camera which has depth range 1m -> 20m. So, I'd set Grid/DepthMin and Grid/DepthMax to 1 and 20 respectively:

<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
  ...
  <param name="Grid/DepthMin" type="string" value="1.0"/>
  <param name="Grid/DepthMax" type="string" value="20.0"/>
  ...
</node>

However, when viewing the parameter server after launching the node, there are two instances of these parameters: one under the rtabmap namespace (with the correct value), and one in the global namespace (with default values of 0 and 4). It seems to me that the rtabmap node is loading its own parameters into the global namespace and using them, rather than using the ones set in the launch file (rviz shows a maximum range of approx 4m for the MapCloud).

I've tried loading the parameters into the global namespace, and then launching rtabmap, but they just get overwritten with the defaults again. Just to be clear, I'm using my own launch file and launching the node itself, not launching through rtabmap_ros/rtabmap.launch. All parameters seem to be default, not just these two used as examples.

Is there anything basic that I could be missing which would cause rtabmap to use default values?

Cheers.


Originally posted by ufr3c_tjc on ROS Answers with karma: 885 on 2017-11-01

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Rtabmap reads private parameters and write back public parameters for convenience so that other nodes don't need to know rtabmap node name to modify parameters (at least nodes should be in the same namespace). Rtabmap should copy your private parameters in the public ones. I tried your example:

$ roslaunch test.launch

SUMMARY
========

PARAMETERS
 * /rosdistro: indigo
 * /rosversion: 1.11.21
 * /rtabmap/Grid/DepthMax: 20.0
 * /rtabmap/Grid/DepthMin: 1.0

NODES
  /
    rtabmap (rtabmap_ros/rtabmap)
...
[ INFO] [1509548641.907457423]: Setting RTAB-Map parameter "Grid/DepthMax"="20.0"
[ INFO] [1509548641.908350452]: Setting RTAB-Map parameter "Grid/DepthMin"="1.0"

We can see that rtabmap set the correct parameters. Now for the private and public parameters:

$ rosparam get /Grid/DepthMax
'20.0'

$ rosparam get /rtabmap/Grid/DepthMax
'20.0'

Both are 20. Note that if we want to change this value online, we should change the public one, then call service update_parameters.

The rtabmap_ros/MapCloud plugin has its own parameters, totally independent of rtabmap. Also, Grid/DepthMax will affect cloud_map (PointCloud2) topic, not the cloud shown by rtabmap_ros/MapCloud plugin.

cheers

Mathieu


Originally posted by matlabbe with karma: 6409 on 2017-11-01

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by ufr3c_tjc on 2017-11-01:
I've come back to it today and now it's accepting my parameters correctly. Thanks for the explanation on why there's two sets. Also good work with rtab, its really good stuff.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.