Public Member Functions | Private Member Functions | Private Attributes | List of all members
RobotLocalization::NavSatTransform Class Reference

#include <navsat_transform.h>

Public Member Functions

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

Private Member Functions

void computeTransform ()
 Computes the transform from the UTM frame to the odom frame. More...
 
bool datumCallback (robot_localization::SetDatum::Request &request, robot_localization::SetDatum::Response &)
 Callback for the datum service. More...
 
void getRobotOriginUtmPose (const tf2::Transform &gps_utm_pose, tf2::Transform &robot_utm_pose, const ros::Time &transform_time)
 Given the pose of the navsat sensor in the UTM frame, removes the offset from the vehicle's centroid and returns the UTM-frame pose of said centroid. More...
 
void getRobotOriginWorldPose (const tf2::Transform &gps_odom_pose, tf2::Transform &robot_odom_pose, const ros::Time &transform_time)
 Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle's centroid and returns the world-frame pose of said centroid. More...
 
void gpsFixCallback (const sensor_msgs::NavSatFixConstPtr &msg)
 Callback for the GPS fix data. More...
 
void imuCallback (const sensor_msgs::ImuConstPtr &msg)
 Callback for the IMU data. More...
 
void odomCallback (const nav_msgs::OdometryConstPtr &msg)
 Callback for the odom data. More...
 
bool prepareFilteredGps (sensor_msgs::NavSatFix &filtered_gps)
 Converts the odometry data back to GPS and broadcasts it. More...
 
bool prepareGpsOdometry (nav_msgs::Odometry &gps_odom)
 Prepares the GPS odometry message before sending. More...
 
void setTransformGps (const sensor_msgs::NavSatFixConstPtr &msg)
 Used for setting the GPS data that will be used to compute the transform. More...
 
void setTransformOdometry (const nav_msgs::OdometryConstPtr &msg)
 Used for setting the odometry data that will be used to compute the transform. More...
 

Private Attributes

std::string base_link_frame_id_
 Frame ID of the robot's body frame. More...
 
bool base_link_frame_param_loaded_
 Whether base link frame parameter was loaded. More...
 
bool broadcast_utm_transform_
 Whether or not we broadcast the UTM transform. More...
 
bool broadcast_utm_transform_as_parent_frame_
 Whether to broadcast the UTM transform as parent frame, default as child. More...
 
std::string gps_frame_id_
 The frame_id of the GPS message (specifies mounting location) More...
 
ros::Time gps_update_time_
 Timestamp of the latest good GPS message. More...
 
bool gps_updated_
 Whether or not we have new GPS data. More...
 
bool has_transform_gps_
 Whether or not the GPS fix is usable. More...
 
bool has_transform_imu_
 Signifies that we have received a usable IMU message. More...
 
bool has_transform_odom_
 Signifies that we have received a usable odometry message. More...
 
Eigen::MatrixXd latest_odom_covariance_
 Covariance for most recent odometry data. More...
 
Eigen::MatrixXd latest_utm_covariance_
 Covariance for most recent GPS/UTM data. More...
 
tf2::Transform latest_utm_pose_
 Latest GPS data, stored as UTM coords. More...
 
tf2::Transform latest_world_pose_
 Latest odometry pose data. More...
 
double magnetic_declination_
 Parameter that specifies the magnetic declination for the robot's environment. More...
 
ros::Time odom_update_time_
 Timestamp of the latest good odometry message. More...
 
bool odom_updated_
 Whether or not we have new odometry data. More...
 
bool publish_gps_
 Whether or not we publish filtered GPS messages. More...
 
tf2_ros::Buffer tf_buffer_
 Transform buffer for managing coordinate transforms. More...
 
tf2_ros::TransformListener tf_listener_
 Transform listener for receiving transforms. More...
 
bool transform_good_
 Whether or not we've computed a good heading. More...
 
tf2::Quaternion transform_orientation_
 Latest IMU orientation. More...
 
ros::Duration transform_timeout_
 Parameter that specifies the how long we wait for a transform to become available. More...
 
tf2::Transform transform_utm_pose_
 Holds the UTM pose that is used to compute the transform. More...
 
tf2::Transform transform_world_pose_
 Latest IMU orientation. More...
 
bool use_manual_datum_
 Whether we get our datum from the first GPS message or from the set_datum service/parameter. More...
 
bool use_odometry_yaw_
 Whether we get the transform's yaw from the odometry or IMU source. More...
 
tf2_ros::StaticTransformBroadcaster utm_broadcaster_
 Used for publishing the static world_frame->utm transform. More...
 
double utm_meridian_convergence_
 UTM's meridian convergence. More...
 
double utm_odom_tf_yaw_
 Stores the yaw we need to compute the transform. More...
 
tf2::Transform utm_world_trans_inverse_
 Holds the odom->UTM transform for filtered GPS broadcast. More...
 
tf2::Transform utm_world_transform_
 Holds the UTM->odom transform. More...
 
std::string utm_zone_
 UTM zone as determined after transforming GPS message. More...
 
std::string world_frame_id_
 Frame ID of the GPS odometry output. More...
 
bool world_frame_param_loaded_
 Whether world frame parameter was loaded. More...
 
double yaw_offset_
 IMU's yaw offset. More...
 
bool zero_altitude_
 Whether or not to report 0 altitude. More...
 

Detailed Description

Definition at line 56 of file navsat_transform.h.

Constructor & Destructor Documentation

RobotLocalization::NavSatTransform::NavSatTransform ( )

Constructor.

Definition at line 46 of file navsat_transform.cpp.

RobotLocalization::NavSatTransform::~NavSatTransform ( )

Destructor.

Definition at line 75 of file navsat_transform.cpp.

Member Function Documentation

void RobotLocalization::NavSatTransform::computeTransform ( )
private

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

Definition at line 253 of file navsat_transform.cpp.

bool RobotLocalization::NavSatTransform::datumCallback ( robot_localization::SetDatum::Request &  request,
robot_localization::SetDatum::Response &   
)
private

Callback for the datum service.

Definition at line 346 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::getRobotOriginUtmPose ( const tf2::Transform gps_utm_pose,
tf2::Transform robot_utm_pose,
const ros::Time transform_time 
)
private

Given the pose of the navsat sensor in the UTM frame, removes the offset from the vehicle's centroid and returns the UTM-frame pose of said centroid.

Definition at line 390 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::getRobotOriginWorldPose ( const tf2::Transform gps_odom_pose,
tf2::Transform robot_odom_pose,
const ros::Time transform_time 
)
private

Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle's centroid and returns the world-frame pose of said centroid.

Definition at line 440 of file navsat_transform.cpp.

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

Callback for the GPS fix data.

Parameters
[in]msgThe NavSatFix message to process

Definition at line 486 of file navsat_transform.cpp.

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

Callback for the IMU data.

Parameters
[in]msgThe IMU message to process

Definition at line 532 of file navsat_transform.cpp.

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

Callback for the odom data.

Parameters
[in]msgThe odometry message to process

Definition at line 587 of file navsat_transform.cpp.

bool RobotLocalization::NavSatTransform::prepareFilteredGps ( sensor_msgs::NavSatFix &  filtered_gps)
private

Converts the odometry data back to GPS and broadcasts it.

Parameters
[out]filtered_gpsThe NavSatFix message to prepare

Definition at line 624 of file navsat_transform.cpp.

bool RobotLocalization::NavSatTransform::prepareGpsOdometry ( nav_msgs::Odometry &  gps_odom)
private

Prepares the GPS odometry message before sending.

Parameters
[out]gps_odomThe odometry message to prepare

Definition at line 683 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::run ( )

Main run loop.

Definition at line 79 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::setTransformGps ( const sensor_msgs::NavSatFixConstPtr &  msg)
private

Used for setting the GPS data that will be used to compute the transform.

Parameters
[in]msgThe NavSatFix message to use in the transform

Definition at line 741 of file navsat_transform.cpp.

void RobotLocalization::NavSatTransform::setTransformOdometry ( const nav_msgs::OdometryConstPtr &  msg)
private

Used for setting the odometry data that will be used to compute the transform.

Parameters
[in]msgThe odometry message to use in the transform

Definition at line 757 of file navsat_transform.cpp.

Member Data Documentation

std::string RobotLocalization::NavSatTransform::base_link_frame_id_
private

Frame ID of the robot's body frame.

This is needed for obtaining transforms from the robot's body frame to the frames of sensors (IMU and GPS)

Definition at line 133 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::base_link_frame_param_loaded_
private

Whether base link frame parameter was loaded.

Definition at line 297 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::broadcast_utm_transform_
private

Whether or not we broadcast the UTM transform.

Definition at line 137 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::broadcast_utm_transform_as_parent_frame_
private

Whether to broadcast the UTM transform as parent frame, default as child.

Definition at line 141 of file navsat_transform.h.

std::string RobotLocalization::NavSatTransform::gps_frame_id_
private

The frame_id of the GPS message (specifies mounting location)

Definition at line 145 of file navsat_transform.h.

ros::Time RobotLocalization::NavSatTransform::gps_update_time_
private

Timestamp of the latest good GPS message.

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

Definition at line 151 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::gps_updated_
private

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

bool RobotLocalization::NavSatTransform::has_transform_gps_
private

Whether or not the GPS fix is usable.

Definition at line 161 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::has_transform_imu_
private

Signifies that we have received a usable IMU message.

Definition at line 165 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::has_transform_odom_
private

Signifies that we have received a usable odometry message.

Definition at line 169 of file navsat_transform.h.

Eigen::MatrixXd RobotLocalization::NavSatTransform::latest_odom_covariance_
private

Covariance for most recent odometry data.

Definition at line 173 of file navsat_transform.h.

Eigen::MatrixXd RobotLocalization::NavSatTransform::latest_utm_covariance_
private

Covariance for most recent GPS/UTM data.

Definition at line 177 of file navsat_transform.h.

tf2::Transform RobotLocalization::NavSatTransform::latest_utm_pose_
private

Latest GPS data, stored as UTM coords.

Definition at line 181 of file navsat_transform.h.

tf2::Transform RobotLocalization::NavSatTransform::latest_world_pose_
private

Latest odometry pose data.

Definition at line 185 of file navsat_transform.h.

double RobotLocalization::NavSatTransform::magnetic_declination_
private

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

Definition at line 189 of file navsat_transform.h.

ros::Time RobotLocalization::NavSatTransform::odom_update_time_
private

Timestamp of the latest good odometry message.

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

Definition at line 195 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::odom_updated_
private

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

bool RobotLocalization::NavSatTransform::publish_gps_
private

Whether or not we publish filtered GPS messages.

Definition at line 205 of file navsat_transform.h.

tf2_ros::Buffer RobotLocalization::NavSatTransform::tf_buffer_
private

Transform buffer for managing coordinate transforms.

Definition at line 209 of file navsat_transform.h.

tf2_ros::TransformListener RobotLocalization::NavSatTransform::tf_listener_
private

Transform listener for receiving transforms.

Definition at line 213 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::transform_good_
private

Whether or not we've computed a good heading.

Definition at line 217 of file navsat_transform.h.

tf2::Quaternion RobotLocalization::NavSatTransform::transform_orientation_
private

Latest IMU orientation.

Definition at line 221 of file navsat_transform.h.

ros::Duration RobotLocalization::NavSatTransform::transform_timeout_
private

Parameter that specifies the how long we wait for a transform to become available.

Definition at line 283 of file navsat_transform.h.

tf2::Transform RobotLocalization::NavSatTransform::transform_utm_pose_
private

Holds the UTM pose that is used to compute the transform.

Definition at line 225 of file navsat_transform.h.

tf2::Transform RobotLocalization::NavSatTransform::transform_world_pose_
private

Latest IMU orientation.

Definition at line 229 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::use_manual_datum_
private

Whether we get our datum from the first GPS message or from the set_datum service/parameter.

Definition at line 234 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::use_odometry_yaw_
private

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

Definition at line 238 of file navsat_transform.h.

tf2_ros::StaticTransformBroadcaster RobotLocalization::NavSatTransform::utm_broadcaster_
private

Used for publishing the static world_frame->utm transform.

Definition at line 242 of file navsat_transform.h.

double RobotLocalization::NavSatTransform::utm_meridian_convergence_
private

UTM's meridian convergence.

Angle between projected meridian (True North) and UTM's grid Y-axis. For UTM projection (Ellipsoidal Transverse Mercator) it is zero on the equator and non-zero everywhere else. It increases as the poles are approached or as we're getting farther from central meridian.

Definition at line 279 of file navsat_transform.h.

double RobotLocalization::NavSatTransform::utm_odom_tf_yaw_
private

Stores the yaw we need to compute the transform.

Definition at line 246 of file navsat_transform.h.

tf2::Transform RobotLocalization::NavSatTransform::utm_world_trans_inverse_
private

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

Definition at line 254 of file navsat_transform.h.

tf2::Transform RobotLocalization::NavSatTransform::utm_world_transform_
private

Holds the UTM->odom transform.

Definition at line 250 of file navsat_transform.h.

std::string RobotLocalization::NavSatTransform::utm_zone_
private

UTM zone as determined after transforming GPS message.

Definition at line 258 of file navsat_transform.h.

std::string RobotLocalization::NavSatTransform::world_frame_id_
private

Frame ID of the GPS odometry output.

This will just match whatever your odometry message has

Definition at line 264 of file navsat_transform.h.

bool RobotLocalization::NavSatTransform::world_frame_param_loaded_
private

Whether world frame parameter was loaded.

Definition at line 293 of file navsat_transform.h.

double RobotLocalization::NavSatTransform::yaw_offset_
private

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

bool RobotLocalization::NavSatTransform::zero_altitude_
private

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


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


robot_localization
Author(s): Tom Moore
autogenerated on Wed Feb 3 2021 03:34:02