Public Member Functions | Private Member Functions | Private Attributes | List of all members
sbg::MessageWrapper Class Reference

#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 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 setRosProcessingTime (const ros::Time &ref_ros_time)
 

Private Member Functions

const ros::Time computeCorrectedRosTime (uint32_t device_timestamp) const
 
const ros::Time convertUtcTimeToEpoch (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
 
template<typename T >
const geometry_msgs::Vector3 createGeometryVector3 (const T *p_array, size_t array_size) 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
 
uint32_t getNumberOfDaysInMonth (uint16_t year, uint8_t month_index) const
 
uint32_t getNumberOfDaysInYear (uint16_t year) const
 
bool isLeapYear (uint16_t year) const
 

Private Attributes

bool m_first_valid_utc_
 
sbg_driver::SbgUtcTime m_last_sbg_utc_
 
ros::Time m_ros_processing_time_
 

Detailed Description

Class to wrap the SBG logs into ROS messages.

Definition at line 79 of file message_wrapper.h.

Constructor & Destructor Documentation

MessageWrapper::MessageWrapper ( void  )

Default constructor.

Class to wrap the SBG logs into ROS messages.

Definition at line 16 of file message_wrapper.cpp.

Member Function Documentation

const ros::Time MessageWrapper::computeCorrectedRosTime ( uint32_t  device_timestamp) const
private

Compute corrected ROS time for the device timestamp.

Parameters
[in]device_timestampSBG device timestamp (in microseconds).
Returns
ROS time.

Definition at line 76 of file message_wrapper.cpp.

const ros::Time MessageWrapper::convertUtcTimeToEpoch ( const sbg_driver::SbgUtcTime &  ref_sbg_utc_msg) const
private

Convert the UTC time to an Epoch time.

Parameters
[in]ref_sbg_utc_msgSBG-ROS UTC message.
Returns
Converted Epoch time (in s).

Definition at line 303 of file message_wrapper.cpp.

const sbg_driver::SbgAirDataStatus MessageWrapper::createAirDataStatusMessage ( const SbgLogAirData ref_sbg_air_data) const
private

Create a SBG-ROS air data status message.

Parameters
[in]ref_sbg_air_dataSBG AirData log.
Returns
SBG-ROS air data status message.

Definition at line 338 of file message_wrapper.cpp.

const sbg_driver::SbgEkfStatus MessageWrapper::createEkfStatusMessage ( uint32_t  ekf_status) const
private

Create SBG-ROS Ekf status message.

Parameters
[in]ekf_statusSBG Ekf status.
Returns
Ekf status message.

Definition at line 96 of file message_wrapper.cpp.

template<typename T >
const geometry_msgs::Vector3 sbg::MessageWrapper::createGeometryVector3 ( const T *  p_array,
size_t  array_size 
) const
inlineprivate

Create a geometry message Vector3 from a raw input vector.

T Numeric template type.

Parameters
[in]p_arrayRaw input vector.
[in]array_sizeRaw vector size, should be defined as 3.
Returns
GeometryMsg Vector3.

Definition at line 100 of file message_wrapper.h.

const sbg_driver::SbgGpsPosStatus MessageWrapper::createGpsPosStatusMessage ( const SbgLogGpsPos ref_log_gps_pos) const
private

Create SBG-ROS GPS Position status message.

Parameters
[in]ref_log_gps_posSBG GPS position log.
Returns
GPS Position status.

Definition at line 121 of file message_wrapper.cpp.

const sbg_driver::SbgGpsVelStatus MessageWrapper::createGpsVelStatusMessage ( const SbgLogGpsVel ref_log_gps_vel) const
private

Create SBG-ROS GPS Velocity status message.

Parameters
[in]ref_log_gps_velSBG GPS Velocity log.
Returns
GPS Velocity status.

Definition at line 136 of file message_wrapper.cpp.

const sbg_driver::SbgImuStatus MessageWrapper::createImuStatusMessage ( uint16_t  sbg_imu_status) const
private

Create a SBG-ROS IMU status message.

Parameters
[in]sbg_imu_statusSBG IMU status.
Returns
IMU status message.

Definition at line 146 of file message_wrapper.cpp.

const sbg_driver::SbgMagStatus MessageWrapper::createMagStatusMessage ( const SbgLogMag ref_log_mag) const
private

Create a SBG-ROS Magnetometer status message.

Parameters
[in]ref_log_magSBG Magnetometer log.
Returns
Magnetometer status message.

Definition at line 164 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.

Parameters
[in]ref_sbg_air_msgSBG-ROS AirData message.
Returns
ROS standard fluid pressure message.

Definition at line 803 of file message_wrapper.cpp.

const std_msgs::Header MessageWrapper::createRosHeader ( uint32_t  device_timestamp) const
private

Create a ROS message header.

Parameters
[in]device_timestampSBG device timestamp (in microseconds).
Returns
ROS header message.

Definition at line 26 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.

Parameters
[in]ref_sbg_imu_msgSBG-ROS IMU message.
[in]ref_sbg_quat_msgSBG_ROS Quaternion message.
Returns
ROS standard IMU message.

Definition at line 643 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.

Parameters
[in]ref_sbg_mag_msgSBG-ROS Mag message.
Returns
ROS standard Mag message.

Definition at line 669 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.

Parameters
[in]ref_sbg_gps_msgSBG-ROS GPS position message.
Returns
ROS standard NavSatFix message.

Definition at line 762 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.

Parameters
[in]ref_sbg_ekf_msgSBG-ROS EkfNav message.
Returns
ROS standard PointStamped message (ECEF).

Definition at line 715 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.

Parameters
[in]ref_sbg_imu_msgSBG-ROS IMU message.
Returns
ROS standard Temperature message.

Definition at line 658 of file message_wrapper.cpp.

const geometry_msgs::TwistStamped MessageWrapper::createRosTwistStampedMessage ( const sbg::SbgVector3f body_vel,
const sbg_driver::SbgImuData &  ref_sbg_imu_msg 
) const
private

Create a ROS standard TwistStamped message.

Parameters
[in]body_velSBG Body velocity vector.
[in]ref_sbg_air_dataSBG IMU message.
Returns
SBG TwistStamped message.

Definition at line 701 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.

Parameters
[in]ref_sbg_ekf_euler_msgSBG-ROS Ekf Euler message.
[in]ref_sbg_ekf_nav_msgSBG-ROS Ekf Nav message.
[in]ref_sbg_imu_msgSBG-ROS IMU message.
Returns
ROS standard TwistStamped message.

Definition at line 679 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.

Parameters
[in]ref_sbg_ekf_quat_msgSBG-ROS Ekf Quaternion message.
[in]ref_sbg_ekf_nav_msgSBG-ROS Ekf Nav message.
[in]ref_sbg_imu_msgSBG-ROS IMU message.
Returns
ROS standard TwistStamped message.

Definition at line 690 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.

Parameters
[in]ref_sbg_utc_msgSBG-ROS UTC message.
Returns
ROS standard timeReference message.

Definition at line 747 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.

Parameters
[in]ref_air_data_logSBG AirData log.
Returns
SBG-ROS airData message.

Definition at line 613 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.

Parameters
[in]ref_log_ekf_eulerSBG Ekf Euler log.
Returns
Ekf Euler message.

Definition at line 365 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.

Parameters
[in]ref_log_ekf_navSBG Ekf Navigation log.
Returns
Ekf Navigation message.

Definition at line 378 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.

Parameters
[in]ref_log_ekf_quatSBG Ekf Quaternion log.
Returns
Ekf Quaternion message.

Definition at line 394 of file message_wrapper.cpp.

const sbg_driver::SbgEvent MessageWrapper::createSbgEventMessage ( const SbgLogEvent ref_log_event) const

Create a SBG-ROS event message.

Parameters
[in]ref_log_eventSBG event log.
Returns
Event message.

Definition at line 410 of file message_wrapper.cpp.

const sbg_driver::SbgGpsHdt MessageWrapper::createSbgGpsHdtMessage ( const SbgLogGpsHdt ref_log_gps_hdt) const

Create SBG-ROS GPS-HDT message.

Parameters
[in]ref_log_gps_hdtSBG GPS HDT log.
Returns
GPS HDT message.

Definition at line 431 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.

Parameters
[in]ref_log_gps_posSBG GPS Position log.
Returns
GPS Position message.

Definition at line 448 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.

Parameters
[in]ref_log_gps_rawSBG GPS raw log.
Returns
GPS raw message.

Definition at line 471 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.

Parameters
[in]ref_log_gps_velSBG GPS Velocity log.
Returns
GPS Velocity message.

Definition at line 480 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.

Parameters
[in]ref_log_imu_dataSBG Imu data log.
Returns
Imu data message.

Definition at line 496 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.

Parameters
[in]ref_short_imu_logSBG Imu short log.
Returns
SBG-ROS Imu short message.

Definition at line 629 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.

Parameters
[in]ref_log_mag_calibSBG Magnetometer calibration log.
Returns
Magnetometer calibration message.

Definition at line 525 of file message_wrapper.cpp.

const sbg_driver::SbgMag MessageWrapper::createSbgMagMessage ( const SbgLogMag ref_log_mag) const

Create a SBG-ROS Magnetometer message.

Parameters
[in]ref_log_magSBG Magnetometer log.
Returns
Magnetometer message.

Definition at line 512 of file message_wrapper.cpp.

const sbg_driver::SbgOdoVel MessageWrapper::createSbgOdoVelMessage ( const SbgLogOdometerData ref_log_odo) const

Create a SBG-ROS Odometer velocity message.

Parameters
[in]ref_log_odoSBG Odometer log.
Returns
Odometer message.

Definition at line 535 of file message_wrapper.cpp.

const sbg_driver::SbgShipMotion MessageWrapper::createSbgShipMotionMessage ( const SbgLogShipMotionData ref_log_ship_motion) const

Create a SBG-ROS Shipmotion message.

Parameters
[in]ref_log_ship_motionSBG Ship motion log.
Returns
Ship motion message.

Definition at line 548 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.

Parameters
[in]ref_log_statusSBG status log.
Returns
Status message.

Definition at line 562 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.

Parameters
[in]ref_log_utcSBG UTC log.
Returns
UTC time message.

Definition at line 576 of file message_wrapper.cpp.

const sbg_driver::SbgShipMotionStatus MessageWrapper::createShipMotionStatusMessage ( const SbgLogShipMotionData ref_log_ship_motion) const
private

Create a SBG-ROS Ship motion status message.

Parameters
[in]ref_log_ship_motionSBG Ship motion log.
Returns
ship motion status message.

Definition at line 181 of file message_wrapper.cpp.

const sbg_driver::SbgStatusAiding MessageWrapper::createStatusAidingMessage ( const SbgLogStatusData ref_log_status) const
private

Create a SBG-ROS aiding status message.

Parameters
[in]ref_log_statusSBG status log.
Returns
Aiding status message.

Definition at line 193 of file message_wrapper.cpp.

const sbg_driver::SbgStatusCom MessageWrapper::createStatusComMessage ( const SbgLogStatusData ref_log_status) const
private

Create a SBG-ROS com status message.

Parameters
[in]ref_log_statusSBG status log.
Returns
Com status message.

Definition at line 209 of file message_wrapper.cpp.

const sbg_driver::SbgStatusGeneral MessageWrapper::createStatusGeneralMessage ( const SbgLogStatusData ref_log_status) const
private

Create a SBG-ROS general status message.

Parameters
[in]ref_log_statusSBG status log.
Returns
General status message.

Definition at line 237 of file message_wrapper.cpp.

const sbg_driver::SbgUtcTimeStatus MessageWrapper::createUtcStatusMessage ( const SbgLogUtcData ref_log_utc) const
private

Create a SBG-ROS UTC time status message.

Parameters
[in]ref_log_utcSBG UTC data log.
Returns
UTC time status message.

Definition at line 250 of file message_wrapper.cpp.

uint32_t MessageWrapper::getNumberOfDaysInMonth ( uint16_t  year,
uint8_t  month_index 
) const
private

Get the number of days of the month index.

Parameters
[in]yearYear.
[in]month_indexMonth index [1..12].
Returns
Number of days in the month.

Definition at line 275 of file message_wrapper.cpp.

uint32_t MessageWrapper::getNumberOfDaysInYear ( uint16_t  year) const
private

Get the number of days in the year.

Parameters
[in]yearYear to get the number of days.
Returns
Number of days in the year.

Definition at line 263 of file message_wrapper.cpp.

bool MessageWrapper::isLeapYear ( uint16_t  year) const
private

Check if the given year is a leap year.

Parameters
[in]yearYear to check.
Returns
True if the year is a leap year.

Definition at line 298 of file message_wrapper.cpp.

void MessageWrapper::setRosProcessingTime ( const ros::Time ref_ros_time)

Set the wrapper processing ROS time. This method is call on the SbgDevice periodic handle, in order to have the same processing time for the messages.

Parameters
[in]ref_ros_timeROS processing time to set.

Definition at line 356 of file message_wrapper.cpp.

Member Data Documentation

bool sbg::MessageWrapper::m_first_valid_utc_
private

Definition at line 85 of file message_wrapper.h.

sbg_driver::SbgUtcTime sbg::MessageWrapper::m_last_sbg_utc_
private

Definition at line 84 of file message_wrapper.h.

ros::Time sbg::MessageWrapper::m_ros_processing_time_
private

Definition at line 83 of file message_wrapper.h.


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


sbg_driver
Author(s): SBG Systems
autogenerated on Thu Oct 22 2020 03:47:22