Skip to content
Permalink
Branch: master
Find file Copy path
Find file Copy path
Fetching contributors…
Cannot retrieve contributors at this time
84 lines (67 sloc) 4.85 KB
<launch>
<group ns="rtabmap">
<node name="rgbd_relay" type="rgbd_relay" pkg="rtabmap_ros">
<remap from="rgbd_image" to="/robot/rgbd_image/compressed"/>
<remap from="/robot/rgbd_image/compressed_relay" to="rgbd_image_relay"/>
<param name="uncompress" value="true"/>
</node>
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="frame_id" type="string" value="base_link"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="approx_sync" type="bool" value="true"/>
<param name="queue_size" type="int" value="30"/>
<remap from="odom" to="/robot/odom"/>
<remap from="rgbd_image" to="rgbd_image_relay"/>
<!-- RTAB-Map's parameters -->
<param name="Rtabmap/DetectionRate" type="string" value="0"/> <!-- no filtering, processing done at the speed of incoming data -->
<param name="Rtabmap/TimeThr" type="string" value="0"/> <!-- offline works much faster -->
<param name="RGBD/AngularUpdate" type="string" value="0.01"/>
<param name="RGBD/LinearUpdate" type="string" value="0.01"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Vis/MinInliers" type="string" value="5"/>
<param name="Vis/FeatureType" type="string" value="0"/> <!-- use SURF -->
<param name="RGBD/OptimizeMaxError" type="string" value="15"/> <!-- should be 0 if Optimizer/Robust is true -->
<param name="RGBD/NeighborLinkRefining" type="string" value="false"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/> <!-- Referred paper did only global loop closure detection -->
<param name="RGBD/ProximityByTime" type="string" value="false"/>
<param name="Reg/Strategy" type="string" value="0"/> <!-- no real laser scan, so no ICP -->
<param name="Vis/MaxDepth" type="string" value="4.0"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.45"/>
<param name="Kp/TfIdfLikelihoodUsed" type="string" value="false"/>
<param name="Bayes/FullPredictionUpdate" type="string" value="true"/>
<param name="Kp/DetectorStrategy" type="string" value="0"/> <!-- use SURF -->
<param name="Kp/MaxFeatures" type="string" value="400"/>
<param name="SURF/Upright" type="string" value="true"/> <!-- we operate in plane, so no need to calculate rotation -->
<param name="SURF/HessianThreshold" type="string" value="300"/> <!-- helps to get features in low contrast frames -->
<param name="Optimizer/Strategy" type="string" value="0"/> <!-- TORO is the most stable for multi-session mapping -->
<param name="Optimizer/Robust" type="string" value="false"/>
<param name="Optimizer/Iterations" type="string" value="100"/>
<param name="Optimizer/Epsilon" type="string" value="0.00001"/>
<param name="Kp/IncrementalFlann" type="string" value="true"/> <!-- Referred paper didn't use incremental FLANN -->
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Grid/3D" type="string" value="false"/>
<param name="Grid/RayTracing" type="string" value="true"/>
<param name="Grid/RangeMax" type="string" value="3.0"/>
<param name="Grid/MaxGroundHeight" type="string" value="0.05"/>
<param name="Grid/MaxObstacleHeight" type="string" value="0.3"/>
<param name="Grid/FromDepth" type="string" value="true" />
<param name="Mem/SaveDepth16Format" type="string" value="false" />
</node>
<!-- Visualisation RTAB-Map -->
<node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d /home/boredman/.ros/rtabmapGUI.ini" output="screen">
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="subscribe_stereo" type="bool" value="false"/>
<param name="subscribe_scan" type="bool" value="false"/>
<param name="subscribe_scan_cloud" type="bool" value="false"/>
<param name="frame_id" type="string" value="base_link"/>
<param name="odom_frame_id" type="string" value="odom"/>
<param name="queue_size" type="int" value="30"/>
<param name="approx_sync" type="bool" value="true"/>
<remap from="odom" to="/robot/odom"/>
<remap from="info" to="/rtabmap/info"/>
<remap from="mapData" to="/rtabmap/mapData"/>
<remap from="rgbd_image" to="/rtabmap/rgbd_image_relay"/>
</node>
</group>
</launch>
You can’t perform that action at this time.