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 {
52 {
53 public:
54 
58  struct SbgLogOutput
59  {
63  };
64 
65 private:
66 
67  std::string m_uart_port_name_;
71 
76 
78 
81 
84 
86 
91 
95 
99 
100  std::vector<SbgLogOutput> m_output_modes_;
103 
104  //---------------------------------------------------------------------//
105  //- Private methods -//
106  //---------------------------------------------------------------------//
107 
118  template <typename T>
119  T getParameter(const ros::NodeHandle& ref_node_handle, std::string param_key, int default_value) const
120  {
121  if (ref_node_handle.hasParam(param_key))
122  {
123  int parameter;
124  ref_node_handle.param<int>(param_key, parameter, default_value);
125 
126  return static_cast<T>(parameter);
127  }
128  else
129  {
130  return static_cast<T>(default_value);
131  }
132  }
133 
139  void loadCommunicationParameters(const ros::NodeHandle& ref_node_handle);
140 
146  void loadSensorParameters(const ros::NodeHandle& ref_node_handle);
147 
153  void loadImuAlignementParameters(const ros::NodeHandle& ref_node_handle);
154 
160  void loadAidingAssignementParameters(const ros::NodeHandle& ref_node_handle);
161 
167  void loadMagnetometersParameters(const ros::NodeHandle& ref_node_handle);
168 
174  void loadGnssParameters(const ros::NodeHandle& ref_node_handle);
175 
181  void loadOdometerParameters(const ros::NodeHandle& ref_node_handle);
182 
191  void loadOutputConfiguration(const ros::NodeHandle& ref_node_handle, const std::string& ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id);
192 
193 public:
194 
195  //---------------------------------------------------------------------//
196  //- Constructor -//
197  //---------------------------------------------------------------------//
198 
202  ConfigStore(void);
203 
204  //---------------------------------------------------------------------//
205  //- Parameters -//
206  //---------------------------------------------------------------------//
207 
213  bool checkConfigWithRos(void) const;
214 
220  bool isInterfaceSerial(void) const;
221 
227  const std::string &getUartPortName(void) const;
228 
234  uint32_t getBaudRate(void) const;
235 
241  SbgEComOutputPort getOutputPort(void) const;
242 
248  bool isInterfaceUdp(void) const;
249 
255  sbgIpAddress getIpAddress(void) const;
256 
262  uint32_t getOutputPortAddress(void) const;
263 
269  uint32_t getInputPortAddress(void) const;
270 
277 
283  const SbgEComModelInfo &getMotionProfile(void) const;
284 
291 
297  const SbgVector3<float> &getSensorLevelArms(void) const;
298 
305 
311  const SbgEComModelInfo &getMagnetometerModel(void) const;
312 
319 
326 
333 
339  const SbgEComModelInfo &getGnssModel(void) const;
340 
346  const SbgEComGnssInstallation &getGnssInstallation(void) const;
347 
353  const SbgEComGnssRejectionConf &getGnssRejection(void) const;
354 
360  const SbgEComOdoConf &getOdometerConf(void) const;
361 
367  const SbgVector3<float> &getOdometerLevelArms(void) const;
368 
375 
381  const std::vector<SbgLogOutput> &getOutputModes(void) const;
382 
388  bool checkRosStandardMessages(void) const;
389 
396  uint32_t getReadingRateFrequency(void) const;
397 
398  //---------------------------------------------------------------------//
399  //- Operations -//
400  //---------------------------------------------------------------------//
401 
407  void loadFromRosNodeHandle(const ros::NodeHandle& ref_node_handle);
408 };
409 }
410 
411 #endif // SBG_ROS_CONFIG_STORE_H
const SbgEComInitConditionConf & getInitialConditions(void) const
SbgEComOutputPort m_output_port_
Definition: config_store.h:68
SbgEComSensorAlignmentInfo m_sensor_alignement_info_
Definition: config_store.h:82
SbgEComOutputMode output_mode
Definition: config_store.h:62
sbgIpAddress getIpAddress(void) const
uint32_t m_out_port_address_
Definition: config_store.h:73
const std::string & getUartPortName(void) const
const std::vector< SbgLogOutput > & getOutputModes(void) const
uint32_t m_uart_baud_rate_
Definition: config_store.h:69
enum _SbgEComMagCalibMode SbgEComMagCalibMode
void loadCommunicationParameters(const ros::NodeHandle &ref_node_handle)
const SbgEComGnssInstallation & getGnssInstallation(void) const
void loadOdometerParameters(const ros::NodeHandle &ref_node_handle)
SbgEComGnssRejectionConf m_gnss_rejection_conf_
Definition: config_store.h:94
SbgEComMagCalibBandwidth m_mag_calib_bandwidth_
Definition: config_store.h:90
const SbgEComMagCalibBandwidth & getMagnetometerCalibBandwidth(void) const
uint32_t m_in_port_address_
Definition: config_store.h:74
enum _SbgEComMagCalibBandwidth SbgEComMagCalibBandwidth
uint32_t getReadingRateFrequency(void) const
const SbgEComGnssRejectionConf & getGnssRejection(void) const
const SbgEComMagCalibMode & getMagnetometerCalibMode(void) const
SbgEComModelInfo m_gnss_model_info_
Definition: config_store.h:92
bool m_configure_through_ros_
Definition: config_store.h:77
bool checkConfigWithRos(void) const
const SbgEComModelInfo & getMotionProfile(void) const
T getParameter(const ros::NodeHandle &ref_node_handle, std::string param_key, int default_value) const
Definition: config_store.h:119
std::vector< SbgLogOutput > m_output_modes_
Definition: config_store.h:100
void loadGnssParameters(const ros::NodeHandle &ref_node_handle)
bool m_upd_communication_
Definition: config_store.h:75
void loadAidingAssignementParameters(const ros::NodeHandle &ref_node_handle)
SbgVector3< float > m_odometer_level_arm_
Definition: config_store.h:97
SbgEComModelInfo m_motion_profile_model_info_
Definition: config_store.h:80
SbgEComOdoRejectionConf m_odometer_rejection_conf_
Definition: config_store.h:98
const SbgVector3< float > & getOdometerLevelArms(void) const
bool m_serial_communication_
Definition: config_store.h:70
SbgEComOdoConf m_odometer_conf_
Definition: config_store.h:96
void loadOutputConfiguration(const ros::NodeHandle &ref_node_handle, const std::string &ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id)
uint32_t getBaudRate(void) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const SbgEComMagRejectionConf & getMagnetometerRejection(void) const
uint32_t getInputPortAddress(void) const
SbgEComMagRejectionConf m_mag_rejection_conf_
Definition: config_store.h:88
void loadSensorParameters(const ros::NodeHandle &ref_node_handle)
void loadFromRosNodeHandle(const ros::NodeHandle &ref_node_handle)
SbgVector3< float > m_sensor_lever_arm_
Definition: config_store.h:83
uint32_t sbgIpAddress
Definition: sbgTypes.h:64
const SbgEComModelInfo & getMagnetometerModel(void) const
SbgEComMagCalibMode m_mag_calib_mode_
Definition: config_store.h:89
uint32_t getOutputPortAddress(void) const
sbgIpAddress m_sbg_ip_address_
Definition: config_store.h:72
void loadMagnetometersParameters(const ros::NodeHandle &ref_node_handle)
void loadImuAlignementParameters(const ros::NodeHandle &ref_node_handle)
const SbgEComOdoConf & getOdometerConf(void) const
bool isInterfaceUdp(void) const
const SbgVector3< float > & getSensorLevelArms(void) const
uint8_t SbgEComMsgId
Definition: sbgEComIds.h:289
const SbgEComAidingAssignConf & getAidingAssignement(void) const
std::string m_uart_port_name_
Definition: config_store.h:67
const SbgEComOdoRejectionConf & getOdometerRejection(void) const
enum _SbgEComOutputPort SbgEComOutputPort
bool isInterfaceSerial(void) const
enum _SbgEComClass SbgEComClass
SbgEComAidingAssignConf m_aiding_assignement_conf_
Definition: config_store.h:85
bool hasParam(const std::string &key) const
Handle a three components vector.
enum _SbgEComOutputMode SbgEComOutputMode
bool m_ros_standard_output_
Definition: config_store.h:101
const SbgEComModelInfo & getGnssModel(void) const
SbgEComGnssInstallation m_gnss_installation_
Definition: config_store.h:93
SbgEComOutputPort getOutputPort(void) const
SbgEComInitConditionConf m_init_condition_conf_
Definition: config_store.h:79
SbgEComModelInfo m_mag_model_info_
Definition: config_store.h:87
Main header file for the SBG Systems Enhanced Communication Library.
const SbgEComSensorAlignmentInfo & getSensorAlignement(void) const
uint32_t m_rate_frequency_
Definition: config_store.h:102
bool checkRosStandardMessages(void) const


sbg_driver
Author(s): SBG Systems
autogenerated on Thu Oct 22 2020 03:47:22