#include <message_wrapper.h>
Public Member Functions | |
const sensor_msgs::FluidPressure | createRosFluidPressureMessage (const sbg_driver::SbgAirData &ref_sbg_air_msg) const |
const sensor_msgs::Imu | createRosImuMessage (const sbg_driver::SbgImuData &ref_sbg_imu_msg, const sbg_driver::SbgEkfQuat &ref_sbg_quat_msg) const |
const sensor_msgs::MagneticField | createRosMagneticMessage (const sbg_driver::SbgMag &ref_sbg_mag_msg) const |
const sensor_msgs::NavSatFix | createRosNavSatFixMessage (const sbg_driver::SbgGpsPos &ref_sbg_gps_msg) const |
const nav_msgs::Odometry | createRosOdoMessage (const sbg_driver::SbgImuData &ref_sbg_imu_msg, const sbg_driver::SbgEkfNav &ref_sbg_ekf_nav_msg, const sbg_driver::SbgEkfQuat &ref_sbg_ekf_quat_msg, const sbg_driver::SbgEkfEuler &ref_sbg_ekf_euler_msg) |
const nav_msgs::Odometry | createRosOdoMessage (const sbg_driver::SbgImuData &ref_sbg_imu_msg, const sbg_driver::SbgEkfNav &ref_sbg_ekf_nav_msg, const sbg_driver::SbgEkfEuler &ref_sbg_ekf_euler_msg) |
const nav_msgs::Odometry | createRosOdoMessage (const sbg_driver::SbgImuData &ref_sbg_imu_msg, const sbg_driver::SbgEkfNav &ref_sbg_ekf_nav_msg, const tf2::Quaternion &ref_orientation, const sbg_driver::SbgEkfEuler &ref_sbg_ekf_euler_msg) |
const geometry_msgs::PointStamped | createRosPointStampedMessage (const sbg_driver::SbgEkfNav &ref_sbg_ekf_msg) const |
const sensor_msgs::Temperature | createRosTemperatureMessage (const sbg_driver::SbgImuData &ref_sbg_imu_msg) const |
const geometry_msgs::TwistStamped | createRosTwistStampedMessage (const sbg_driver::SbgEkfEuler &ref_sbg_ekf_vel_msg, const sbg_driver::SbgEkfNav &ref_sbg_ekf_nav_msg, const sbg_driver::SbgImuData &ref_sbg_imu_msg) const |
const geometry_msgs::TwistStamped | createRosTwistStampedMessage (const sbg_driver::SbgEkfQuat &ref_sbg_ekf_vel_msg, const sbg_driver::SbgEkfNav &ref_sbg_ekf_nav_msg, const sbg_driver::SbgImuData &ref_sbg_imu_msg) const |
const sensor_msgs::TimeReference | createRosUtcTimeReferenceMessage (const sbg_driver::SbgUtcTime &ref_sbg_utc_msg) const |
const sbg_driver::SbgAirData | createSbgAirDataMessage (const SbgLogAirData &ref_air_data_log) const |
const sbg_driver::SbgEkfEuler | createSbgEkfEulerMessage (const SbgLogEkfEulerData &ref_log_ekf_euler) const |
const sbg_driver::SbgEkfNav | createSbgEkfNavMessage (const SbgLogEkfNavData &ref_log_ekf_nav) const |
const sbg_driver::SbgEkfQuat | createSbgEkfQuatMessage (const SbgLogEkfQuatData &ref_log_ekf_quat) const |
const sbg_driver::SbgEvent | createSbgEventMessage (const SbgLogEvent &ref_log_event) const |
const sbg_driver::SbgGpsHdt | createSbgGpsHdtMessage (const SbgLogGpsHdt &ref_log_gps_hdt) const |
const sbg_driver::SbgGpsPos | createSbgGpsPosMessage (const SbgLogGpsPos &ref_log_gps_pos) const |
const sbg_driver::SbgGpsRaw | createSbgGpsRawMessage (const SbgLogGpsRaw &ref_log_gps_raw) const |
const sbg_driver::SbgGpsVel | createSbgGpsVelMessage (const SbgLogGpsVel &ref_log_gps_vel) const |
const sbg_driver::SbgImuData | createSbgImuDataMessage (const SbgLogImuData &ref_log_imu_data) const |
const sbg_driver::SbgImuShort | createSbgImuShortMessage (const SbgLogImuShort &ref_short_imu_log) const |
const sbg_driver::SbgMagCalib | createSbgMagCalibMessage (const SbgLogMagCalib &ref_log_mag_calib) const |
const sbg_driver::SbgMag | createSbgMagMessage (const SbgLogMag &ref_log_mag) const |
const sbg_driver::SbgOdoVel | createSbgOdoVelMessage (const SbgLogOdometerData &ref_log_odo) const |
const sbg_driver::SbgShipMotion | createSbgShipMotionMessage (const SbgLogShipMotionData &ref_log_ship_motion) const |
const sbg_driver::SbgStatus | createSbgStatusMessage (const SbgLogStatusData &ref_log_status) const |
const sbg_driver::SbgUtcTime | createSbgUtcTimeMessage (const SbgLogUtcData &ref_log_utc) |
MessageWrapper (void) | |
void | setFrameId (const std::string &frame_id) |
void | setOdomBaseFrameId (const std::string &ref_frame_id) |
void | setOdomEnable (bool odom_enable) |
void | setOdomFrameId (const std::string &ref_frame_id) |
void | setOdomInitFrameId (const std::string &ref_frame_id) |
void | setOdomPublishTf (bool publish_tf) |
void | setTimeReference (TimeReference time_reference) |
void | setUseEnu (bool enu) |
Private Member Functions | |
double | computeMeridian (int zone_number) const |
const ros::Time | convertInsTimeToUnix (uint32_t device_timestamp) const |
const ros::Time | convertUtcToUnix (const sbg_driver::SbgUtcTime &ref_sbg_utc_msg) const |
const sbg_driver::SbgAirDataStatus | createAirDataStatusMessage (const SbgLogAirData &ref_sbg_air_data) const |
const sbg_driver::SbgEkfStatus | createEkfStatusMessage (uint32_t ekf_status) const |
const sbg_driver::SbgGpsPosStatus | createGpsPosStatusMessage (const SbgLogGpsPos &ref_log_gps_pos) const |
const sbg_driver::SbgGpsVelStatus | createGpsVelStatusMessage (const SbgLogGpsVel &ref_log_gps_vel) const |
const sbg_driver::SbgImuStatus | createImuStatusMessage (uint16_t sbg_imu_status) const |
const sbg_driver::SbgMagStatus | createMagStatusMessage (const SbgLogMag &ref_log_mag) const |
const std_msgs::Header | createRosHeader (uint32_t device_timestamp) const |
const geometry_msgs::TwistStamped | createRosTwistStampedMessage (const sbg::SbgVector3f &body_vel, const sbg_driver::SbgImuData &ref_sbg_imu_msg) const |
const sbg_driver::SbgShipMotionStatus | createShipMotionStatusMessage (const SbgLogShipMotionData &ref_log_ship_motion) const |
const sbg_driver::SbgStatusAiding | createStatusAidingMessage (const SbgLogStatusData &ref_log_status) const |
const sbg_driver::SbgStatusCom | createStatusComMessage (const SbgLogStatusData &ref_log_status) const |
const sbg_driver::SbgStatusGeneral | createStatusGeneralMessage (const SbgLogStatusData &ref_log_status) const |
const sbg_driver::SbgUtcTimeStatus | createUtcStatusMessage (const SbgLogUtcData &ref_log_utc) const |
void | fillTransform (const std::string &ref_parent_frame_id, const std::string &ref_child_frame_id, const geometry_msgs::Pose &ref_pose, geometry_msgs::TransformStamped &ref_transform_stamped) |
uint32_t | getNumberOfDaysInMonth (uint16_t year, uint8_t month_index) const |
uint32_t | getNumberOfDaysInYear (uint16_t year) const |
void | initUTM (double Lat, double Long, double altitude) |
bool | isLeapYear (uint16_t year) const |
void | LLtoUTM (double Lat, double Long, int zoneNumber, double &UTMNorthing, double &UTMEasting) const |
char | UTMLetterDesignator (double Lat) |
float | wrapAngle2Pi (float angle_rad) const |
float | wrapAngle360 (float angle_deg) const |
Private Attributes | |
bool | m_first_valid_utc_ |
std::string | m_frame_id_ |
sbg_driver::SbgUtcTime | m_last_sbg_utc_ |
std::string | m_odom_base_frame_id_ |
bool | m_odom_enable_ |
std::string | m_odom_frame_id_ |
std::string | m_odom_init_frame_id_ |
bool | m_odom_publish_tf_ |
ros::Time | m_ros_processing_time_ |
tf2_ros::StaticTransformBroadcaster | m_static_tf_broadcaster_ |
tf2_ros::TransformBroadcaster | m_tf_broadcaster_ |
TimeReference | m_time_reference_ |
bool | m_use_enu_ |
UTM0 | m_utm0_ |
Class to wrap the SBG logs into ROS messages.
Definition at line 92 of file message_wrapper.h.
MessageWrapper::MessageWrapper | ( | void | ) |
Default constructor.
Class to wrap the SBG logs into ROS messages.
Definition at line 22 of file message_wrapper.cpp.
|
private |
Compute UTM zone meridian.
[in] | zone_number | UTM Zone number. |
Definition at line 65 of file message_wrapper.cpp.
|
private |
Convert INS timestamp from a SBG device to UNIX timestamp.
[in] | device_timestamp | SBG device timestamp (in microseconds). |
Definition at line 88 of file message_wrapper.cpp.
|
private |
Convert the UTC time to an Unix time.
[in] | ref_sbg_utc_msg | UTC message. |
Definition at line 324 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS air data status message.
[in] | ref_sbg_air_data | SBG AirData log. |
Definition at line 359 of file message_wrapper.cpp.
|
private |
Create SBG-ROS Ekf status message.
[in] | ekf_status | SBG Ekf status. |
Definition at line 108 of file message_wrapper.cpp.
|
private |
Create SBG-ROS GPS Position status message.
[in] | ref_log_gps_pos | SBG GPS position log. |
Definition at line 136 of file message_wrapper.cpp.
|
private |
Create SBG-ROS GPS Velocity status message.
[in] | ref_log_gps_vel | SBG GPS Velocity log. |
Definition at line 153 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS IMU status message.
[in] | sbg_imu_status | SBG IMU status. |
Definition at line 163 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS Magnetometer status message.
[in] | ref_log_mag | SBG Magnetometer log. |
Definition at line 183 of file message_wrapper.cpp.
const sensor_msgs::FluidPressure MessageWrapper::createRosFluidPressureMessage | ( | const sbg_driver::SbgAirData & | ref_sbg_air_msg | ) | const |
Create a ROS standard FluidPressure message.
[in] | ref_sbg_air_msg | SBG-ROS AirData message. |
Definition at line 1300 of file message_wrapper.cpp.
|
private |
Create a ROS message header.
[in] | device_timestamp | SBG device timestamp (in microseconds). |
Definition at line 70 of file message_wrapper.cpp.
const sensor_msgs::Imu MessageWrapper::createRosImuMessage | ( | const sbg_driver::SbgImuData & | ref_sbg_imu_msg, |
const sbg_driver::SbgEkfQuat & | ref_sbg_quat_msg | ||
) | const |
Create a ROS standard IMU message from SBG messages.
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
[in] | ref_sbg_quat_msg | SBG_ROS Quaternion message. |
Definition at line 1016 of file message_wrapper.cpp.
const sensor_msgs::MagneticField MessageWrapper::createRosMagneticMessage | ( | const sbg_driver::SbgMag & | ref_sbg_mag_msg | ) | const |
Create a ROS standard MagneticField message from SBG message.
[in] | ref_sbg_mag_msg | SBG-ROS Mag message. |
Definition at line 1167 of file message_wrapper.cpp.
const sensor_msgs::NavSatFix MessageWrapper::createRosNavSatFixMessage | ( | const sbg_driver::SbgGpsPos & | ref_sbg_gps_msg | ) | const |
Create a ROS standard NavSatFix message from a Gps message.
[in] | ref_sbg_gps_msg | SBG-ROS GPS position message. |
Definition at line 1259 of file message_wrapper.cpp.
const nav_msgs::Odometry MessageWrapper::createRosOdoMessage | ( | const sbg_driver::SbgImuData & | ref_sbg_imu_msg, |
const sbg_driver::SbgEkfNav & | ref_sbg_ekf_nav_msg, | ||
const sbg_driver::SbgEkfQuat & | ref_sbg_ekf_quat_msg, | ||
const sbg_driver::SbgEkfEuler & | ref_sbg_ekf_euler_msg | ||
) |
Create a ROS standard odometry message from SBG messages.
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
[in] | ref_sbg_ekf_nav_msg | SBG-ROS Ekf Nav message. |
[in] | ref_sbg_ekf_quat_msg | SBG-ROS Ekf Quaternion message. |
[in] | ref_sbg_ekf_euler_msg | SBG-ROS Ekf Euler message. |
Definition at line 1061 of file message_wrapper.cpp.
const nav_msgs::Odometry MessageWrapper::createRosOdoMessage | ( | const sbg_driver::SbgImuData & | ref_sbg_imu_msg, |
const sbg_driver::SbgEkfNav & | ref_sbg_ekf_nav_msg, | ||
const sbg_driver::SbgEkfEuler & | ref_sbg_ekf_euler_msg | ||
) |
Create a ROS standard odometry message from SBG messages.
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
[in] | ref_sbg_ekf_nav_msg | SBG-ROS Ekf Nav message. |
[in] | ref_sbg_ekf_euler_msg | SBG-ROS Ekf Euler message. |
Definition at line 1068 of file message_wrapper.cpp.
const nav_msgs::Odometry MessageWrapper::createRosOdoMessage | ( | const sbg_driver::SbgImuData & | ref_sbg_imu_msg, |
const sbg_driver::SbgEkfNav & | ref_sbg_ekf_nav_msg, | ||
const tf2::Quaternion & | ref_orientation, | ||
const sbg_driver::SbgEkfEuler & | ref_sbg_ekf_euler_msg | ||
) |
Create a ROS standard odometry message from SBG messages and tf2 quaternion.
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
[in] | ref_sbg_ekf_nav_msg | SBG-ROS Ekf Nav message. |
[in] | orientation | Orientation as a Tf2 quaternion. |
[in] | ref_sbg_ekf_euler_msg | SBG-ROS Ekf Euler message. |
Definition at line 1078 of file message_wrapper.cpp.
const geometry_msgs::PointStamped MessageWrapper::createRosPointStampedMessage | ( | const sbg_driver::SbgEkfNav & | ref_sbg_ekf_msg | ) | const |
Create a ROS standard PointStamped message from SBG messages.
[in] | ref_sbg_ekf_msg | SBG-ROS EkfNav message. |
Definition at line 1212 of file message_wrapper.cpp.
const sensor_msgs::Temperature MessageWrapper::createRosTemperatureMessage | ( | const sbg_driver::SbgImuData & | ref_sbg_imu_msg | ) | const |
Create a ROS standard Temperature message from SBG message.
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
Definition at line 1156 of file message_wrapper.cpp.
|
private |
Create a ROS standard TwistStamped message.
[in] | body_vel | SBG Body velocity vector. |
[in] | ref_sbg_air_data | SBG IMU message. |
Definition at line 1198 of file message_wrapper.cpp.
const geometry_msgs::TwistStamped MessageWrapper::createRosTwistStampedMessage | ( | const sbg_driver::SbgEkfEuler & | ref_sbg_ekf_vel_msg, |
const sbg_driver::SbgEkfNav & | ref_sbg_ekf_nav_msg, | ||
const sbg_driver::SbgImuData & | ref_sbg_imu_msg | ||
) | const |
Create a ROS standard TwistStamped message from SBG messages.
[in] | ref_sbg_ekf_vel_msg | SBG-ROS Ekf velocity message. |
[in] | ref_sbg_ekf_nav_msg | SBG-ROS Ekf Nav message. |
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
Definition at line 1177 of file message_wrapper.cpp.
const geometry_msgs::TwistStamped MessageWrapper::createRosTwistStampedMessage | ( | const sbg_driver::SbgEkfQuat & | ref_sbg_ekf_vel_msg, |
const sbg_driver::SbgEkfNav & | ref_sbg_ekf_nav_msg, | ||
const sbg_driver::SbgImuData & | ref_sbg_imu_msg | ||
) | const |
Create a ROS standard TwistStamped message from SBG messages.
[in] | ref_sbg_ekf_quat_msg | SBG-ROS Ekf Quaternion message. |
[in] | ref_sbg_ekf_nav_msg | SBG-ROS Ekf Nav message. |
[in] | ref_sbg_imu_msg | SBG-ROS IMU message. |
Definition at line 1188 of file message_wrapper.cpp.
const sensor_msgs::TimeReference MessageWrapper::createRosUtcTimeReferenceMessage | ( | const sbg_driver::SbgUtcTime & | ref_sbg_utc_msg | ) | const |
Create a ROS standard timeReference message for a UTC time.
[in] | ref_sbg_utc_msg | SBG-ROS UTC message. |
Definition at line 1244 of file message_wrapper.cpp.
const sbg_driver::SbgAirData MessageWrapper::createSbgAirDataMessage | ( | const SbgLogAirData & | ref_air_data_log | ) | const |
Create a SBG-ROS Air data message from a SBG log.
[in] | ref_air_data_log | SBG AirData log. |
Definition at line 967 of file message_wrapper.cpp.
const sbg_driver::SbgEkfEuler MessageWrapper::createSbgEkfEulerMessage | ( | const SbgLogEkfEulerData & | ref_log_ekf_euler | ) | const |
Create a SBG-ROS Ekf Euler message.
[in] | ref_log_ekf_euler | SBG Ekf Euler log. |
Definition at line 558 of file message_wrapper.cpp.
const sbg_driver::SbgEkfNav MessageWrapper::createSbgEkfNavMessage | ( | const SbgLogEkfNavData & | ref_log_ekf_nav | ) | const |
Create a SBG-ROS Ekf Navigation message.
[in] | ref_log_ekf_nav | SBG Ekf Navigation log. |
Definition at line 586 of file message_wrapper.cpp.
const sbg_driver::SbgEkfQuat MessageWrapper::createSbgEkfQuatMessage | ( | const SbgLogEkfQuatData & | ref_log_ekf_quat | ) | const |
Create a SBG-ROS Ekf Quaternion message.
[in] | ref_log_ekf_quat | SBG Ekf Quaternion log. |
Definition at line 631 of file message_wrapper.cpp.
const sbg_driver::SbgEvent MessageWrapper::createSbgEventMessage | ( | const SbgLogEvent & | ref_log_event | ) | const |
Create a SBG-ROS event message.
[in] | ref_log_event | SBG event log. |
Definition at line 661 of file message_wrapper.cpp.
const sbg_driver::SbgGpsHdt MessageWrapper::createSbgGpsHdtMessage | ( | const SbgLogGpsHdt & | ref_log_gps_hdt | ) | const |
Create SBG-ROS GPS-HDT message.
[in] | ref_log_gps_hdt | SBG GPS HDT log. |
Definition at line 682 of file message_wrapper.cpp.
const sbg_driver::SbgGpsPos MessageWrapper::createSbgGpsPosMessage | ( | const SbgLogGpsPos & | ref_log_gps_pos | ) | const |
Create a SBG-ROS GPS-Position message.
[in] | ref_log_gps_pos | SBG GPS Position log. |
Definition at line 708 of file message_wrapper.cpp.
const sbg_driver::SbgGpsRaw MessageWrapper::createSbgGpsRawMessage | ( | const SbgLogGpsRaw & | ref_log_gps_raw | ) | const |
Create a SBG-ROS GPS raw message.
[in] | ref_log_gps_raw | SBG GPS raw log. |
Definition at line 742 of file message_wrapper.cpp.
const sbg_driver::SbgGpsVel MessageWrapper::createSbgGpsVelMessage | ( | const SbgLogGpsVel & | ref_log_gps_vel | ) | const |
Create a SBG-ROS GPS Velocity message.
[in] | ref_log_gps_vel | SBG GPS Velocity log. |
Definition at line 751 of file message_wrapper.cpp.
const sbg_driver::SbgImuData MessageWrapper::createSbgImuDataMessage | ( | const SbgLogImuData & | ref_log_imu_data | ) | const |
Create a SBG-ROS Imu data message.
[in] | ref_log_imu_data | SBG Imu data log. |
Definition at line 789 of file message_wrapper.cpp.
const sbg_driver::SbgImuShort MessageWrapper::createSbgImuShortMessage | ( | const SbgLogImuShort & | ref_short_imu_log | ) | const |
Create a SBG-ROS Short Imu message.
[in] | ref_short_imu_log | SBG Imu short log. |
Definition at line 983 of file message_wrapper.cpp.
const sbg_driver::SbgMagCalib MessageWrapper::createSbgMagCalibMessage | ( | const SbgLogMagCalib & | ref_log_mag_calib | ) | const |
Create a SBG-ROS Magnetometer calibration message.
[in] | ref_log_mag_calib | SBG Magnetometer calibration log. |
Definition at line 870 of file message_wrapper.cpp.
const sbg_driver::SbgMag MessageWrapper::createSbgMagMessage | ( | const SbgLogMag & | ref_log_mag | ) | const |
Create a SBG-ROS Magnetometer message.
[in] | ref_log_mag | SBG Magnetometer log. |
Definition at line 838 of file message_wrapper.cpp.
const sbg_driver::SbgOdoVel MessageWrapper::createSbgOdoVelMessage | ( | const SbgLogOdometerData & | ref_log_odo | ) | const |
Create a SBG-ROS Odometer velocity message.
[in] | ref_log_odo | SBG Odometer log. |
Definition at line 880 of file message_wrapper.cpp.
const sbg_driver::SbgShipMotion MessageWrapper::createSbgShipMotionMessage | ( | const SbgLogShipMotionData & | ref_log_ship_motion | ) | const |
Create a SBG-ROS Shipmotion message.
[in] | ref_log_ship_motion | SBG Ship motion log. |
Definition at line 893 of file message_wrapper.cpp.
const sbg_driver::SbgStatus MessageWrapper::createSbgStatusMessage | ( | const SbgLogStatusData & | ref_log_status | ) | const |
Create a SBG-ROS status message from a SBG status log.
[in] | ref_log_status | SBG status log. |
Definition at line 916 of file message_wrapper.cpp.
const sbg_driver::SbgUtcTime MessageWrapper::createSbgUtcTimeMessage | ( | const SbgLogUtcData & | ref_log_utc | ) |
Create a SBG-ROS UTC time message from a SBG UTC log.
[in] | ref_log_utc | SBG UTC log. |
Definition at line 930 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS Ship motion status message.
[in] | ref_log_ship_motion | SBG Ship motion log. |
Definition at line 202 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS aiding status message.
[in] | ref_log_status | SBG status log. |
Definition at line 214 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS com status message.
[in] | ref_log_status | SBG status log. |
Definition at line 230 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS general status message.
[in] | ref_log_status | SBG status log. |
Definition at line 258 of file message_wrapper.cpp.
|
private |
Create a SBG-ROS UTC time status message.
[in] | ref_log_utc | SBG UTC data log. |
Definition at line 271 of file message_wrapper.cpp.
|
private |
Fill a transformation.
[in] | ref_parent_frame_id | Parent frame ID. |
[in] | ref_child_frame_id | Child frame ID. |
[in] | ref_pose | Pose. |
[out] | ref_transform_stamped | Stamped transformation. |
Definition at line 1042 of file message_wrapper.cpp.
|
private |
Get the number of days of the month index.
[in] | year | Year. |
[in] | month_index | Month index [1..12]. |
Definition at line 296 of file message_wrapper.cpp.
|
private |
Get the number of days in the year.
[in] | year | Year to get the number of days. |
Definition at line 284 of file message_wrapper.cpp.
|
private |
Set UTM initial position.
[in] | Lat | Latitude, in degrees. |
[in] | Long | Longitude, in degrees. |
[in] | altitude | Altitude, in meters. |
Definition at line 409 of file message_wrapper.cpp.
|
private |
Check if the given year is a leap year.
[in] | year | Year to check. |
Definition at line 319 of file message_wrapper.cpp.
|
private |
Convert latitude and longitude to a position relative to UTM initial position.
[in] | Lat | Latitude, in degrees. |
[in] | Long | Longitude, in degrees. |
[in] | zoneNumber | UTM zone number. |
[out] | UTMNorthing | UTM northing, in meters. |
[out] | UTMEasting | UTM easting, in meters. |
Definition at line 454 of file message_wrapper.cpp.
void MessageWrapper::setFrameId | ( | const std::string & | frame_id | ) |
void MessageWrapper::setOdomBaseFrameId | ( | const std::string & | ref_frame_id | ) |
Set the odometry base frame ID.
[in] | ref_frame_id | Odometry base frame ID. |
Definition at line 544 of file message_wrapper.cpp.
void MessageWrapper::setOdomEnable | ( | bool | odom_enable | ) |
Set odom enable.
[in] | odom_enable | If true enable odometry. |
Definition at line 529 of file message_wrapper.cpp.
void MessageWrapper::setOdomFrameId | ( | const std::string & | ref_frame_id | ) |
Set the odometry frame ID.
[in] | ref_frame_id | Odometry frame ID. |
Definition at line 539 of file message_wrapper.cpp.
void MessageWrapper::setOdomInitFrameId | ( | const std::string & | ref_frame_id | ) |
Set the odometry init frame ID.
[in] | ref_frame_id | Odometry init frame ID. |
Definition at line 549 of file message_wrapper.cpp.
void MessageWrapper::setOdomPublishTf | ( | bool | publish_tf | ) |
Set odom publish_tf.
[in] | publish_tf | If true publish odometry transforms. |
Definition at line 534 of file message_wrapper.cpp.
void MessageWrapper::setTimeReference | ( | TimeReference | time_reference | ) |
Set the time reference.
[in] | time_reference | Time reference. |
Definition at line 514 of file message_wrapper.cpp.
void MessageWrapper::setUseEnu | ( | bool | enu | ) |
Set use ENU.
[in] | enu | If true publish data in the ENU convention. |
Definition at line 524 of file message_wrapper.cpp.
|
private |
Get UTM letter designator for the given latitude.
[in] | Lat | Latitude, in degrees. |
Get UTM letter designator for the given latitude.
Written by Chuck Gantz- chuck .gan tz@gl obal star. com
Definition at line 380 of file message_wrapper.cpp.
|
private |
Wrap an angle to 2 PI.
[in] | angle_rad | Angle in rad. |
Definition at line 35 of file message_wrapper.cpp.
|
private |
Wrap an angle to 360 degres.
[in] | angle_deg | Angle in degree. |
Definition at line 50 of file message_wrapper.cpp.
|
private |
Definition at line 98 of file message_wrapper.h.
|
private |
Definition at line 99 of file message_wrapper.h.
|
private |
Definition at line 97 of file message_wrapper.h.
|
private |
Definition at line 109 of file message_wrapper.h.
|
private |
Definition at line 106 of file message_wrapper.h.
|
private |
Definition at line 108 of file message_wrapper.h.
|
private |
Definition at line 110 of file message_wrapper.h.
|
private |
Definition at line 107 of file message_wrapper.h.
|
private |
Definition at line 96 of file message_wrapper.h.
|
private |
Definition at line 104 of file message_wrapper.h.
|
private |
Definition at line 103 of file message_wrapper.h.
|
private |
Definition at line 101 of file message_wrapper.h.
|
private |
Definition at line 100 of file message_wrapper.h.
|
private |
Definition at line 102 of file message_wrapper.h.