Program Listing for File message_publisher.h

Return to documentation for file (include/sbg_driver/message_publisher.h)

#ifndef SBG_ROS_MESSAGE_PUBLISHER_H
#define SBG_ROS_MESSAGE_PUBLISHER_H

// Project headers
#include <config_store.h>
#include <message_wrapper.h>

namespace sbg
{
class MessagePublisher
{
private:

  rclcpp::Publisher<sbg_driver::msg::SbgStatus, std::allocator<void>>::SharedPtr        sbg_status_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgUtcTime, std::allocator<void>>::SharedPtr       sbg_utc_time_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgImuData, std::allocator<void>>::SharedPtr       sbg_imu_data_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEkfEuler, std::allocator<void>>::SharedPtr      sbg_ekf_euler_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEkfQuat, std::allocator<void>>::SharedPtr       sbg_ekf_quat_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEkfNav, std::allocator<void>>::SharedPtr        sbg_ekf_nav_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEkfVelBody, std::allocator<void>>::SharedPtr    sbg_ekf_vel_body_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEkfRotAccel, std::allocator<void>>::SharedPtr   sbg_ekf_rot_accel_body_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEkfRotAccel, std::allocator<void>>::SharedPtr   sbg_ekf_rot_accel_ned_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgShipMotion, std::allocator<void>>::SharedPtr    sbg_ship_motion_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgMag, std::allocator<void>>::SharedPtr           sbg_mag_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgMagCalib, std::allocator<void>>::SharedPtr      sbg_mag_calib_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgGpsVel, std::allocator<void>>::SharedPtr        sbg_gps_vel_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgGpsPos, std::allocator<void>>::SharedPtr        sbg_gps_pos_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgGpsHdt, std::allocator<void>>::SharedPtr        sbg_gps_hdt_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgGpsRaw, std::allocator<void>>::SharedPtr        sbg_gps_raw_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgOdoVel, std::allocator<void>>::SharedPtr        sbg_odo_vel_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEvent, std::allocator<void>>::SharedPtr         sbg_event_a_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEvent, std::allocator<void>>::SharedPtr         sbg_event_b_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEvent, std::allocator<void>>::SharedPtr         sbg_event_c_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEvent, std::allocator<void>>::SharedPtr         sbg_event_d_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgEvent, std::allocator<void>>::SharedPtr         sbg_event_e_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgImuShort, std::allocator<void>>::SharedPtr      sbg_imu_short_pub_;
  rclcpp::Publisher<sbg_driver::msg::SbgAirData, std::allocator<void>>::SharedPtr       sbg_air_data_pub_;

  rclcpp::Publisher<sensor_msgs::msg::Imu, std::allocator<void>>::SharedPtr             imu_pub_;
  sbg_driver::msg::SbgImuData                                                           sbg_imu_message_;
  sbg_driver::msg::SbgEkfQuat                                                           sbg_ekf_quat_message_;
  sbg_driver::msg::SbgEkfNav                                                            sbg_ekf_nav_message_;
  sbg_driver::msg::SbgEkfEuler                                                          sbg_ekf_euler_message_;

  rclcpp::Publisher<sensor_msgs::msg::Temperature, std::allocator<void>>::SharedPtr     temp_pub_;
  rclcpp::Publisher<sensor_msgs::msg::MagneticField, std::allocator<void>>::SharedPtr   mag_pub_;
  rclcpp::Publisher<sensor_msgs::msg::FluidPressure, std::allocator<void>>::SharedPtr   fluid_pub_;
  rclcpp::Publisher<geometry_msgs::msg::PointStamped, std::allocator<void>>::SharedPtr  pos_ecef_pub_;
  rclcpp::Publisher<geometry_msgs::msg::TwistStamped, std::allocator<void>>::SharedPtr  velocity_pub_;
  rclcpp::Publisher<sensor_msgs::msg::TimeReference, std::allocator<void>>::SharedPtr   utc_reference_pub_;
  rclcpp::Publisher<sensor_msgs::msg::NavSatFix, std::allocator<void>>::SharedPtr       nav_sat_fix_pub_;
  rclcpp::Publisher<nav_msgs::msg::Odometry, std::allocator<void>>::SharedPtr           odometry_pub_;

  rclcpp::Publisher<nmea_msgs::msg::Sentence, std::allocator<void>>::SharedPtr          nmea_gga_pub_;

  MessageWrapper                                                                        message_wrapper_;
  uint32_t                                                                              max_messages_;
  std::string                                                                           frame_id_;

  //---------------------------------------------------------------------//
  //- Private methods                                                   -//
  //---------------------------------------------------------------------//

  std::string getOutputTopicName(SbgEComMsgId sbg_message_id) const;

  void initPublisher(rclcpp::Node& ref_ros_node_handle, SbgEComMsgId sbg_msg_id, SbgEComOutputMode output_conf, const std::string &ref_output_topic);

  void defineRosStandardPublishers(rclcpp::Node& ref_ros_node_handle, bool odom_enable, bool enu_enable);

  void publishIMUData(const SbgEComLogUnion &ref_sbg_log);

  void processRosVelMessage();

  void processRosImuMessage();

  void processRosOdoMessage();

  void publishMagData(const SbgEComLogUnion &ref_sbg_log);

  void publishFluidPressureData(const SbgEComLogUnion &ref_sbg_log);

  void publishEkfNavigationData(const SbgEComLogUnion &ref_sbg_log);

  void publishUtcData(const SbgEComLogUnion &ref_sbg_log);

  void publishGpsPosData(const SbgEComLogUnion &ref_sbg_log, SbgEComMsgId sbg_msg_id);

public:

  //---------------------------------------------------------------------//
  //- Constructor                                                       -//
  //---------------------------------------------------------------------//

  MessagePublisher();

  //---------------------------------------------------------------------//
  //- Operations                                                        -//
  //---------------------------------------------------------------------//

  void initPublishers(rclcpp::Node& ref_ros_node_handle, const ConfigStore &ref_config_store);

  void publish(SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id, const SbgEComLogUnion &ref_sbg_log);
};
}

#endif // SBG_ROS_MESSAGE_PUBLISHER_H