message_publisher.h
Go to the documentation of this file.
1 
32 #ifndef SBG_ROS_MESSAGE_PUBLISHER_H
33 #define SBG_ROS_MESSAGE_PUBLISHER_H
34 
35 // Project headers
36 #include <config_store.h>
37 #include <message_wrapper.h>
38 
39 namespace sbg
40 {
45 {
46 private:
47 
69 
71  sbg_driver::SbgImuData m_sbg_imu_message_;
72  sbg_driver::SbgEkfQuat m_sbg_ekf_quat_message_;
73  sbg_driver::SbgEkfNav m_sbg_ekf_nav_message_;
74  sbg_driver::SbgEkfEuler m_sbg_ekf_euler_message_;
75 
84 
86  uint32_t m_max_messages_;
87  std::string m_frame_id_;
88 
89  //---------------------------------------------------------------------//
90  //- Private methods -//
91  //---------------------------------------------------------------------//
92 
99  std::string getOutputTopicName(SbgEComMsgId sbg_message_id) const;
100 
109  void initPublisher(ros::NodeHandle& ref_ros_node_handle, SbgEComMsgId sbg_msg_id, SbgEComOutputMode output_conf, const std::string &ref_output_topic);
110 
117  void defineRosStandardPublishers(ros::NodeHandle& ref_ros_node_handle, bool odom_enable);
118 
124  void publishIMUData(const SbgBinaryLogData &ref_sbg_log);
125 
129  void processRosVelMessage(void);
130 
134  void processRosImuMessage(void);
135 
139  void processRosOdoMessage(void);
140 
146  void publishMagData(const SbgBinaryLogData &ref_sbg_log);
147 
153  void publishFluidPressureData(const SbgBinaryLogData &ref_sbg_log);
154 
160  void publishEkfNavigationData(const SbgBinaryLogData &ref_sbg_log);
161 
167  void publishUtcData(const SbgBinaryLogData &ref_sbg_log);
168 
174  void publishGpsPosData(const SbgBinaryLogData &ref_sbg_log);
175 
176 public:
177 
178  //---------------------------------------------------------------------//
179  //- Constructor -//
180  //---------------------------------------------------------------------//
181 
185  MessagePublisher(void);
186 
187  //---------------------------------------------------------------------//
188  //- Operations -//
189  //---------------------------------------------------------------------//
190 
197  void initPublishers(ros::NodeHandle& ref_ros_node_handle, const ConfigStore &ref_config_store);
198 
206  void publish(SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id, const SbgBinaryLogData &ref_sbg_log);
207 };
208 }
209 
210 #endif // SBG_ROS_MESSAGE_PUBLISHER_H
ros::Publisher m_sbgGpsVel_pub_
ros::Publisher m_imu_pub_
ros::Publisher m_pos_ecef_pub_
void defineRosStandardPublishers(ros::NodeHandle &ref_ros_node_handle, bool odom_enable)
ros::Publisher m_sbgImuShort_pub_
MessageWrapper m_message_wrapper_
std::string getOutputTopicName(SbgEComMsgId sbg_message_id) const
ros::Publisher m_sbgImuData_pub_
void publishIMUData(const SbgBinaryLogData &ref_sbg_log)
ros::Publisher m_sbgEkfQuat_pub_
Handle creation of messages.
void publish(SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id, const SbgBinaryLogData &ref_sbg_log)
void publishEkfNavigationData(const SbgBinaryLogData &ref_sbg_log)
ros::Publisher m_odometry_pub_
ros::Publisher m_sbgUtcTime_pub_
void publishMagData(const SbgBinaryLogData &ref_sbg_log)
ros::Publisher m_sbgEventD_pub_
void initPublisher(ros::NodeHandle &ref_ros_node_handle, SbgEComMsgId sbg_msg_id, SbgEComOutputMode output_conf, const std::string &ref_output_topic)
Class to handle the device configuration.
ros::Publisher m_sbgGpsPos_pub_
ros::Publisher m_sbgEkfNav_pub_
ros::Publisher m_sbgEventB_pub_
void publishUtcData(const SbgBinaryLogData &ref_sbg_log)
sbg_driver::SbgEkfQuat m_sbg_ekf_quat_message_
ros::Publisher m_temp_pub_
ros::Publisher m_mag_pub_
ros::Publisher m_utc_reference_pub_
ros::Publisher m_sbgGpsRaw_pub_
void publishGpsPosData(const SbgBinaryLogData &ref_sbg_log)
ros::Publisher m_sbgEventC_pub_
ros::Publisher m_sbgMagCalib_pub_
ros::Publisher m_sbgEventA_pub_
uint8_t SbgEComMsgId
Definition: sbgEComIds.h:289
ros::Publisher m_sbgGpsHdt_pub_
ros::Publisher m_sbgEventE_pub_
ros::Publisher m_sbgAirData_pub_
ros::Publisher m_sbgShipMotion_pub_
void publishFluidPressureData(const SbgBinaryLogData &ref_sbg_log)
void initPublishers(ros::NodeHandle &ref_ros_node_handle, const ConfigStore &ref_config_store)
ros::Publisher m_sbgStatus_pub_
enum _SbgEComClass SbgEComClass
ros::Publisher m_fluid_pub_
ros::Publisher m_nav_sat_fix_pub_
sbg_driver::SbgEkfEuler m_sbg_ekf_euler_message_
enum _SbgEComOutputMode SbgEComOutputMode
sbg_driver::SbgImuData m_sbg_imu_message_
ros::Publisher m_sbgOdoVel_pub_
sbg_driver::SbgEkfNav m_sbg_ekf_nav_message_
ros::Publisher m_sbgEkfEuler_pub_
ros::Publisher m_velocity_pub_
ros::Publisher m_sbgMag_pub_


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