Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
This post was updated on Jan 24, 2021; 7:10pm.
This is my launch file.
<launch> <include file="$(find realsense2_camera)/launch/rs_d400_and_t265.launch" /> <include file="$(find rtabmap_ros)/launch/rtabmap.launch" > <arg name="odom_topic" value="/t265/odom/sample"/> <arg name="frame_id" value="t265_link"/> <arg name="rgbd_sync" value="true"/> <arg name="depth_topic" value="/d400/aligned_depth_to_color/image_raw"/> <arg name="rgb_topic" value="/d400/color/image_raw"/> <arg name="camera_info_topic" value="/d400/color/camera_info"/> <arg name="approx_rgbd_sync" value="false"/> <arg name="visual_odometry" value="false"/> <param name="Reg/Strategy" type="string" value="0"/> <param name="Mem/UseOdomGravity" value="true"/> <param name="Optimizer/GravitySigma" value="0.3"/> <param name="Grid/MaxGroundHeight" type="string" value="0.2"/> <!-- all points below 20 cm are ground --> <param name="Grid/MaxObstacleHeight" type="string" value="2"/> <!-- all points above 20 cm and below 2 m are obstacles --> <param name="Grid/NormalsSegmentation" type="string" value="false"/> <!-- Use simple passthrough to filter the ground instead of normals segmentation --> </include> </launch> When I launch it I get a long list of parameters that cant be found. The parameters I set in the launch file above are all not found. Parameter Reg/Strategy not found Parameter Optimizer/GravitySigma not found Parameter Mem/UseOdomGravity not found Parameter Grid/MaxGroundHeight not found Parameter Grid/MaxObstacleHeight not found Everything seems to work but I'm trying to optimize. What am I doing wrong? I can share my src on google drive. (ps. for some reason when I post my message here it's removing the lines and it shows up as blank space in the launch file above.) |
Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
I think im figuring it out. parameters are persistent between launches. I can use rosparam to set the parameters or set them under the rtabmap node.
|
Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
Administrator
|
In reply to this post by ryleymcc
Hi,
When using rtabmap.launch, you cannot set RTAB-Map's parameters like that. For convenience, we added an argument named "rtabmap_args" to feed parameters liek the standalone way (note that this is also how we can delete the default database on start "--delete_db_on_start"): <launch> <include file="$(find realsense2_camera)/launch/rs_d400_and_t265.launch" /> <include file="$(find rtabmap_ros)/launch/rtabmap.launch" > <arg name="odom_topic" value="/t265/odom/sample"/> <arg name="frame_id" value="t265_link"/> <arg name="rgbd_sync" value="true"/> <arg name="depth_topic" value="/d400/aligned_depth_to_color/image_raw"/> <arg name="rgb_topic" value="/d400/color/image_raw"/> <arg name="camera_info_topic" value="/d400/color/camera_info"/> <arg name="approx_rgbd_sync" value="false"/> <arg name="visual_odometry" value="false"/> <arg name="rtabmap_args" value=" --delete_db_on_start --Reg/Strategy 0 --Mem/UseOdomGravity true ---Optimizer/GravitySigma 0.3 --Grid/MaxGroundHeight 0.2 --Grid/MaxObstacleHeight 2 --Grid/NormalsSegmentation false"/> </include> </launch> cheers, Mathieu |
Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
Thanks A LOT!
|
Free forum by Nabble | Edit this page |