config_store.h
Go to the documentation of this file.
1 
34 #ifndef SBG_ROS_CONFIG_STORE_H
35 #define SBG_ROS_CONFIG_STORE_H
36 
37 // SbgECom headers
38 #include <sbgEComLib.h>
39 
40 // ROS headers
41 #include <ros/ros.h>
42 
43 // Project headers
44 #include "sbg_vector3.h"
45 
46 namespace sbg
47 {
51  enum class TimeReference
52  {
53  ROS = 0,
54  INS_UNIX = 1,
55  };
56 
61 {
62 public:
63 
67  struct SbgLogOutput
68  {
72  };
73 
74 private:
75 
76  std::string uart_port_name_;
78  uint32_t uart_baud_rate_;
80 
83  uint32_t in_port_address_;
85 
87 
90 
93 
95 
100 
104 
108 
109  std::vector<SbgLogOutput> output_modes_;
111 
113 
114  uint32_t rate_frequency_;
115  std::string frame_id_;
116  bool use_enu_;
117 
120  std::string odom_frame_id_;
121  std::string odom_base_frame_id_;
122  std::string odom_init_frame_id_;
123 
125  std::string rtcm_full_topic_;
126 
128  std::string nmea_full_topic_;
129 
130  //---------------------------------------------------------------------//
131  //- Private methods -//
132  //---------------------------------------------------------------------//
133 
144  template <typename T>
145  T getParameter(const ros::NodeHandle& ref_node_handle, std::string param_key, int default_value) const
146  {
147  if (ref_node_handle.hasParam(param_key))
148  {
149  int parameter;
150  ref_node_handle.param<int>(param_key, parameter, default_value);
151 
152  return static_cast<T>(parameter);
153  }
154  else
155  {
156  return static_cast<T>(default_value);
157  }
158  }
159 
165  void loadDriverParameters(const ros::NodeHandle& ref_node_handle);
166 
172  void loadOdomParameters(const ros::NodeHandle& ref_node_handle);
173 
179  void loadCommunicationParameters(const ros::NodeHandle& ref_node_handle);
180 
186  void loadSensorParameters(const ros::NodeHandle& ref_node_handle);
187 
193  void loadImuAlignementParameters(const ros::NodeHandle& ref_node_handle);
194 
200  void loadAidingAssignementParameters(const ros::NodeHandle& ref_node_handle);
201 
207  void loadMagnetometersParameters(const ros::NodeHandle& ref_node_handle);
208 
214  void loadGnssParameters(const ros::NodeHandle& ref_node_handle);
215 
221  void loadOdometerParameters(const ros::NodeHandle& ref_node_handle);
222 
228  void loadOutputFrameParameters(const ros::NodeHandle& ref_node_handle);
229 
238  void loadOutputConfiguration(const ros::NodeHandle& ref_node_handle, const std::string& ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id);
239 
246  void loadOutputTimeReference(const ros::NodeHandle& ref_node_handle, const std::string& ref_key);
247 
253  void loadRtcmParameters(const ros::NodeHandle& ref_node_handle);
254 
260  void loadNmeaParameters(const ros::NodeHandle& ref_node_handle);
261 
262 public:
263 
264  //---------------------------------------------------------------------//
265  //- Constructor -//
266  //---------------------------------------------------------------------//
267 
271  ConfigStore();
272 
273  //---------------------------------------------------------------------//
274  //- Parameters -//
275  //---------------------------------------------------------------------//
276 
282  bool checkConfigWithRos() const;
283 
289  bool isInterfaceSerial() const;
290 
296  const std::string &getUartPortName() const;
297 
303  uint32_t getBaudRate() const;
304 
311 
317  bool isInterfaceUdp() const;
318 
324  sbgIpAddress getIpAddress() const;
325 
331  uint32_t getOutputPortAddress() const;
332 
338  uint32_t getInputPortAddress() const;
339 
346 
352  const SbgEComModelInfo &getMotionProfile() const;
353 
360 
366  const SbgVector3<float> &getSensorLevelArms() const;
367 
374 
380  const SbgEComModelInfo &getMagnetometerModel() const;
381 
388 
395 
402 
408  const SbgEComModelInfo &getGnssModel() const;
409 
416 
423 
429  const SbgEComOdoConf &getOdometerConf() const;
430 
437 
444 
450  const std::vector<SbgLogOutput> &getOutputModes() const;
451 
457  bool checkRosStandardMessages() const;
458 
465  uint32_t getReadingRateFrequency() const;
466 
472  const std::string &getFrameId() const;
473 
479  bool getUseEnu() const;
480 
486  bool getOdomEnable() const;
487 
493  bool getOdomPublishTf() const;
494 
500  const std::string &getOdomFrameId() const;
501 
507  const std::string &getOdomBaseFrameId() const;
508 
514  const std::string &getOdomInitFrameId() const;
515 
522 
528  bool shouldSubscribeToRtcm() const;
529 
535  const std::string &getRtcmFullTopic() const;
536 
544  bool shouldPublishNmea() const;
545 
551  const std::string &getNmeaFullTopic() const;
552 
553  //---------------------------------------------------------------------//
554  //- Operations -//
555  //---------------------------------------------------------------------//
556 
562  void loadFromRosNodeHandle(const ros::NodeHandle& ref_node_handle);
563 };
564 }
565 
566 #endif // SBG_ROS_CONFIG_STORE_H
sbg::ConfigStore::getGnssInstallation
const SbgEComGnssInstallation & getGnssInstallation() const
Definition: config_store.cpp:319
sbg::ConfigStore::getOdomFrameId
const std::string & getOdomFrameId() const
Definition: config_store.cpp:384
sbg::ConfigStore::nmea_full_topic_
std::string nmea_full_topic_
Definition: config_store.h:128
sbg::SbgVector3< float >
sbg::ConfigStore::getIpAddress
sbgIpAddress getIpAddress() const
Definition: config_store.cpp:254
sbg::ConfigStore::init_condition_conf_
SbgEComInitConditionConf init_condition_conf_
Definition: config_store.h:88
sbg::ConfigStore::gnss_model_info_
SbgEComModelInfo gnss_model_info_
Definition: config_store.h:101
_SbgEComAidingAssignConf
Definition: sbgEComCmdSensor.h:89
sbg::ConfigStore::sensor_lever_arm_
SbgVector3< float > sensor_lever_arm_
Definition: config_store.h:92
sbg::ConfigStore::upd_communication_
bool upd_communication_
Definition: config_store.h:84
sbg::ConfigStore::out_port_address_
uint32_t out_port_address_
Definition: config_store.h:82
_SbgEComMagRejectionConf
Definition: sbgEComCmdMag.h:102
sbg::ConfigStore::loadNmeaParameters
void loadNmeaParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:208
_SbgEComModelInfo
Definition: sbgEComCmdCommon.h:58
sbg::ConfigStore::time_reference_
TimeReference time_reference_
Definition: config_store.h:112
sbg::ConfigStore::getGnssRejection
const SbgEComGnssRejectionConf & getGnssRejection() const
Definition: config_store.cpp:324
sbg::ConfigStore::use_enu_
bool use_enu_
Definition: config_store.h:116
sbg::ConfigStore::configure_through_ros_
bool configure_through_ros_
Definition: config_store.h:86
sbg::ConfigStore::getSensorLevelArms
const SbgVector3< float > & getSensorLevelArms() const
Definition: config_store.cpp:284
ros.h
sbg::ConfigStore::sensor_alignement_info_
SbgEComSensorAlignmentInfo sensor_alignement_info_
Definition: config_store.h:91
sbg::ConfigStore::nmea_publish_
bool nmea_publish_
Definition: config_store.h:127
SbgEComOutputMode
enum _SbgEComOutputMode SbgEComOutputMode
sbg::ConfigStore::SbgLogOutput::output_mode
SbgEComOutputMode output_mode
Definition: config_store.h:71
sbg::ConfigStore::loadGnssParameters
void loadGnssParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:117
sbg::ConfigStore::loadOutputFrameParameters
void loadOutputFrameParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:162
sbg::ConfigStore::getNmeaFullTopic
const std::string & getNmeaFullTopic() const
Definition: config_store.cpp:414
sbg::ConfigStore::odom_frame_id_
std::string odom_frame_id_
Definition: config_store.h:120
sbg::ConfigStore::loadAidingAssignementParameters
void loadAidingAssignementParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:100
_SbgEComInitConditionConf
Definition: sbgEComCmdSensor.h:115
sbg::ConfigStore::getReadingRateFrequency
uint32_t getReadingRateFrequency() const
Definition: config_store.cpp:354
sbg::ConfigStore::output_port_
SbgEComOutputPort output_port_
Definition: config_store.h:77
sbg::ConfigStore::getMotionProfile
const SbgEComModelInfo & getMotionProfile() const
Definition: config_store.cpp:274
sbg::ConfigStore::getGnssModel
const SbgEComModelInfo & getGnssModel() const
Definition: config_store.cpp:314
sbg::ConfigStore::getOutputPort
SbgEComOutputPort getOutputPort() const
Definition: config_store.cpp:244
sbg::ConfigStore::getMagnetometerRejection
const SbgEComMagRejectionConf & getMagnetometerRejection() const
Definition: config_store.cpp:299
_SbgEComOdoConf
Definition: sbgEComCmdOdo.h:32
sbg::ConfigStore::sbg_ip_address_
sbgIpAddress sbg_ip_address_
Definition: config_store.h:81
sbg::ConfigStore::in_port_address_
uint32_t in_port_address_
Definition: config_store.h:83
sbg::ConfigStore
Definition: config_store.h:60
sbg::ConfigStore::getOdomPublishTf
bool getOdomPublishTf() const
Definition: config_store.cpp:379
sbg::ConfigStore::loadDriverParameters
void loadDriverParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:28
sbg::ConfigStore::loadCommunicationParameters
void loadCommunicationParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:42
sbg::ConfigStore::getOdometerConf
const SbgEComOdoConf & getOdometerConf() const
Definition: config_store.cpp:329
sbg::ConfigStore::motion_profile_model_info_
SbgEComModelInfo motion_profile_model_info_
Definition: config_store.h:89
sbg::ConfigStore::odometer_level_arm_
SbgVector3< float > odometer_level_arm_
Definition: config_store.h:106
sbg::ConfigStore::loadOdometerParameters
void loadOdometerParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:135
sbg::ConfigStore::loadOutputTimeReference
void loadOutputTimeReference(const ros::NodeHandle &ref_node_handle, const std::string &ref_key)
Definition: config_store.cpp:176
sbg::ConfigStore::odom_enable_
bool odom_enable_
Definition: config_store.h:118
sbg::ConfigStore::getRtcmFullTopic
const std::string & getRtcmFullTopic() const
Definition: config_store.cpp:404
sbg::ConfigStore::getFrameId
const std::string & getFrameId() const
Definition: config_store.cpp:359
sbg::ConfigStore::mag_model_info_
SbgEComModelInfo mag_model_info_
Definition: config_store.h:96
sbg::ConfigStore::gnss_rejection_conf_
SbgEComGnssRejectionConf gnss_rejection_conf_
Definition: config_store.h:103
sbg::ConfigStore::odometer_rejection_conf_
SbgEComOdoRejectionConf odometer_rejection_conf_
Definition: config_store.h:107
sbg::ConfigStore::mag_calib_mode_
SbgEComMagCalibMode mag_calib_mode_
Definition: config_store.h:98
sbg::ConfigStore::checkConfigWithRos
bool checkConfigWithRos() const
Definition: config_store.cpp:224
sbg::TimeReference
TimeReference
Definition: config_store.h:51
SbgEComClass
enum _SbgEComClass SbgEComClass
sbg::ConfigStore::getOutputPortAddress
uint32_t getOutputPortAddress() const
Definition: config_store.cpp:259
sbg::ConfigStore::rtcm_full_topic_
std::string rtcm_full_topic_
Definition: config_store.h:125
sbg::ConfigStore::getOdometerRejection
const SbgEComOdoRejectionConf & getOdometerRejection() const
Definition: config_store.cpp:339
sbg::ConfigStore::isInterfaceSerial
bool isInterfaceSerial() const
Definition: config_store.cpp:229
SbgEComOutputPort
enum _SbgEComOutputPort SbgEComOutputPort
This file implements SbgECom commands related to outputs.
sbg::ConfigStore::getTimeReference
TimeReference getTimeReference() const
Definition: config_store.cpp:369
sbg::TimeReference::ROS
@ ROS
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
sbg::ConfigStore::loadOdomParameters
void loadOdomParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:33
sbg::ConfigStore::odom_publish_tf_
bool odom_publish_tf_
Definition: config_store.h:119
sbg::ConfigStore::getAidingAssignement
const SbgEComAidingAssignConf & getAidingAssignement() const
Definition: config_store.cpp:289
sbg::ConfigStore::getSensorAlignement
const SbgEComSensorAlignmentInfo & getSensorAlignement() const
Definition: config_store.cpp:279
sbg::ConfigStore::SbgLogOutput
Definition: config_store.h:67
sbg::ConfigStore::uart_port_name_
std::string uart_port_name_
Definition: config_store.h:76
sbg::ConfigStore::rtcm_subscribe_
bool rtcm_subscribe_
Definition: config_store.h:124
sbg::ConfigStore::getInputPortAddress
uint32_t getInputPortAddress() const
Definition: config_store.cpp:264
sbg::ConfigStore::loadRtcmParameters
void loadRtcmParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:196
sbg::ConfigStore::checkRosStandardMessages
bool checkRosStandardMessages() const
Definition: config_store.cpp:349
sbg::ConfigStore::SbgLogOutput::message_id
SbgEComMsgId message_id
Definition: config_store.h:70
_SbgEComGnssRejectionConf
Definition: sbgEComCmdGnss.h:91
sbg::ConfigStore::getParameter
T getParameter(const ros::NodeHandle &ref_node_handle, std::string param_key, int default_value) const
Definition: config_store.h:145
sbg::ConfigStore::frame_id_
std::string frame_id_
Definition: config_store.h:115
sbg::ConfigStore::odometer_conf_
SbgEComOdoConf odometer_conf_
Definition: config_store.h:105
sbg::ConfigStore::getOutputModes
const std::vector< SbgLogOutput > & getOutputModes() const
Definition: config_store.cpp:344
SbgEComMagCalibMode
enum _SbgEComMagCalibMode SbgEComMagCalibMode
This file implements SbgECom commands related to Magnetometer module.
sbg::ConfigStore::rate_frequency_
uint32_t rate_frequency_
Definition: config_store.h:114
sbg::ConfigStore::isInterfaceUdp
bool isInterfaceUdp() const
Definition: config_store.cpp:249
sbg::ConfigStore::getInitialConditions
const SbgEComInitConditionConf & getInitialConditions() const
Definition: config_store.cpp:269
sbg::ConfigStore::loadOutputConfiguration
void loadOutputConfiguration(const ros::NodeHandle &ref_node_handle, const std::string &ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id)
Definition: config_store.cpp:151
sbg::ConfigStore::ros_standard_output_
bool ros_standard_output_
Definition: config_store.h:110
sbg::ConfigStore::serial_communication_
bool serial_communication_
Definition: config_store.h:79
_SbgEComOdoRejectionConf
Definition: sbgEComCmdOdo.h:42
sbg
Definition: config_applier.h:45
sbg::ConfigStore::loadSensorParameters
void loadSensorParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:70
sbg::ConfigStore::getUseEnu
bool getUseEnu() const
Definition: config_store.cpp:364
SbgEComMsgId
uint8_t SbgEComMsgId
Definition: sbgEComIds.h:289
default_value
def default_value(type_)
sbgEComLib.h
sbg::ConfigStore::odom_base_frame_id_
std::string odom_base_frame_id_
Definition: config_store.h:121
sbg::ConfigStore::shouldSubscribeToRtcm
bool shouldSubscribeToRtcm() const
Definition: config_store.cpp:399
sbgIpAddress
uint32_t sbgIpAddress
Definition: sbgTypes.h:64
sbg::ConfigStore::getMagnetometerCalibBandwidth
const SbgEComMagCalibBandwidth & getMagnetometerCalibBandwidth() const
Definition: config_store.cpp:309
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
sbg::TimeReference::INS_UNIX
@ INS_UNIX
sbg::ConfigStore::loadFromRosNodeHandle
void loadFromRosNodeHandle(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:423
sbg::ConfigStore::mag_calib_bandwidth_
SbgEComMagCalibBandwidth mag_calib_bandwidth_
Definition: config_store.h:99
sbg::ConfigStore::uart_baud_rate_
uint32_t uart_baud_rate_
Definition: config_store.h:78
sbg::ConfigStore::loadMagnetometersParameters
void loadMagnetometersParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:108
sbg::ConfigStore::getUartPortName
const std::string & getUartPortName() const
Definition: config_store.cpp:234
sbg::ConfigStore::ConfigStore
ConfigStore()
Definition: config_store.cpp:13
sbg::ConfigStore::getOdomEnable
bool getOdomEnable() const
Definition: config_store.cpp:374
_SbgEComSensorAlignmentInfo
Definition: sbgEComCmdSensor.h:103
sbg::ConfigStore::loadImuAlignementParameters
void loadImuAlignementParameters(const ros::NodeHandle &ref_node_handle)
Definition: config_store.cpp:83
sbg::ConfigStore::output_modes_
std::vector< SbgLogOutput > output_modes_
Definition: config_store.h:109
sbg::ConfigStore::getOdometerLevelArms
const SbgVector3< float > & getOdometerLevelArms() const
Definition: config_store.cpp:334
sbg::ConfigStore::getMagnetometerCalibMode
const SbgEComMagCalibMode & getMagnetometerCalibMode() const
Definition: config_store.cpp:304
sbg_vector3.h
Handle a X,Y,Z vector.
sbg::ConfigStore::getMagnetometerModel
const SbgEComModelInfo & getMagnetometerModel() const
Definition: config_store.cpp:294
sbg::ConfigStore::aiding_assignement_conf_
SbgEComAidingAssignConf aiding_assignement_conf_
Definition: config_store.h:94
sbg::ConfigStore::odom_init_frame_id_
std::string odom_init_frame_id_
Definition: config_store.h:122
sbg::ConfigStore::getBaudRate
uint32_t getBaudRate() const
Definition: config_store.cpp:239
sbg::ConfigStore::getOdomInitFrameId
const std::string & getOdomInitFrameId() const
Definition: config_store.cpp:394
_SbgEComGnssInstallation
Definition: sbgEComCmdGnss.h:79
sbg::ConfigStore::shouldPublishNmea
bool shouldPublishNmea() const
Definition: config_store.cpp:409
SbgEComMagCalibBandwidth
enum _SbgEComMagCalibBandwidth SbgEComMagCalibBandwidth
sbg::ConfigStore::mag_rejection_conf_
SbgEComMagRejectionConf mag_rejection_conf_
Definition: config_store.h:97
sbg::ConfigStore::gnss_installation_
SbgEComGnssInstallation gnss_installation_
Definition: config_store.h:102
ros::NodeHandle
sbg::ConfigStore::SbgLogOutput::message_class
SbgEComClass message_class
Definition: config_store.h:69
sbg::ConfigStore::getOdomBaseFrameId
const std::string & getOdomBaseFrameId() const
Definition: config_store.cpp:389


sbg_driver
Author(s): SBG Systems
autogenerated on Fri Oct 11 2024 02:13:40