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

#include <message_publisher.h>

Public Member Functions

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

Private Member Functions

void defineRosStandardPublishers (ros::NodeHandle &ref_ros_node_handle, bool odom_enable, bool enu_enable)
 
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 processRosOdoMessage ()
 
void processRosVelMessage ()
 
void publishEkfNavigationData (const SbgBinaryLogData &ref_sbg_log)
 
void publishFluidPressureData (const SbgBinaryLogData &ref_sbg_log)
 
void publishGpsPosData (const SbgBinaryLogData &ref_sbg_log, SbgEComMsgId sbg_msg_id)
 
void publishIMUData (const SbgBinaryLogData &ref_sbg_log)
 
void publishMagData (const SbgBinaryLogData &ref_sbg_log)
 
void publishUtcData (const SbgBinaryLogData &ref_sbg_log)
 

Private Attributes

ros::Publisher fluid_pub_
 
std::string frame_id_
 
ros::Publisher imu_pub_
 
ros::Publisher mag_pub_
 
uint32_t max_messages_
 
MessageWrapper message_wrapper_
 
ros::Publisher nav_sat_fix_pub_
 
ros::Publisher nmea_gga_pub_
 
ros::Publisher odometry_pub_
 
ros::Publisher pos_ecef_pub_
 
ros::Publisher sbg_air_data_pub_
 
sbg_driver::SbgEkfEuler sbg_ekf_euler_message_
 
sbg_driver::SbgEkfNav sbg_ekf_nav_message_
 
ros::Publisher sbg_ekf_nav_pub_
 
sbg_driver::SbgEkfQuat sbg_ekf_quat_message_
 
ros::Publisher sbg_ekf_quat_pub_
 
ros::Publisher sbg_ekf_ruler_pub_
 
ros::Publisher sbg_event_A_pub_
 
ros::Publisher sbg_event_B_pub_
 
ros::Publisher sbg_event_C_pub_
 
ros::Publisher sbg_event_D_pub_
 
ros::Publisher sbg_event_E_pub_
 
ros::Publisher sbg_gps_hdt_pub_
 
ros::Publisher sbg_gps_pos_pub_
 
ros::Publisher sbg_gps_raw_pub_
 
ros::Publisher sbg_gps_vel_pub_
 
ros::Publisher sbg_imu_data_pub_
 
sbg_driver::SbgImuData sbg_imu_message_
 
ros::Publisher sbg_imu_short_pub_
 
ros::Publisher sbg_mag_calib_pub_
 
ros::Publisher sbg_mag_pub_
 
ros::Publisher sbg_odo_vel_pub_
 
ros::Publisher sbg_ship_motion_pub_
 
ros::Publisher sbg_status_pub_
 
ros::Publisher sbg_utc_time_pub_
 
ros::Publisher temp_pub_
 
ros::Publisher utc_reference_pub_
 
ros::Publisher 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::MessagePublisher ( )

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

◆ defineRosStandardPublishers()

void MessagePublisher::defineRosStandardPublishers ( ros::NodeHandle ref_ros_node_handle,
bool  odom_enable,
bool  enu_enable 
)
private

Define standard ROS publishers.

Parameters
[in]ref_ros_node_handleRos NodeHandle to advertise the publisher.
[in]odom_enableIf true, enable odometry messages.

Definition at line 203 of file message_publisher.cpp.

◆ getOutputTopicName()

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 21 of file message_publisher.cpp.

◆ initPublisher()

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 100 of file message_publisher.cpp.

◆ initPublishers()

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 472 of file message_publisher.cpp.

◆ processRosImuMessage()

void MessagePublisher::processRosImuMessage ( )
private

Process a ROS IMU standard message.

Definition at line 336 of file message_publisher.cpp.

◆ processRosOdoMessage()

void MessagePublisher::processRosOdoMessage ( )
private

Process a ROS odometry standard message.

Definition at line 347 of file message_publisher.cpp.

◆ processRosVelMessage()

void MessagePublisher::processRosVelMessage ( )
private

Process a ROS Velocity standard message.

Definition at line 321 of file message_publisher.cpp.

◆ publish()

void MessagePublisher::publish ( 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]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 507 of file message_publisher.cpp.

◆ publishEkfNavigationData()

void MessagePublisher::publishEkfNavigationData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG EkfNav log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 408 of file message_publisher.cpp.

◆ publishFluidPressureData()

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 393 of file message_publisher.cpp.

◆ publishGpsPosData()

void MessagePublisher::publishGpsPosData ( const SbgBinaryLogData ref_sbg_log,
SbgEComMsgId  sbg_msg_id 
)
private

Publish a received SBG GpsPos log.

Parameters
[in]ref_sbg_logSBG log.
[in]sbg_msg_idId of the SBG message.

Definition at line 442 of file message_publisher.cpp.

◆ publishIMUData()

void MessagePublisher::publishIMUData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG IMU log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 304 of file message_publisher.cpp.

◆ publishMagData()

void MessagePublisher::publishMagData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG Magnetic log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 378 of file message_publisher.cpp.

◆ publishUtcData()

void MessagePublisher::publishUtcData ( const SbgBinaryLogData ref_sbg_log)
private

Publish a received SBG UTC log.

Parameters
[in]ref_sbg_logSBG log.

Definition at line 423 of file message_publisher.cpp.

Member Data Documentation

◆ fluid_pub_

ros::Publisher sbg::MessagePublisher::fluid_pub_
private

Definition at line 78 of file message_publisher.h.

◆ frame_id_

std::string sbg::MessagePublisher::frame_id_
private

Definition at line 89 of file message_publisher.h.

◆ imu_pub_

ros::Publisher sbg::MessagePublisher::imu_pub_
private

Definition at line 70 of file message_publisher.h.

◆ mag_pub_

ros::Publisher sbg::MessagePublisher::mag_pub_
private

Definition at line 77 of file message_publisher.h.

◆ max_messages_

uint32_t sbg::MessagePublisher::max_messages_
private

Definition at line 88 of file message_publisher.h.

◆ message_wrapper_

MessageWrapper sbg::MessagePublisher::message_wrapper_
private

Definition at line 87 of file message_publisher.h.

◆ nav_sat_fix_pub_

ros::Publisher sbg::MessagePublisher::nav_sat_fix_pub_
private

Definition at line 82 of file message_publisher.h.

◆ nmea_gga_pub_

ros::Publisher sbg::MessagePublisher::nmea_gga_pub_
private

Definition at line 85 of file message_publisher.h.

◆ odometry_pub_

ros::Publisher sbg::MessagePublisher::odometry_pub_
private

Definition at line 83 of file message_publisher.h.

◆ pos_ecef_pub_

ros::Publisher sbg::MessagePublisher::pos_ecef_pub_
private

Definition at line 79 of file message_publisher.h.

◆ sbg_air_data_pub_

ros::Publisher sbg::MessagePublisher::sbg_air_data_pub_
private

Definition at line 68 of file message_publisher.h.

◆ sbg_ekf_euler_message_

sbg_driver::SbgEkfEuler sbg::MessagePublisher::sbg_ekf_euler_message_
private

Definition at line 74 of file message_publisher.h.

◆ sbg_ekf_nav_message_

sbg_driver::SbgEkfNav sbg::MessagePublisher::sbg_ekf_nav_message_
private

Definition at line 73 of file message_publisher.h.

◆ sbg_ekf_nav_pub_

ros::Publisher sbg::MessagePublisher::sbg_ekf_nav_pub_
private

Definition at line 53 of file message_publisher.h.

◆ sbg_ekf_quat_message_

sbg_driver::SbgEkfQuat sbg::MessagePublisher::sbg_ekf_quat_message_
private

Definition at line 72 of file message_publisher.h.

◆ sbg_ekf_quat_pub_

ros::Publisher sbg::MessagePublisher::sbg_ekf_quat_pub_
private

Definition at line 52 of file message_publisher.h.

◆ sbg_ekf_ruler_pub_

ros::Publisher sbg::MessagePublisher::sbg_ekf_ruler_pub_
private

Definition at line 51 of file message_publisher.h.

◆ sbg_event_A_pub_

ros::Publisher sbg::MessagePublisher::sbg_event_A_pub_
private

Definition at line 62 of file message_publisher.h.

◆ sbg_event_B_pub_

ros::Publisher sbg::MessagePublisher::sbg_event_B_pub_
private

Definition at line 63 of file message_publisher.h.

◆ sbg_event_C_pub_

ros::Publisher sbg::MessagePublisher::sbg_event_C_pub_
private

Definition at line 64 of file message_publisher.h.

◆ sbg_event_D_pub_

ros::Publisher sbg::MessagePublisher::sbg_event_D_pub_
private

Definition at line 65 of file message_publisher.h.

◆ sbg_event_E_pub_

ros::Publisher sbg::MessagePublisher::sbg_event_E_pub_
private

Definition at line 66 of file message_publisher.h.

◆ sbg_gps_hdt_pub_

ros::Publisher sbg::MessagePublisher::sbg_gps_hdt_pub_
private

Definition at line 59 of file message_publisher.h.

◆ sbg_gps_pos_pub_

ros::Publisher sbg::MessagePublisher::sbg_gps_pos_pub_
private

Definition at line 58 of file message_publisher.h.

◆ sbg_gps_raw_pub_

ros::Publisher sbg::MessagePublisher::sbg_gps_raw_pub_
private

Definition at line 60 of file message_publisher.h.

◆ sbg_gps_vel_pub_

ros::Publisher sbg::MessagePublisher::sbg_gps_vel_pub_
private

Definition at line 57 of file message_publisher.h.

◆ sbg_imu_data_pub_

ros::Publisher sbg::MessagePublisher::sbg_imu_data_pub_
private

Definition at line 50 of file message_publisher.h.

◆ sbg_imu_message_

sbg_driver::SbgImuData sbg::MessagePublisher::sbg_imu_message_
private

Definition at line 71 of file message_publisher.h.

◆ sbg_imu_short_pub_

ros::Publisher sbg::MessagePublisher::sbg_imu_short_pub_
private

Definition at line 67 of file message_publisher.h.

◆ sbg_mag_calib_pub_

ros::Publisher sbg::MessagePublisher::sbg_mag_calib_pub_
private

Definition at line 56 of file message_publisher.h.

◆ sbg_mag_pub_

ros::Publisher sbg::MessagePublisher::sbg_mag_pub_
private

Definition at line 55 of file message_publisher.h.

◆ sbg_odo_vel_pub_

ros::Publisher sbg::MessagePublisher::sbg_odo_vel_pub_
private

Definition at line 61 of file message_publisher.h.

◆ sbg_ship_motion_pub_

ros::Publisher sbg::MessagePublisher::sbg_ship_motion_pub_
private

Definition at line 54 of file message_publisher.h.

◆ sbg_status_pub_

ros::Publisher sbg::MessagePublisher::sbg_status_pub_
private

Definition at line 48 of file message_publisher.h.

◆ sbg_utc_time_pub_

ros::Publisher sbg::MessagePublisher::sbg_utc_time_pub_
private

Definition at line 49 of file message_publisher.h.

◆ temp_pub_

ros::Publisher sbg::MessagePublisher::temp_pub_
private

Definition at line 76 of file message_publisher.h.

◆ utc_reference_pub_

ros::Publisher sbg::MessagePublisher::utc_reference_pub_
private

Definition at line 81 of file message_publisher.h.

◆ velocity_pub_

ros::Publisher sbg::MessagePublisher::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 Fri Oct 11 2024 02:13:41