config_store.cpp
Go to the documentation of this file.
1 // File header
2 #include "config_store.h"
3 
4 using sbg::ConfigStore;
5 
9 //---------------------------------------------------------------------//
10 //- Constructor -//
11 //---------------------------------------------------------------------//
12 
13 ConfigStore::ConfigStore(void):
14 m_serial_communication_(false),
15 m_upd_communication_(false),
16 m_configure_through_ros_(false),
17 m_ros_standard_output_(false)
18 {
19 
20 }
21 
22 //---------------------------------------------------------------------//
23 //- Private methods -//
24 //---------------------------------------------------------------------//
25 
27 {
28  ref_node_handle.param<bool>("confWithRos", m_configure_through_ros_, false);
29 
30  if (ref_node_handle.hasParam("uartConf"))
31  {
33  ref_node_handle.param<std::string>("uartConf/portName", m_uart_port_name_, "/dev/ttyUSB0");
34 
35  m_uart_baud_rate_ = getParameter<uint32_t>(ref_node_handle, "uartConf/baudRate", 0);
36  m_output_port_ = getParameter<SbgEComOutputPort>(ref_node_handle, "uartConf/portID", SBG_ECOM_OUTPUT_PORT_A);
37  }
38  else if (ref_node_handle.hasParam("ipConf"))
39  {
40  std::string ip_address;
41  ref_node_handle.param<std::string>("ipConf/ipAddress", ip_address, "0.0.0.0");
42 
43  m_upd_communication_ = true;
44  m_sbg_ip_address_ = sbgNetworkIpFromString(ip_address.c_str());
45  m_out_port_address_ = getParameter<uint32_t>(ref_node_handle, "ipConf/out_port", 0);
46  m_in_port_address_ = getParameter<uint32_t>(ref_node_handle, "ipConf/in_port", 0);
47  }
48  else
49  {
50  throw ros::Exception("SBG DRIVER - Invalid communication interface parameters.");
51  }
52 }
53 
55 {
56  ref_node_handle.param<double>("sensorParameters/initLat", m_init_condition_conf_.latitude, 48.419727);
57  ref_node_handle.param<double>("sensorParameters/initLong", m_init_condition_conf_.longitude, -4.472119);
58  ref_node_handle.param<double>("sensorParameters/initAlt", m_init_condition_conf_.altitude, 100);
59 
60  m_init_condition_conf_.year = getParameter<uint16_t>(ref_node_handle, "sensorParameters/year", 2018);
61  m_init_condition_conf_.month = getParameter<uint8_t>(ref_node_handle, "sensorParameters/year", 03);
62  m_init_condition_conf_.day = getParameter<uint8_t>(ref_node_handle, "sensorParameters/year", 10);
63 
64  m_motion_profile_model_info_.id = getParameter<uint32>(ref_node_handle, "sensorParameters/motionProfile", SBG_ECOM_MOTION_PROFILE_GENERAL_PURPOSE);
65 }
66 
68 {
69  m_sensor_alignement_info_.axisDirectionX = getParameter<SbgEComAxisDirection>(ref_node_handle, "imuAlignementLeverArm/axisDirectionX", SBG_ECOM_ALIGNMENT_FORWARD);
70  m_sensor_alignement_info_.axisDirectionY = getParameter<SbgEComAxisDirection>(ref_node_handle, "imuAlignementLeverArm/axisDirectionY", SBG_ECOM_ALIGNMENT_FORWARD);
71 
72  ref_node_handle.param<float>("imuAlignementLeverArm/misRoll", m_sensor_alignement_info_.misRoll, 0.0f);
73  ref_node_handle.param<float>("imuAlignementLeverArm/misPitch", m_sensor_alignement_info_.misPitch, 0.0f);
74  ref_node_handle.param<float>("imuAlignementLeverArm/misYaw", m_sensor_alignement_info_.misYaw, 0.0f);
75 
76  float sensor_level_arm[3];
77  ref_node_handle.param<float>("imuAlignementLeverArm/leverArmX", sensor_level_arm[0], 0.0f);
78  ref_node_handle.param<float>("imuAlignementLeverArm/leverArmY", sensor_level_arm[1], 0.0f);
79  ref_node_handle.param<float>("imuAlignementLeverArm/leverArmZ", sensor_level_arm[2], 0.0f);
80 
81  m_sensor_lever_arm_ = SbgVector3<float>(sensor_level_arm, 3);
82 }
83 
85 {
86  m_aiding_assignement_conf_.gps1Port = getParameter<SbgEComModulePortAssignment>(ref_node_handle, "aidingAssignment/gnss1ModulePortAssignment", SBG_ECOM_MODULE_PORT_B);
87  m_aiding_assignement_conf_.gps1Sync = getParameter<SbgEComModuleSyncAssignment>(ref_node_handle, "aidingAssignment/gnss1ModuleSyncAssignment", SBG_ECOM_MODULE_SYNC_DISABLED);
88  m_aiding_assignement_conf_.rtcmPort = getParameter<SbgEComModulePortAssignment>(ref_node_handle, "aidingAssignment/rtcmPortAssignment", SBG_ECOM_MODULE_DISABLED);
89  m_aiding_assignement_conf_.odometerPinsConf = getParameter<SbgEComOdometerPinAssignment>(ref_node_handle, "aidingAssignment/odometerPinAssignment", SBG_ECOM_MODULE_ODO_DISABLED);
90 }
91 
93 {
94  m_mag_model_info_.id = getParameter<uint32_t>(ref_node_handle, "magnetometer/magnetometerModel", SBG_ECOM_MAG_MODEL_NORMAL);
95  m_mag_rejection_conf_.magneticField = getParameter<SbgEComRejectionMode>(ref_node_handle, "magnetometer/magnetometerRejectMode", SBG_ECOM_AUTOMATIC_MODE);
96 
97  m_mag_calib_mode_ = getParameter<SbgEComMagCalibMode>(ref_node_handle, "magnetometer/calibration/mode", SBG_ECOM_MAG_CALIB_MODE_2D);
98  m_mag_calib_bandwidth_ = getParameter<SbgEComMagCalibBandwidth>(ref_node_handle, "magnetometer/calibration/bandwidth", SBG_ECOM_MAG_CALIB_HIGH_BW);
99 }
100 
102 {
103  m_gnss_model_info_.id = getParameter<uint32_t>(ref_node_handle, "gnss/gnss_model_id", SBG_ECOM_GNSS_MODEL_NMEA);
104 
105  ref_node_handle.param<float>("gnss/primaryLeverArmX", m_gnss_installation_.leverArmPrimary[0], 0.0f);
106  ref_node_handle.param<float>("gnss/primaryLeverArmY", m_gnss_installation_.leverArmPrimary[1], 0.0f);
107  ref_node_handle.param<float>("gnss/primaryLeverArmZ", m_gnss_installation_.leverArmPrimary[2], 0.0f);
108  ref_node_handle.param<bool>("gnss/primaryLeverPrecise", m_gnss_installation_.leverArmPrimaryPrecise, true);
109  ref_node_handle.param<float>("gnss/secondaryLeverArmX", m_gnss_installation_.leverArmSecondary[0], 0.0f);
110  ref_node_handle.param<float>("gnss/secondaryLeverArmY", m_gnss_installation_.leverArmSecondary[1], 0.0f);
111  ref_node_handle.param<float>("gnss/secondaryLeverArmZ", m_gnss_installation_.leverArmSecondary[2], 0.0f);
112  m_gnss_installation_.leverArmSecondaryMode = getParameter<SbgEComGnssInstallationMode>(ref_node_handle, "gnss/secondaryLeverMode", SBG_ECOM_GNSS_INSTALLATION_MODE_SINGLE);
113 
114  m_gnss_rejection_conf_.position = getParameter<SbgEComRejectionMode>(ref_node_handle, "gnss/posRejectMode", SBG_ECOM_AUTOMATIC_MODE);
115  m_gnss_rejection_conf_.velocity = getParameter<SbgEComRejectionMode>(ref_node_handle, "gnss/velRejectMode", SBG_ECOM_AUTOMATIC_MODE);
116  m_gnss_rejection_conf_.hdt = getParameter<SbgEComRejectionMode>(ref_node_handle, "gnss/hdtRejectMode", SBG_ECOM_AUTOMATIC_MODE);
117 }
118 
120 {
121  ref_node_handle.param<float>("odom/gain", m_odometer_conf_.gain, 4800.0f);
122  ref_node_handle.param<bool>("odom/direction", m_odometer_conf_.reverseMode, false);
123 
124  float odometer_level_arm_[3];
125  ref_node_handle.param<float>("odom/leverArmX", odometer_level_arm_[0], 0.0f);
126  ref_node_handle.param<float>("odom/leverArmY", odometer_level_arm_[1], 0.0f);
127  ref_node_handle.param<float>("odom/leverArmZ", odometer_level_arm_[2], 0.0f);
128 
129  m_odometer_level_arm_ = SbgVector3<float>(odometer_level_arm_, 3);
130 
131  m_odometer_conf_.gainError = getParameter<uint8_t>(ref_node_handle, "odom/gain_error", 0.1);
132  m_odometer_rejection_conf_.velocity = getParameter<SbgEComRejectionMode>(ref_node_handle, "odom/rejectMode", SBG_ECOM_AUTOMATIC_MODE);
133 }
134 
135 void ConfigStore::loadOutputConfiguration(const ros::NodeHandle& ref_node_handle, const std::string& ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id)
136 {
137  SbgLogOutput log_output;
138 
139  log_output.message_class = sbg_msg_class;
140  log_output.message_id = sbg_msg_id;
141  log_output.output_mode = getParameter<SbgEComOutputMode>(ref_node_handle, ref_key, SBG_ECOM_OUTPUT_MODE_DISABLED);
142 
143  m_output_modes_.push_back(log_output);
144 }
145 
146 //---------------------------------------------------------------------//
147 //- Parameters -//
148 //---------------------------------------------------------------------//
149 
151 {
153 }
154 
156 {
158 }
159 
160 const std::string &ConfigStore::getUartPortName(void) const
161 {
162  return m_uart_port_name_;
163 }
164 
165 uint32_t ConfigStore::getBaudRate(void) const
166 {
167  return m_uart_baud_rate_;
168 }
169 
171 {
172  return m_output_port_;
173 }
174 
176 {
177  return m_upd_communication_;
178 }
179 
181 {
182  return m_sbg_ip_address_;
183 }
184 
186 {
187  return m_out_port_address_;
188 }
189 
191 {
192  return m_in_port_address_;
193 }
194 
196 {
197  return m_init_condition_conf_;
198 }
199 
201 {
203 }
204 
206 {
208 }
209 
211 {
212  return m_sensor_lever_arm_;
213 }
214 
216 {
218 }
219 
221 {
222  return m_mag_model_info_;
223 }
224 
226 {
227  return m_mag_rejection_conf_;
228 }
229 
231 {
232  return m_mag_calib_mode_;
233 }
234 
236 {
237  return m_mag_calib_bandwidth_;
238 }
239 
241 {
242  return m_gnss_model_info_;
243 }
244 
246 {
247  return m_gnss_installation_;
248 }
249 
251 {
252  return m_gnss_rejection_conf_;
253 }
254 
256 {
257  return m_odometer_conf_;
258 }
259 
261 {
262  return m_odometer_level_arm_;
263 }
264 
266 {
268 }
269 
270 const std::vector<ConfigStore::SbgLogOutput> &ConfigStore::getOutputModes(void) const
271 {
272  return m_output_modes_;
273 }
274 
276 {
277  return m_ros_standard_output_;
278 }
279 
281 {
282  return m_rate_frequency_;
283 }
284 
285 //---------------------------------------------------------------------//
286 //- Operations -//
287 //---------------------------------------------------------------------//
288 
290 {
291  loadCommunicationParameters(ref_node_handle);
292  loadSensorParameters(ref_node_handle);
293  loadImuAlignementParameters(ref_node_handle);
294  loadAidingAssignementParameters(ref_node_handle);
295  loadMagnetometersParameters(ref_node_handle);
296  loadGnssParameters(ref_node_handle);
297  loadOdometerParameters(ref_node_handle);
298 
299  loadOutputConfiguration(ref_node_handle, "output/log_status", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_STATUS);
300  loadOutputConfiguration(ref_node_handle, "output/log_imu_data", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_IMU_DATA);
301  loadOutputConfiguration(ref_node_handle, "output/log_ekf_euler", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EKF_EULER);
302  loadOutputConfiguration(ref_node_handle, "output/log_ekf_quat", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EKF_QUAT);
303  loadOutputConfiguration(ref_node_handle, "output/log_ekf_nav", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EKF_NAV);
304  loadOutputConfiguration(ref_node_handle, "output/log_ship_motion", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_SHIP_MOTION);
305  loadOutputConfiguration(ref_node_handle, "output/log_utc_time", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_UTC_TIME);
306  loadOutputConfiguration(ref_node_handle, "output/log_mag", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_MAG);
307  loadOutputConfiguration(ref_node_handle, "output/log_mag_calib", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_MAG_CALIB);
308  loadOutputConfiguration(ref_node_handle, "output/log_gps1_vel", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_GPS1_VEL);
309  loadOutputConfiguration(ref_node_handle, "output/log_gps1_pos", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_GPS1_POS);
310  loadOutputConfiguration(ref_node_handle, "output/log_gps1_hdt", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_GPS1_HDT);
311  loadOutputConfiguration(ref_node_handle, "output/log_gps1_raw", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_GPS1_RAW);
312  loadOutputConfiguration(ref_node_handle, "output/log_odo_vel", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_ODO_VEL);
313  loadOutputConfiguration(ref_node_handle, "output/log_event_a", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EVENT_A);
314  loadOutputConfiguration(ref_node_handle, "output/log_event_b", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EVENT_B);
315  loadOutputConfiguration(ref_node_handle, "output/log_event_c", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EVENT_C);
316  loadOutputConfiguration(ref_node_handle, "output/log_event_d", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EVENT_D);
317  loadOutputConfiguration(ref_node_handle, "output/log_event_e", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_EVENT_E);
318  loadOutputConfiguration(ref_node_handle, "output/log_air_data", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_AIR_DATA);
319  loadOutputConfiguration(ref_node_handle, "output/log_imu_short", SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_IMU_SHORT);
320 
321  ref_node_handle.param<bool>("output/ros_standard", m_ros_standard_output_, false);
322  m_rate_frequency_ = getParameter<uint32_t>(ref_node_handle, "output/frequency", 0);
323 }
const SbgEComInitConditionConf & getInitialConditions(void) const
SbgEComAxisDirection axisDirectionX
SbgEComOutputPort m_output_port_
Definition: config_store.h:68
SbgEComSensorAlignmentInfo m_sensor_alignement_info_
Definition: config_store.h:82
SbgEComRejectionMode velocity
SbgEComOutputMode output_mode
Definition: config_store.h:62
SbgEComModulePortAssignment gps1Port
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
SbgEComAxisDirection axisDirectionY
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
SbgEComRejectionMode hdt
SbgEComMagCalibBandwidth m_mag_calib_bandwidth_
Definition: config_store.h:90
SbgEComRejectionMode velocity
Definition: sbgEComCmdOdo.h:44
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
SbgEComGnssInstallationMode leverArmSecondaryMode
SbgEComModuleSyncAssignment gps1Sync
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)
SbgEComModulePortAssignment rtcmPort
SbgVector3< float > m_odometer_level_arm_
Definition: config_store.h:97
SbgEComModelInfo m_motion_profile_model_info_
Definition: config_store.h:80
Class to handle the device configuration.
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)
SbgEComOdometerPinAssignment odometerPinsConf
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
SbgEComRejectionMode magneticField
SBG_COMMON_LIB_API sbgIpAddress sbgNetworkIpFromString(const char *pBuffer)
Definition: sbgNetwork.c:35
SbgEComRejectionMode position
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
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