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 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_
 

Detailed Description

Class to wrap the SBG logs into ROS messages.

Definition at line 92 of file message_wrapper.h.

Constructor & Destructor Documentation

◆ MessageWrapper()

MessageWrapper::MessageWrapper ( void  )

Default constructor.

Class to wrap the SBG logs into ROS messages.

Definition at line 22 of file message_wrapper.cpp.

Member Function Documentation

◆ computeMeridian()

double MessageWrapper::computeMeridian ( int  zone_number) const
private

Compute UTM zone meridian.

Parameters
[in]zone_numberUTM Zone number.
Returns
Meridian angle, in degrees.

Definition at line 65 of file message_wrapper.cpp.

◆ convertInsTimeToUnix()

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

Convert INS timestamp from a SBG device to UNIX timestamp.

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

Definition at line 88 of file message_wrapper.cpp.

◆ convertUtcToUnix()

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

Convert the UTC time to an Unix time.

Parameters
[in]ref_sbg_utc_msgUTC message.
Returns
Converted Epoch time (in s).

Definition at line 324 of file message_wrapper.cpp.

◆ createAirDataStatusMessage()

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 359 of file message_wrapper.cpp.

◆ createEkfStatusMessage()

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 108 of file message_wrapper.cpp.

◆ createGpsPosStatusMessage()

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 136 of file message_wrapper.cpp.

◆ createGpsVelStatusMessage()

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 153 of file message_wrapper.cpp.

◆ createImuStatusMessage()

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 163 of file message_wrapper.cpp.

◆ createMagStatusMessage()

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 183 of file message_wrapper.cpp.

◆ createRosFluidPressureMessage()

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 1300 of file message_wrapper.cpp.

◆ createRosHeader()

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 70 of file message_wrapper.cpp.

◆ createRosImuMessage()

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 1016 of file message_wrapper.cpp.

◆ createRosMagneticMessage()

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 1167 of file message_wrapper.cpp.

◆ createRosNavSatFixMessage()

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 1259 of file message_wrapper.cpp.

◆ createRosOdoMessage() [1/3]

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.

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

Definition at line 1061 of file message_wrapper.cpp.

◆ createRosOdoMessage() [2/3]

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.

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

Definition at line 1068 of file message_wrapper.cpp.

◆ createRosOdoMessage() [3/3]

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.

Parameters
[in]ref_sbg_imu_msgSBG-ROS IMU message.
[in]ref_sbg_ekf_nav_msgSBG-ROS Ekf Nav message.
[in]orientationOrientation as a Tf2 quaternion.
[in]ref_sbg_ekf_euler_msgSBG-ROS Ekf Euler message.
Returns
ROS standard odometry message.

Definition at line 1078 of file message_wrapper.cpp.

◆ createRosPointStampedMessage()

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 1212 of file message_wrapper.cpp.

◆ createRosTemperatureMessage()

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 1156 of file message_wrapper.cpp.

◆ createRosTwistStampedMessage() [1/3]

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 1198 of file message_wrapper.cpp.

◆ createRosTwistStampedMessage() [2/3]

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_vel_msgSBG-ROS Ekf velocity 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 1177 of file message_wrapper.cpp.

◆ createRosTwistStampedMessage() [3/3]

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 1188 of file message_wrapper.cpp.

◆ createRosUtcTimeReferenceMessage()

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 1244 of file message_wrapper.cpp.

◆ createSbgAirDataMessage()

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 967 of file message_wrapper.cpp.

◆ createSbgEkfEulerMessage()

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 558 of file message_wrapper.cpp.

◆ createSbgEkfNavMessage()

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 586 of file message_wrapper.cpp.

◆ createSbgEkfQuatMessage()

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 631 of file message_wrapper.cpp.

◆ createSbgEventMessage()

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 661 of file message_wrapper.cpp.

◆ createSbgGpsHdtMessage()

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 682 of file message_wrapper.cpp.

◆ createSbgGpsPosMessage()

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 708 of file message_wrapper.cpp.

◆ createSbgGpsRawMessage()

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 742 of file message_wrapper.cpp.

◆ createSbgGpsVelMessage()

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 751 of file message_wrapper.cpp.

◆ createSbgImuDataMessage()

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 789 of file message_wrapper.cpp.

◆ createSbgImuShortMessage()

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 983 of file message_wrapper.cpp.

◆ createSbgMagCalibMessage()

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 870 of file message_wrapper.cpp.

◆ createSbgMagMessage()

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 838 of file message_wrapper.cpp.

◆ createSbgOdoVelMessage()

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 880 of file message_wrapper.cpp.

◆ createSbgShipMotionMessage()

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 893 of file message_wrapper.cpp.

◆ createSbgStatusMessage()

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 916 of file message_wrapper.cpp.

◆ createSbgUtcTimeMessage()

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 930 of file message_wrapper.cpp.

◆ createShipMotionStatusMessage()

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 202 of file message_wrapper.cpp.

◆ createStatusAidingMessage()

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 214 of file message_wrapper.cpp.

◆ createStatusComMessage()

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 230 of file message_wrapper.cpp.

◆ createStatusGeneralMessage()

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 258 of file message_wrapper.cpp.

◆ createUtcStatusMessage()

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 271 of file message_wrapper.cpp.

◆ fillTransform()

void MessageWrapper::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 
)
private

Fill a transformation.

Parameters
[in]ref_parent_frame_idParent frame ID.
[in]ref_child_frame_idChild frame ID.
[in]ref_posePose.
[out]ref_transform_stampedStamped transformation.

Definition at line 1042 of file message_wrapper.cpp.

◆ getNumberOfDaysInMonth()

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 296 of file message_wrapper.cpp.

◆ getNumberOfDaysInYear()

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 284 of file message_wrapper.cpp.

◆ initUTM()

void MessageWrapper::initUTM ( double  Lat,
double  Long,
double  altitude 
)
private

Set UTM initial position.

Parameters
[in]LatLatitude, in degrees.
[in]LongLongitude, in degrees.
[in]altitudeAltitude, in meters.

Definition at line 409 of file message_wrapper.cpp.

◆ isLeapYear()

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 319 of file message_wrapper.cpp.

◆ LLtoUTM()

void MessageWrapper::LLtoUTM ( double  Lat,
double  Long,
int  zoneNumber,
double &  UTMNorthing,
double &  UTMEasting 
) const
private

Convert latitude and longitude to a position relative to UTM initial position.

Parameters
[in]LatLatitude, in degrees.
[in]LongLongitude, in degrees.
[in]zoneNumberUTM zone number.
[out]UTMNorthingUTM northing, in meters.
[out]UTMEastingUTM easting, in meters.

Definition at line 454 of file message_wrapper.cpp.

◆ setFrameId()

void MessageWrapper::setFrameId ( const std::string &  frame_id)

Set Frame ID.

Parameters
[in]frame_idFrame ID.

Definition at line 519 of file message_wrapper.cpp.

◆ setOdomBaseFrameId()

void MessageWrapper::setOdomBaseFrameId ( const std::string &  ref_frame_id)

Set the odometry base frame ID.

Parameters
[in]ref_frame_idOdometry base frame ID.

Definition at line 544 of file message_wrapper.cpp.

◆ setOdomEnable()

void MessageWrapper::setOdomEnable ( bool  odom_enable)

Set odom enable.

Parameters
[in]odom_enableIf true enable odometry.

Definition at line 529 of file message_wrapper.cpp.

◆ setOdomFrameId()

void MessageWrapper::setOdomFrameId ( const std::string &  ref_frame_id)

Set the odometry frame ID.

Parameters
[in]ref_frame_idOdometry frame ID.

Definition at line 539 of file message_wrapper.cpp.

◆ setOdomInitFrameId()

void MessageWrapper::setOdomInitFrameId ( const std::string &  ref_frame_id)

Set the odometry init frame ID.

Parameters
[in]ref_frame_idOdometry init frame ID.

Definition at line 549 of file message_wrapper.cpp.

◆ setOdomPublishTf()

void MessageWrapper::setOdomPublishTf ( bool  publish_tf)

Set odom publish_tf.

Parameters
[in]publish_tfIf true publish odometry transforms.

Definition at line 534 of file message_wrapper.cpp.

◆ setTimeReference()

void MessageWrapper::setTimeReference ( TimeReference  time_reference)

Set the time reference.

Parameters
[in]time_referenceTime reference.

Definition at line 514 of file message_wrapper.cpp.

◆ setUseEnu()

void MessageWrapper::setUseEnu ( bool  enu)

Set use ENU.

Parameters
[in]enuIf true publish data in the ENU convention.

Definition at line 524 of file message_wrapper.cpp.

◆ UTMLetterDesignator()

char MessageWrapper::UTMLetterDesignator ( double  Lat)
private

Get UTM letter designator for the given latitude.

Parameters
[in]LatLatitude, in degrees.
Returns
UTM letter designator.

Get UTM letter designator for the given latitude.

Returns
'Z' if latitude is outside the UTM limits of 84N to 80S

Written by Chuck Gantz- chuck.nosp@m..gan.nosp@m.tz@gl.nosp@m.obal.nosp@m.star..nosp@m.com

Definition at line 380 of file message_wrapper.cpp.

◆ wrapAngle2Pi()

float MessageWrapper::wrapAngle2Pi ( float  angle_rad) const
private

Wrap an angle to 2 PI.

Parameters
[in]angle_radAngle in rad.
Returns
Wrapped angle.

Definition at line 35 of file message_wrapper.cpp.

◆ wrapAngle360()

float MessageWrapper::wrapAngle360 ( float  angle_deg) const
private

Wrap an angle to 360 degres.

Parameters
[in]angle_degAngle in degree.
Returns
Wrapped angle.

Definition at line 50 of file message_wrapper.cpp.

Member Data Documentation

◆ m_first_valid_utc_

bool sbg::MessageWrapper::m_first_valid_utc_
private

Definition at line 98 of file message_wrapper.h.

◆ m_frame_id_

std::string sbg::MessageWrapper::m_frame_id_
private

Definition at line 99 of file message_wrapper.h.

◆ m_last_sbg_utc_

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

Definition at line 97 of file message_wrapper.h.

◆ m_odom_base_frame_id_

std::string sbg::MessageWrapper::m_odom_base_frame_id_
private

Definition at line 109 of file message_wrapper.h.

◆ m_odom_enable_

bool sbg::MessageWrapper::m_odom_enable_
private

Definition at line 106 of file message_wrapper.h.

◆ m_odom_frame_id_

std::string sbg::MessageWrapper::m_odom_frame_id_
private

Definition at line 108 of file message_wrapper.h.

◆ m_odom_init_frame_id_

std::string sbg::MessageWrapper::m_odom_init_frame_id_
private

Definition at line 110 of file message_wrapper.h.

◆ m_odom_publish_tf_

bool sbg::MessageWrapper::m_odom_publish_tf_
private

Definition at line 107 of file message_wrapper.h.

◆ m_ros_processing_time_

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

Definition at line 96 of file message_wrapper.h.

◆ m_static_tf_broadcaster_

tf2_ros::StaticTransformBroadcaster sbg::MessageWrapper::m_static_tf_broadcaster_
private

Definition at line 104 of file message_wrapper.h.

◆ m_tf_broadcaster_

tf2_ros::TransformBroadcaster sbg::MessageWrapper::m_tf_broadcaster_
private

Definition at line 103 of file message_wrapper.h.

◆ m_time_reference_

TimeReference sbg::MessageWrapper::m_time_reference_
private

Definition at line 101 of file message_wrapper.h.

◆ m_use_enu_

bool sbg::MessageWrapper::m_use_enu_
private

Definition at line 100 of file message_wrapper.h.

◆ m_utm0_

UTM0 sbg::MessageWrapper::m_utm0_
private

Definition at line 102 of file message_wrapper.h.


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


sbg_driver
Author(s): SBG Systems
autogenerated on Sat Sep 3 2022 02:53:36