ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Found this thread: http://official-rtab-map-forum.67519.x6.nabble.com/Proj-map-min-obstacles-height-td2866.html
Try these settings I tested them in my sim. RTABMap should be publishing to "/rtabmap/proj_map":
<param name="Grid/FromDepth" type="bool" value="true"/>
<param name="Grid/MaxGroundHeight" type="string" value="0.2"/>
<param name="Grid/MaxObstacleHeight" type="string" value="2"/>
<param name="Grid/NormalsSegmentation" type="string" value="false"/>
Here's a the relevant part of my launch file for reference:
<rosparam command="load" file="$(find frc_robot)/config/slam.yaml"/>
<group ns="rtabmap">
<node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
<remap from="rgb/image" to="/$(arg camera_frame)/rgb/image_raw"/>
<remap from="depth/image" to="/$(arg camera_frame)/depth/image_raw"/>
<remap from="rgb/camera_info" to="/$(arg camera_frame)/rgb/camera_info"/>
<remap from="rgbd_image" to="rgbd_image"/> <!-- Output -->
</node>
<!-- SLAM -->
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<remap from="scan" to="/scan"/>
Ignore these params below. I'm using Hector_Slam for localization.
<param name="odom_frame_id" type="string" value="map"/>
<param name="odom_tf_linear_variance" type="double" value="0.0005"/>
<param name="odom_tf_angular_variance" type="double" value="0.0005"/>
</node>
</group>
And my YAML file:
rtabmap:
rtabmap:
frame_id: base_link
map_frame_id: map
odom_frame_id: odom
subscribe_depth: false
subscribe_rgb: false
subscribe_rgbd: true
subscribe_scan: true
publish_tf: false
Reg/Strategy: 2
Reg/Force3DoF: true
RGBD/ProximityBySpace: false
RGBD/ProximityPathMaxNeighbors: 10
Grid/Scan2dUnknownSpaceFilled: true
Grid/FromDepth: true
Grid/MaxGroundHeight: 0.2
Grid/MaxObstacleHeight: 2.0
Grid/NormalsSegmentation: false
2 | No.2 Revision |
Found this thread: http://official-rtab-map-forum.67519.x6.nabble.com/Proj-map-min-obstacles-height-td2866.htmlhttp://official-rtab-map-forum.206.s1.nabble.com/Proj-map-min-obstacles-height-td2866.html
Try these settings I tested them in my sim. RTABMap should be publishing to "/rtabmap/proj_map":
<param name="Grid/FromDepth" type="bool" value="true"/>
<param name="Grid/MaxGroundHeight" type="string" value="0.2"/>
<param name="Grid/MaxObstacleHeight" type="string" value="2"/>
<param name="Grid/NormalsSegmentation" type="string" value="false"/>
Here's a the relevant part of my launch file for reference:
<rosparam command="load" file="$(find frc_robot)/config/slam.yaml"/>
<group ns="rtabmap">
<node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
<remap from="rgb/image" to="/$(arg camera_frame)/rgb/image_raw"/>
<remap from="depth/image" to="/$(arg camera_frame)/depth/image_raw"/>
<remap from="rgb/camera_info" to="/$(arg camera_frame)/rgb/camera_info"/>
<remap from="rgbd_image" to="rgbd_image"/> <!-- Output -->
</node>
<!-- SLAM -->
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<remap from="scan" to="/scan"/>
Ignore these params below. I'm using Hector_Slam for localization.
<param name="odom_frame_id" type="string" value="map"/>
<param name="odom_tf_linear_variance" type="double" value="0.0005"/>
<param name="odom_tf_angular_variance" type="double" value="0.0005"/>
</node>
</group>
And my YAML file:
rtabmap:
rtabmap:
frame_id: base_link
map_frame_id: map
odom_frame_id: odom
subscribe_depth: false
subscribe_rgb: false
subscribe_rgbd: true
subscribe_scan: true
publish_tf: false
Reg/Strategy: 2
Reg/Force3DoF: true
RGBD/ProximityBySpace: false
RGBD/ProximityPathMaxNeighbors: 10
Grid/Scan2dUnknownSpaceFilled: true
Grid/FromDepth: true
Grid/MaxGroundHeight: 0.2
Grid/MaxObstacleHeight: 2.0
Grid/NormalsSegmentation: false