52 lines
3.4 KiB
XML
Executable File
52 lines
3.4 KiB
XML
Executable File
<!--
|
|
This node needs to know the values of three variables in order to function:
|
|
|
|
(1) A world-referenced heading (yaw). The node assumes an ENU standard for heading, with 0 facing east, though it
|
|
can support any heading.
|
|
(2) Odometry data that gives the robot's current pose in its own world coordinate frame (typically map or odom)
|
|
(3) A latitude/longitude/altitude.
|
|
|
|
These three items allow us to compute a transform from the global frame to your robot's local frame. There are
|
|
several means of providing them, though keep in mind that these modes are typically mutually exclusive.
|
|
(1) World-referenced yaw can be provided by:
|
|
(a) an IMU in a sensor_msgs/Imu message (topic is /imu/data/)
|
|
(b) the heading in the nav_msgs/Odometry message in (2) below can be used. To enable this behavior, set the
|
|
use_odometry_yaw parameter to true, and set the delay parameter to some small value (~3 seconds). Be
|
|
careful, though: this heading must still be globally referenced, so if your state estimation node always
|
|
starts with a 0 heading, you CAN NOT use this option.
|
|
(c) the "datum" service. See the template parameter file (params/navsat_transform_template.yaml).
|
|
(2) The odometry data, which needs to have a valid frame_id, can be provided by:
|
|
(a) a nav_msgs/Odometry message from your robot_localization state estimation node.
|
|
(b) the "datum" service (all odometry variables are assumed to be 0 in this case). See the template
|
|
parameter file.
|
|
(3) The latitude, longitude, and altitude can be provided by:
|
|
(a) a sensor_msgs/NavSatFix message
|
|
(b) the "datum" service. See the template parameter file.
|
|
(4) Alternatively, at any time, the user can send a robot_localization/SetDatum service message to the "datum"
|
|
service. This will manually set the latitude, longitude, altitude, and world-referenced heading, and will
|
|
assume an odometry message containing all zeros. This will effectively set the origin at the specified
|
|
lat/long, with the X-axis aligned with east. The user can set this datum via the "datum" service, or via the
|
|
launch file. If the wait_for_datum parameter is set to true, then the node will attempt to use the datum
|
|
parameter. If the parameter is not set, it will wait until it receives a service call.
|
|
|
|
The output of this node is an odometry message that contains the GPS data transformed into the robot's world
|
|
coordinate frame (i.e., the frame specified by input (2)'s frame_id), or the coordinate frame defined by the
|
|
message sent to the "datum" service. Optionally, the node can also produce a NavSatFix message corresponding
|
|
to the filtered odometry, transformed back into lat/long coordinates. The node can also optionally publish the
|
|
transform from the UTM frame the the world frame.
|
|
-->
|
|
|
|
<launch>
|
|
<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" clear_params="true">
|
|
<rosparam command="load" file="$(find robot_localization)/params/navsat_transform_template.yaml" />
|
|
|
|
<!-- Placeholders for input remapping. Set your topic names as the "to" values.
|
|
<remap from="imu/data" to=""/>
|
|
<remap from="odometry/filtered" to=""/>
|
|
<remap from="gps/fix" to=""/>
|
|
-->
|
|
|
|
</node>
|
|
</launch>
|
|
|