Files
rf2o_laser_odometry/launch/rf2o_laser_odometry.launch

29 lines
1.5 KiB
XML

<!--
This node presents a fast and precise method to estimate the planar motion of a lidar
from consecutive range scans. It is very useful for the estimation of the robot odometry from
2D laser range measurements.
For more info please visit: http://mapir.isa.uma.es/work/rf2o
Requirements:
- 2D laser scan, publishing sensor_msgs::LaserScan
- TF transform from the laser to the robot base
- MRPT (http://www.mrpt.org/)
- Tested with v1.3 (official ubuntu release)
-->
<launch>
<node pkg="rf2o_laser_odometry" type="rf2o_laser_odometry_node" name="rf2o_laser_odometry" output="screen">
<param name="laser_scan_topic" value="/laser_scan"/> # topic where the lidar scans are being published
<param name="odom_topic" value="/odom_rf2o" /> # topic where tu publish the odometry estimations
<param name="publish_tf" value="false" /> # wheter or not to publish the tf::transform (base->odom)
<param name="base_frame_id" value="/base_link"/> # frame_id (tf) of the mobile robot base. A tf transform from the laser_frame to the base_frame is mandatory
<param name="odom_frame_id" value="/odom" /> # frame_id (tf) to publish the odometry estimations
<param name="init_pose_from_topic" value="/base_pose_ground_truth" /> # (Odom topic) Leave empty to start at point (0,0)
<param name="freq" value="6.0"/> # Execution frequency.
<param name="verbose" value="true" /> # verbose
</node>
</launch>