Program Listing for File ublox_firmware8.hpp
↰ Return to documentation for file (/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/ublox_firmware8.hpp
)
#ifndef UBLOX_GPS_UBLOX_FIRMWARE8_HPP
#define UBLOX_GPS_UBLOX_FIRMWARE8_HPP
#include <memory>
#include <string>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <rclcpp/rclcpp.hpp>
#include <ublox_msgs/msg/cfg_nmea.hpp>
#include <ublox_msgs/msg/mon_hw.hpp>
#include <ublox_msgs/msg/nav_pvt.hpp>
#include <ublox_msgs/msg/nav_sat.hpp>
#include <ublox_msgs/msg/rxm_rtcm.hpp>
#include <ublox_gps/gps.hpp>
#include <ublox_gps/ublox_firmware7plus.hpp>
namespace ublox_node {
class UbloxFirmware8 : public UbloxFirmware7Plus<ublox_msgs::msg::NavPVT> {
public:
explicit UbloxFirmware8(const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, std::shared_ptr<FixDiagnostic> freq_diag, std::shared_ptr<Gnss> gnss, rclcpp::Node* node)
: UbloxFirmware7Plus<ublox_msgs::msg::NavPVT>(frame_id, updater, freq_diag, gnss, node) {
if (getRosBoolean(node_, "publish.nav.sat")) {
nav_sat_pub_ = node->create_publisher<ublox_msgs::msg::NavSAT>("navstate", 1);
}
if (getRosBoolean(node_, "publish.mon.hw")) {
mon_hw_pub_ = node->create_publisher<ublox_msgs::msg::MonHW>("monhw", 1);
}
if (getRosBoolean(node_, "publish.rxm.rtcm")) {
rxm_rtcm_pub_ = node->create_publisher<ublox_msgs::msg::RxmRTCM>("rxmrtcm", 1);
}
}
void getRosParams() override;
bool configureUblox(std::shared_ptr<ublox_gps::Gps> gps) override;
void subscribe(std::shared_ptr<ublox_gps::Gps> gps) override;
protected:
// Set from ROS parameters
bool enable_galileo_{false};
bool enable_beidou_{false};
bool enable_imes_{false};
ublox_msgs::msg::CfgNMEA cfg_nmea_;
bool clear_bbr_{false};
bool save_on_shutdown_{false};
private:
rclcpp::Publisher<ublox_msgs::msg::NavSAT>::SharedPtr nav_sat_pub_;
rclcpp::Publisher<ublox_msgs::msg::MonHW>::SharedPtr mon_hw_pub_;
rclcpp::Publisher<ublox_msgs::msg::RxmRTCM>::SharedPtr rxm_rtcm_pub_;
};
} // namespace ublox_node
#endif // UBLOX_GPS_UBLOX_FIRMWARE8_HPP