git commit -m "first commit"
This commit is contained in:
27
navigations/robot_localization/launch/dual_ekf_navsat_example.launch
Executable file
27
navigations/robot_localization/launch/dual_ekf_navsat_example.launch
Executable file
@@ -0,0 +1,27 @@
|
||||
<!--
|
||||
This launch file provides an example of how to work with GPS data using robot_localization. It runs three nodes:
|
||||
(1) An EKF instance that fuses odometry and IMU data and outputs an odom-frame state estimate
|
||||
(2) A second EKF instance that fuses the same data, but also fuses the transformed GPS data from (3)
|
||||
(3) An instance of navsat_transform_node, which takes in GPS data and produces pose data that has been
|
||||
transformed into your robot's world frame (here, map). The node produces a map-frame state estimate.
|
||||
|
||||
The first EKF instance produces the odom->base_link transform. The second EKF produces the map->odom transform,
|
||||
but requires the odom->base_link transform from the first instance in order to do so. See the
|
||||
params/dual_ekf_navsat_example.yaml file for parameter specification.
|
||||
-->
|
||||
|
||||
<launch>
|
||||
|
||||
<rosparam command="load" file="$(find robot_localization)/params/dual_ekf_navsat_example.yaml" />
|
||||
|
||||
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_se_odom" clear_params="true"/>
|
||||
|
||||
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_se_map" clear_params="true">
|
||||
<remap from="odometry/filtered" to="odometry/filtered_map"/>
|
||||
</node>
|
||||
|
||||
<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform" clear_params="true">
|
||||
<remap from="odometry/filtered" to="odometry/filtered_map"/>
|
||||
</node>
|
||||
|
||||
</launch>
|
||||
Reference in New Issue
Block a user