navsat_transform_node takes as input a nav_msgs/Odometry message (usually the output of ekf_localization_node or ukf_localization_node), a sensor_msgs/Imu.html containing an accurate estimate of your robot’s heading, and a sensor_msgs/NavSatFix.html message containing GPS data. It produces an odometry message in coordinates that are consistent with your robot’s world frame. This value can be directly fused into your state estimate.
Note
If you fuse the output of this node with any of the state estimation nodes in robot_localization, you should make sure that the odomN_differential setting is false for that input.
The real-valued frequency, in Hz, at which navsat_transform_node checks for new sensor_msgs/NavSatFix.html messages, and publishes filtered sensor_msgs/NavSatFix.html when publish_filtered_gps is set to true.
The time, in seconds, to wait before calculating the transform from GPS coordinates to your robot’s world frame.
Enter the magnetic declination for your location. If you don’t know it, see http://www.ngdc.noaa.gov/geomag-web (make sure to convert the value to radians). This parameter is needed if your IMU prodives its orientation with respect to the magnetic north.
Your IMU should read 0 for yaw when facing east. If it doesn’t, enter the offset here (desired_value = offset + sensor_raw_value). For example, if your IMU reports 0 when facing north, as most of them do, this parameter would be pi/2 (~1.5707963). This parameter changed in version 2.2.1. Previously, navsat_transform_node assumed that IMUs read 0 when facing north, so yaw_offset was used acordingly.
If this is true, the nav_msgs/Odometry message produced by this node has its pose Z value set to 0.
If true, navsat_transform_node will also transform your robot’s world frame (e.g., map) position back to GPS coordinates, and publish a sensor_msgs/NavSatFix.html message on the /gps/filtered topic.
If this is true, navsat_transform_node will broadcast the transform between the UTM grid and the frame of the input odometry data. See Published Transforms below for more information.
If true, navsat_transform_node will not get its heading from the IMU data, but from the input odometry message. Users should take care to only set this to true if your odometry message has orientation data specified in an earth-referenced frame, e.g., as produced by a magnetometer. Additionally, if the odometry source is one of the state estimation nodes in robot_localization, the user should have at least one source of absolute orientation data being fed into the node, with the _differential and _relative parameters set to false.
If true, navsat_transform_node will wait to get a datum from either:
Enter search terms or a module, class or function name.