Public Member Functions | Private Member Functions | Private Attributes
RobotLocalization::NavSatTransform Class Reference

#include <navsat_transform.h>

List of all members.

Public Member Functions

 NavSatTransform ()
 Constructor.
void run ()
 Main run loop.
 ~NavSatTransform ()
 Destructor.

Private Member Functions

void computeTransform ()
 Computes the transform from the UTM frame to the odom frame.
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.
void odomCallback (const nav_msgs::OdometryConstPtr &msg)
 Callback for the odom data.
bool prepareFilteredGps (sensor_msgs::NavSatFix &filteredGps)
 Converts the odometry data back to GPS and broadcasts it.
bool prepareGpsOdometry (nav_msgs::Odometry &gpsOdom)
 Prepares the GPS odometry message before sending.

Private Attributes

bool broadcastUtmTransform_
 Whether or not we broadcast the UTM transform.
bool gpsUpdated_
 Whether or not we have new GPS data.
ros::Time gpsUpdateTime_
 Timestamp of the latest good GPS message.
bool hasGps_
 Whether or not the GPS fix is usable.
bool hasImu_
 Signifies that we have received an IMU message.
bool hasOdom_
 Signifies that we have an odometry message.
Eigen::MatrixXd latestOdomCovariance_
 Covariance for most recent odometry data.
tf::Quaternion latestOrientation_
 Latest IMU orientation.
Eigen::MatrixXd latestUtmCovariance_
 Covariance for most recent GPS/UTM data.
tf::Pose latestUtmPose_
 Latest GPS data, stored as UTM coords.
tf::Pose latestWorldPose_
 Latest odometry data.
double magneticDeclination_
 Parameter that specifies the magnetic decliation for the robot's environment.
bool odomUpdated_
 Whether or not we have new odometry data.
ros::Time odomUpdateTime_
 Timestamp of the latest good odometry message.
bool publishGps_
 Whether or not we publish filtered GPS messages.
bool transformGood_
 Whether or not we've computed a good heading.
bool useOdometryYaw_
 Whether we get the transform's yaw from the odometry or IMU source.
double utmOdomTfYaw_
 Stores the yaw we need to compute the transform.
tf::Transform utmWorldTransform_
 Holds the UTM->odom transform.
tf::Transform utmWorldTransInverse_
 Holds the odom->UTM transform for filtered GPS broadcast.
std::string utmZone_
 UTM zone as determined after transforming GPS message.
std::string worldFrameId_
 Frame ID of the GPS odometry output.
double yawOffset_
 IMU's yaw offset.
bool zeroAltitude_
 Whether or not to report 0 altitude.

Detailed Description

Definition at line 45 of file navsat_transform.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 42 of file navsat_transform.cpp.

Destructor.

Definition at line 61 of file navsat_transform.cpp.


Member Function Documentation

Computes the transform from the UTM frame to the odom frame.

Definition at line 120 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::gpsFixCallback ( const sensor_msgs::NavSatFixConstPtr &  msg) [private]

Callback for the GPS fix data.

Definition at line 85 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::imuCallback ( const sensor_msgs::ImuConstPtr &  msg) [private]

Callback for the IMU data.

Definition at line 114 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::odomCallback ( const nav_msgs::OdometryConstPtr &  msg) [private]

Callback for the odom data.

Definition at line 66 of file navsat_transform.cpp.

bool RobotLocalization::NavSatTransform::prepareFilteredGps ( sensor_msgs::NavSatFix &  filteredGps) [private]

Converts the odometry data back to GPS and broadcasts it.

Definition at line 258 of file navsat_transform.cpp.

bool RobotLocalization::NavSatTransform::prepareGpsOdometry ( nav_msgs::Odometry &  gpsOdom) [private]

Prepares the GPS odometry message before sending.

Definition at line 205 of file navsat_transform.cpp.

Main run loop.

Definition at line 313 of file navsat_transform.cpp.


Member Data Documentation

Whether or not we broadcast the UTM transform.

Definition at line 65 of file navsat_transform.h.

Whether or not we have new GPS data.

We only want to compute and broadcast our transformed GPS data if it's new. This variable keeps track of that.

Definition at line 97 of file navsat_transform.h.

Timestamp of the latest good GPS message.

We assign this value to the timestamp of the odometry message that we output

Definition at line 111 of file navsat_transform.h.

Whether or not the GPS fix is usable.

Definition at line 78 of file navsat_transform.h.

Signifies that we have received an IMU message.

Definition at line 86 of file navsat_transform.h.

Signifies that we have an odometry message.

Definition at line 82 of file navsat_transform.h.

Covariance for most recent odometry data.

Definition at line 171 of file navsat_transform.h.

Latest IMU orientation.

Definition at line 163 of file navsat_transform.h.

Covariance for most recent GPS/UTM data.

Definition at line 167 of file navsat_transform.h.

Latest GPS data, stored as UTM coords.

Definition at line 159 of file navsat_transform.h.

Latest odometry data.

Definition at line 155 of file navsat_transform.h.

Parameter that specifies the magnetic decliation for the robot's environment.

Definition at line 70 of file navsat_transform.h.

Whether or not we have new odometry data.

If we're creating filtered GPS messages, then we only want to broadcast them when new odometry data arrives.

Definition at line 104 of file navsat_transform.h.

Timestamp of the latest good odometry message.

We assign this value to the timestamp of the odometry message that we output

Definition at line 118 of file navsat_transform.h.

Whether or not we publish filtered GPS messages.

Definition at line 137 of file navsat_transform.h.

Whether or not we've computed a good heading.

Definition at line 90 of file navsat_transform.h.

Whether we get the transform's yaw from the odometry or IMU source.

Definition at line 141 of file navsat_transform.h.

Stores the yaw we need to compute the transform.

Definition at line 74 of file navsat_transform.h.

Holds the UTM->odom transform.

Definition at line 175 of file navsat_transform.h.

Holds the odom->UTM transform for filtered GPS broadcast.

Definition at line 179 of file navsat_transform.h.

UTM zone as determined after transforming GPS message.

Definition at line 151 of file navsat_transform.h.

Frame ID of the GPS odometry output.

This will just match whatever your odometry message has

Definition at line 147 of file navsat_transform.h.

IMU's yaw offset.

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 126 of file navsat_transform.h.

Whether or not to report 0 altitude.

If this parameter is true, we always report 0 for the altitude of the converted GPS odometry message.

Definition at line 133 of file navsat_transform.h.


The documentation for this class was generated from the following files:


robot_localization
Author(s): Tom Moore
autogenerated on Fri Aug 28 2015 12:26:20