Program Listing for File config_store.h
↰ Return to documentation for file (include/sbg_driver/config_store.h)
#ifndef SBG_ROS_CONFIG_STORE_H
#define SBG_ROS_CONFIG_STORE_H
// SbgECom headers
#include <sbgEComLib.h>
// ROS headers
#include <rclcpp/rclcpp.hpp>
// Project headers
#include "sbg_vector3.h"
namespace sbg
{
enum class TimeReference
{
ROS = 0,
INS_UNIX = 1,
};
class ConfigStore
{
public:
struct SbgLogOutput
{
SbgEComClass message_class;
SbgEComMsgId message_id;
SbgEComOutputMode output_mode;
};
private:
std::string uart_port_name_;
SbgEComOutputPort output_port_;
uint32_t uart_baud_rate_;
std::vector<int64_t> uart_fallback_baud_rates_;
bool serial_communication_;
sbgIpAddress sbg_ip_address_;
uint32_t out_port_address_;
uint32_t in_port_address_;
bool upd_communication_;
std::string sbg_file_;
bool file_communication_;
bool configure_through_ros_;
SbgEComInitConditionConf init_condition_conf_;
SbgEComMotionProfileStdIds motion_profile_model_info_;
SbgEComSensorAlignmentInfo sensor_alignement_info_;
SbgVector3<float> sensor_lever_arm_;
SbgEComAidingAssignConf aiding_assignement_conf_;
SbgEComMagModelsStdId mag_model_info_;
SbgEComMagRejectionConf mag_rejection_conf_;
SbgEComMagCalibMode mag_calib_mode_;
SbgEComMagCalibBandwidth mag_calib_bandwidth_;
SbgEComGnssModelsStdIds gnss_model_info_;
SbgEComGnssInstallation gnss_installation_;
SbgEComGnssRejectionConf gnss_rejection_conf_;
SbgEComOdoConf odometer_conf_;
SbgVector3<float> odometer_lever_arm_;
SbgEComOdoRejectionConf odometer_rejection_conf_;
std::vector<SbgLogOutput> output_modes_;
bool ros_standard_output_;
TimeReference time_reference_;
uint32_t rate_frequency_;
std::string frame_id_;
bool use_enu_;
bool odom_enable_;
bool odom_publish_tf_;
std::string odom_frame_id_;
std::string odom_base_frame_id_;
std::string odom_init_frame_id_;
bool rtcm_subscribe_;
std::string rtcm_full_topic_;
bool nmea_publish_;
std::string nmea_full_topic_;
//---------------------------------------------------------------------//
//- Private methods -//
//---------------------------------------------------------------------//
template <typename T>
T getParameter(const rclcpp::Node& ref_node_handle, std::string param_key, int default_value) const
{
if (ref_node_handle.has_parameter(param_key))
{
int parameter;
ref_node_handle.get_parameter_or<int>(param_key, parameter, default_value);
return static_cast<T>(parameter);
}
else
{
return static_cast<T>(default_value);
}
}
void loadDriverParameters(const rclcpp::Node& ref_node_handle);
void loadOdomParameters(const rclcpp::Node& ref_node_handle);
void loadCommunicationParameters(const rclcpp::Node& ref_node_handle);
void loadSensorParameters(const rclcpp::Node& ref_node_handle);
void loadImuAlignementParameters(const rclcpp::Node& ref_node_handle);
void loadAidingAssignementParameters(const rclcpp::Node& ref_node_handle);
void loadMagnetometersParameters(const rclcpp::Node& ref_node_handle);
void loadGnssParameters(const rclcpp::Node& ref_node_handle);
void loadOdometerParameters(const rclcpp::Node& ref_node_handle);
void loadOutputFrameParameters(const rclcpp::Node& ref_node_handle);
void loadOutputConfiguration(const rclcpp::Node& ref_node_handle, const std::string& ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id);
void loadOutputTimeReference(const rclcpp::Node& ref_node_handle, const std::string& ref_key);
void loadRtcmParameters(const rclcpp::Node& ref_node_handle);
void loadNmeaParameters(const rclcpp::Node& ref_node_handle);
public:
//---------------------------------------------------------------------//
//- Constructor -//
//---------------------------------------------------------------------//
ConfigStore();
//---------------------------------------------------------------------//
//- Parameters -//
//---------------------------------------------------------------------//
bool checkConfigWithRos() const;
bool isInterfaceSerial() const;
const std::string &getUartPortName() const;
uint32_t getBaudRate() const;
const std::vector<int64_t> getFallbackBaudRates() const;
SbgEComOutputPort getOutputPort() const;
bool isInterfaceUdp() const;
sbgIpAddress getIpAddress() const;
uint32_t getOutputPortAddress() const;
uint32_t getInputPortAddress() const;
bool isInterfaceFile() const;
const std::string &getFile() const;
const SbgEComInitConditionConf &getInitialConditions() const;
const SbgEComMotionProfileStdIds &getMotionProfile() const;
const SbgEComSensorAlignmentInfo &getSensorAlignement() const;
const SbgVector3<float> &getSensorLeverArm() const;
const SbgEComAidingAssignConf &getAidingAssignement() const;
const SbgEComMagModelsStdId &getMagnetometerModel() const;
const SbgEComMagRejectionConf &getMagnetometerRejection() const;
const SbgEComMagCalibMode &getMagnetometerCalibMode() const;
const SbgEComMagCalibBandwidth &getMagnetometerCalibBandwidth() const;
const SbgEComGnssModelsStdIds &getGnssModel() const;
const SbgEComGnssInstallation &getGnssInstallation() const;
const SbgEComGnssRejectionConf &getGnssRejection() const;
const SbgEComOdoConf &getOdometerConf() const;
const SbgVector3<float> &getOdometerLeverArm() const;
const SbgEComOdoRejectionConf &getOdometerRejection() const;
const std::vector<SbgLogOutput> &getOutputModes() const;
bool checkRosStandardMessages() const;
uint32_t getReadingRateFrequency() const;
const std::string &getFrameId() const;
bool getUseEnu() const;
bool getOdomEnable() const;
bool getOdomPublishTf() const;
const std::string &getOdomFrameId() const;
const std::string &getOdomBaseFrameId() const;
const std::string &getOdomInitFrameId() const;
TimeReference getTimeReference() const;
bool shouldSubscribeToRtcm() const;
const std::string &getRtcmFullTopic() const;
bool shouldPublishNmea() const;
const std::string &getNmeaFullTopic() const;
//---------------------------------------------------------------------//
//- Operations -//
//---------------------------------------------------------------------//
void loadFromRosNodeHandle(const rclcpp::Node& ref_node_handle);
};
}
#endif // SBG_ROS_CONFIG_STORE_H