#include <ros/ros.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
Go to the source code of this file.
Functions | |
void | computeOdomUtmTransform () |
Computes the transform from the odometry message's frame_id to the UTM message's frame_id. | |
void | gpsFixCallback (const sensor_msgs::NavSatFixConstPtr &msg) |
Callback for the GPS fix data. | |
void | imuCallback (const sensor_msgs::ImuConstPtr &msg) |
Callback for the IMU data. | |
int | main (int argc, char **argv) |
Waits until a transform is ready, then broadcasts it at a specified rate. | |
void | odomCallback (const nav_msgs::OdometryConstPtr &msg) |
Callback for the odom data. | |
void | utmCallback (const nav_msgs::OdometryConstPtr &msg) |
Callback for the UTM data. | |
Variables | |
bool | hasFix_ |
Whether or not the GPS fix is usable. | |
sensor_msgs::Imu * | latestImuMsg_ |
nav_msgs::Odometry * | latestOdomMessage_ |
nav_msgs::Odometry * | latestUtmMsg_ |
Used for calculating the utm_frame->odom_frame transform. | |
double | magneticDeclination_ |
Parameter that specifies the magnetic decliation for the robot's environment. | |
tf::StampedTransform * | odomUtmTransform_ |
The utm_frame->odom_frame transform object. | |
tf::Pose | originalOdomPose_ |
Used for updating the transform so as to remove altitude from the UTM measurements. | |
tf::Pose | originalUtmPose_ |
Used for updating the transform so as to remove altitude from the UTM measurements. | |
double | pitchOffset_ |
On level ground, your IMU should read 0 pitch. If it doesn't, this (parameterized) value gives the offset. | |
double | rollOffset_ |
On level ground, your IMU should read 0 roll. If it doesn't, this (parameterized) value gives the offset. | |
tf::TransformListener * | tfListener_ |
TF listener used for converting. | |
bool | transformGood_ |
Whether or not we've computed a good heading. | |
double | utmOdomTfPitch_ |
Stores the pitch we need to compute the transform. | |
double | utmOdomTfRoll_ |
Stores the roll we need to compute the transform. | |
double | utmOdomTfYaw_ |
Stores the yaw we need to compute the transform. | |
double | yawOffset_ |
Your IMU should read 0 when facing *magnetic* north. If it doesn't, this (parameterized) value gives the offset (NOTE: if you have a magenetic declination, use the parameter setting for that). | |
bool | zeroAltitude_ |
If this parameter is true, we continually update the transform using the current altitude from the UTM message. This allows users to receive a (nearly) zero Z measurement when they use the transform. |
void computeOdomUtmTransform | ( | ) |
Computes the transform from the odometry message's frame_id to the UTM message's frame_id.
The transform is computed from the odom frame to the UTM frame so that we don't accidentally attempt to give a second parent to the odom frame in the tf tree. Users may already have a parent for that frame_id, and we don't want to stomp on it.
Definition at line 107 of file utm_transform_node.cpp.
void gpsFixCallback | ( | const sensor_msgs::NavSatFixConstPtr & | msg | ) |
Callback for the GPS fix data.
Definition at line 280 of file utm_transform_node.cpp.
void imuCallback | ( | const sensor_msgs::ImuConstPtr & | msg | ) |
Callback for the IMU data.
Definition at line 252 of file utm_transform_node.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Waits until a transform is ready, then broadcasts it at a specified rate.
Definition at line 291 of file utm_transform_node.cpp.
void odomCallback | ( | const nav_msgs::OdometryConstPtr & | msg | ) |
Callback for the odom data.
Definition at line 266 of file utm_transform_node.cpp.
void utmCallback | ( | const nav_msgs::OdometryConstPtr & | msg | ) |
Callback for the UTM data.
Definition at line 226 of file utm_transform_node.cpp.
bool hasFix_ |
Whether or not the GPS fix is usable.
Definition at line 76 of file utm_transform_node.cpp.
sensor_msgs::Imu* latestImuMsg_ |
Definition at line 46 of file utm_transform_node.cpp.
nav_msgs::Odometry* latestOdomMessage_ |
Definition at line 45 of file utm_transform_node.cpp.
nav_msgs::Odometry* latestUtmMsg_ |
Used for calculating the utm_frame->odom_frame transform.
Definition at line 44 of file utm_transform_node.cpp.
double magneticDeclination_ |
Parameter that specifies the magnetic decliation for the robot's environment.
Definition at line 64 of file utm_transform_node.cpp.
The utm_frame->odom_frame transform object.
Definition at line 52 of file utm_transform_node.cpp.
Used for updating the transform so as to remove altitude from the UTM measurements.
Definition at line 56 of file utm_transform_node.cpp.
Used for updating the transform so as to remove altitude from the UTM measurements.
Definition at line 60 of file utm_transform_node.cpp.
double pitchOffset_ |
On level ground, your IMU should read 0 pitch. If it doesn't, this (parameterized) value gives the offset.
Definition at line 87 of file utm_transform_node.cpp.
double rollOffset_ |
On level ground, your IMU should read 0 roll. If it doesn't, this (parameterized) value gives the offset.
Definition at line 83 of file utm_transform_node.cpp.
TF listener used for converting.
Definition at line 49 of file utm_transform_node.cpp.
bool transformGood_ |
Whether or not we've computed a good heading.
Definition at line 79 of file utm_transform_node.cpp.
double utmOdomTfPitch_ |
Stores the pitch we need to compute the transform.
Definition at line 70 of file utm_transform_node.cpp.
double utmOdomTfRoll_ |
Stores the roll we need to compute the transform.
Definition at line 67 of file utm_transform_node.cpp.
double utmOdomTfYaw_ |
Stores the yaw we need to compute the transform.
Definition at line 73 of file utm_transform_node.cpp.
double yawOffset_ |
Your IMU should read 0 when facing *magnetic* north. If it doesn't, this (parameterized) value gives the offset (NOTE: if you have a magenetic declination, use the parameter setting for that).
Definition at line 92 of file utm_transform_node.cpp.
bool zeroAltitude_ |
If this parameter is true, we continually update the transform using the current altitude from the UTM message. This allows users to receive a (nearly) zero Z measurement when they use the transform.
Definition at line 97 of file utm_transform_node.cpp.