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

#include <message_publisher.h>

Public Member Functions

uint32_t getMaxOutputFrequency (void) const
 
void initPublishers (ros::NodeHandle &ref_ros_node_handle, const ConfigStore &ref_config_store)
 
 MessagePublisher (void)
 
void publish (const ros::Time &ref_ros_time, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id, const SbgBinaryLogData &ref_sbg_log)
 

Private Member Functions

void defineRosStandardPublishers (ros::NodeHandle &ref_ros_node_handle)
 
uint32_t getCorrespondingFrequency (SbgEComOutputMode output_mode) const
 
std::string getOutputTopicName (SbgEComMsgId sbg_message_id) const
 
void initPublisher (ros::NodeHandle &ref_ros_node_handle, SbgEComMsgId sbg_msg_id, SbgEComOutputMode output_conf, const std::string &ref_output_topic)
 
void processRosImuMessage (void)
 
void processRosVelMessage (void)
 
void publishEkfNavigationData (const SbgBinaryLogData &ref_sbg_log)
 
void publishFluidPressureData (const SbgBinaryLogData &ref_sbg_log)
 
void publishGpsPosData (const SbgBinaryLogData &ref_sbg_log)
 
void publishIMUData (const SbgBinaryLogData &ref_sbg_log)
 
void publishMagData (const SbgBinaryLogData &ref_sbg_log)
 
void publishUtcData (const SbgBinaryLogData &ref_sbg_log)
 
void updateMaxOutputFrequency (SbgEComOutputMode output_mode)
 

Private Attributes

ros::Publisher m_fluid_pub_
 
ros::Publisher m_imu_pub_
 
ros::Publisher m_mag_pub_
 
uint32_t m_max_mesages_
 
MessageWrapper m_message_wrapper_
 
ros::Publisher m_nav_sat_fix_pub_
 
SbgEComOutputMode m_output_mode_
 
ros::Publisher m_pos_ecef_pub_
 
sbg_driver::SbgEkfEuler m_sbg_ekf_euler_message_
 
sbg_driver::SbgEkfNav m_sbg_ekf_nav_message_
 
sbg_driver::SbgEkfQuat m_sbg_ekf_quat_message_
 
sbg_driver::SbgImuData m_sbg_imu_message_
 
ros::Publisher m_sbgAirData_pub_
 
ros::Publisher m_sbgEkfEuler_pub_
 
ros::Publisher m_sbgEkfNav_pub_
 
ros::Publisher m_sbgEkfQuat_pub_
 
ros::Publisher m_sbgEventA_pub_
 
ros::Publisher m_sbgEventB_pub_
 
ros::Publisher m_sbgEventC_pub_
 
ros::Publisher m_sbgEventD_pub_
 
ros::Publisher m_sbgEventE_pub_
 
ros::Publisher m_sbgGpsHdt_pub_
 
ros::Publisher m_sbgGpsPos_pub_
 
ros::Publisher m_sbgGpsRaw_pub_
 
ros::Publisher m_sbgGpsVel_pub_
 
ros::Publisher m_sbgImuData_pub_
 
ros::Publisher m_sbgImuShort_pub_
 
ros::Publisher m_sbgMag_pub_
 
ros::Publisher m_sbgMagCalib_pub_
 
ros::Publisher m_sbgOdoVel_pub_
 
ros::Publisher m_sbgShipMotion_pub_
 
ros::Publisher m_sbgStatus_pub_
 
ros::Publisher m_sbgUtcTime_pub_
 
ros::Publisher m_temp_pub_
 
ros::Publisher m_utc_reference_pub_
 
ros::Publisher m_velocity_pub_
 

Detailed Description

Class to publish all SBG-ROS messages to the corresponding publishers.

Definition at line 44 of file message_publisher.h.

Constructor & Destructor Documentation

MessagePublisher::MessagePublisher ( void  )

Default constructor.

Class to publish all SBG-ROS messages to the corresponding publishers.

Definition at line 12 of file message_publisher.cpp.

Member Function Documentation

void MessagePublisher::defineRosStandardPublishers ( ros::NodeHandle ref_ros_node_handle)
private

Define standard ROS publishers.

Parameters
[in]ref_ros_node_handleRos NodeHandle to advertise the publisher.

Definition at line 285 of file message_publisher.cpp.

uint32_t MessagePublisher::getCorrespondingFrequency ( SbgEComOutputMode  output_mode) const
private

Get the corresponding frequency for the SBG output mode.

Parameters
[in]output_modeOutput mode.
Returns
Output frequency (in Hz).

Definition at line 49 of file message_publisher.cpp.

uint32_t MessagePublisher::getMaxOutputFrequency ( void  ) const

Get the maximal output frequency for the publisher.

Returns
Maixmal output frequency (in Hz).

Definition at line 490 of file message_publisher.cpp.

std::string MessagePublisher::getOutputTopicName ( SbgEComMsgId  sbg_message_id) const
private

Get the corresponding topic name output for the SBG output mode.

Parameters
[in]sbg_message_idSBG message ID.
Returns
Output topic name.

Definition at line 94 of file message_publisher.cpp.

void MessagePublisher::initPublisher ( ros::NodeHandle ref_ros_node_handle,
SbgEComMsgId  sbg_msg_id,
SbgEComOutputMode  output_conf,
const std::string &  ref_output_topic 
)
private

Initialize the publisher for the specified SBG Id, and the output configuration.

Parameters
[in]ref_ros_node_handleRos NodeHandle to advertise the publisher.
[in]sbg_msg_idId of the SBG message.
[in]output_confOutput configuration.
[in]ref_output_topicOutput topic for the publisher.

Definition at line 166 of file message_publisher.cpp.

void MessagePublisher::initPublishers ( ros::NodeHandle ref_ros_node_handle,
const ConfigStore ref_config_store 
)

Initialize the publishers for the output configuration.

Parameters
[in]ref_ros_node_handleRos NodeHandle to advertise the publisher.
[in]ref_config_storeStore configuration for the publishers.

Definition at line 499 of file message_publisher.cpp.

void MessagePublisher::processRosImuMessage ( void  )
private

Process a ROS IMU standard message.

Definition at line 395 of file message_publisher.cpp.

void MessagePublisher::processRosVelMessage ( void  )
private

Process a ROS Velocity standard message.

Definition at line 380 of file message_publisher.cpp.

void MessagePublisher::publish ( const ros::Time ref_ros_time,
SbgEComClass  sbg_msg_class,
SbgEComMsgId  sbg_msg_id,
const SbgBinaryLogData ref_sbg_log 
)

Publish the received SbgLog if the corresponding publisher is defined.

Parameters
[in]ref_ros_timeROS processing time for the messages.
[in]sbg_msg_classClass ID of the SBG message.
[in]sbg_msg_idId of the SBG message.
[in]ref_sbg_logSBG binary log.

Definition at line 517 of file message_publisher.cpp.

void MessagePublisher::publishEkfNavigationData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG EkfNav log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 436 of file message_publisher.cpp.

void MessagePublisher::publishFluidPressureData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG Fluid pressure log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 421 of file message_publisher.cpp.

void MessagePublisher::publishGpsPosData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG GpsPos log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 470 of file message_publisher.cpp.

void MessagePublisher::publishIMUData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG IMU log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 364 of file message_publisher.cpp.

void MessagePublisher::publishMagData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG Magnetic log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 406 of file message_publisher.cpp.

void MessagePublisher::publishUtcData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG UTC log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 451 of file message_publisher.cpp.

void MessagePublisher::updateMaxOutputFrequency ( SbgEComOutputMode  output_mode)
private

Update the maximal output frequency for the defined pubishers. Each time a new publisher is defined, update the maximal output frequency if required.

Parameters
[in]output_mode_freqOutput mode.

Definition at line 23 of file message_publisher.cpp.

Member Data Documentation

ros::Publisher sbg::MessagePublisher::m_fluid_pub_
private

Definition at line 78 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_imu_pub_
private

Definition at line 70 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_mag_pub_
private

Definition at line 77 of file message_publisher.h.

uint32_t sbg::MessagePublisher::m_max_mesages_
private

Definition at line 86 of file message_publisher.h.

MessageWrapper sbg::MessagePublisher::m_message_wrapper_
private

Definition at line 84 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_nav_sat_fix_pub_
private

Definition at line 82 of file message_publisher.h.

SbgEComOutputMode sbg::MessagePublisher::m_output_mode_
private

Definition at line 85 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_pos_ecef_pub_
private

Definition at line 79 of file message_publisher.h.

sbg_driver::SbgEkfEuler sbg::MessagePublisher::m_sbg_ekf_euler_message_
private

Definition at line 74 of file message_publisher.h.

sbg_driver::SbgEkfNav sbg::MessagePublisher::m_sbg_ekf_nav_message_
private

Definition at line 73 of file message_publisher.h.

sbg_driver::SbgEkfQuat sbg::MessagePublisher::m_sbg_ekf_quat_message_
private

Definition at line 72 of file message_publisher.h.

sbg_driver::SbgImuData sbg::MessagePublisher::m_sbg_imu_message_
private

Definition at line 71 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgAirData_pub_
private

Definition at line 68 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEkfEuler_pub_
private

Definition at line 51 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEkfNav_pub_
private

Definition at line 53 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEkfQuat_pub_
private

Definition at line 52 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEventA_pub_
private

Definition at line 62 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEventB_pub_
private

Definition at line 63 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEventC_pub_
private

Definition at line 64 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEventD_pub_
private

Definition at line 65 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgEventE_pub_
private

Definition at line 66 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgGpsHdt_pub_
private

Definition at line 59 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgGpsPos_pub_
private

Definition at line 58 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgGpsRaw_pub_
private

Definition at line 60 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgGpsVel_pub_
private

Definition at line 57 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgImuData_pub_
private

Definition at line 50 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgImuShort_pub_
private

Definition at line 67 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgMag_pub_
private

Definition at line 55 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgMagCalib_pub_
private

Definition at line 56 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgOdoVel_pub_
private

Definition at line 61 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgShipMotion_pub_
private

Definition at line 54 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgStatus_pub_
private

Definition at line 48 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_sbgUtcTime_pub_
private

Definition at line 49 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_temp_pub_
private

Definition at line 76 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_utc_reference_pub_
private

Definition at line 81 of file message_publisher.h.

ros::Publisher sbg::MessagePublisher::m_velocity_pub_
private

Definition at line 80 of file message_publisher.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