14 m_reboot_needed_(false),
15 m_ref_sbg_com_handle(ref_sbg_com_handle)
28 ROS_WARN(
"SBG_DRIVER - [Config] Configuration %s is not available for the connected device.", ref_conf_title.c_str());
32 std::string error_message(
"[Config] Unable to get the ");
33 error_message.append(ref_conf_title);
34 error_message.append(
" configuration : ");
45 ROS_WARN(
"SBG_DRIVER - [Config] Configuration %s is not available for the connected device.", ref_conf_title.c_str());
49 std::string error_message(
"[Config] Unable to set the ");
50 error_message.append(ref_conf_title);
51 error_message.append(
" configuration : ");
58 ROS_INFO(
"SBG_DRIVER - [Config] %s updated on the device.", ref_conf_title.c_str());
76 if ((init_condition.
year != ref_init_condition.
year)
77 || (init_condition.
month != ref_init_condition.
month)
78 || (init_condition.
day != ref_init_condition.
day)
102 if (motion_profile.
id != ref_motion_profile.
id)
118 float level_arms_device[3];
126 if ((level_arms_vector != ref_level_arms)
176 if (model_info.
id != ref_mag_model.
id)
218 if (model_info.
id != ref_gnss_model.
id)
248 if ((gnss_device_primary != gnss_config_primary)
249 || (gnss_device_secondary != gnss_config_secondary)
272 if ((rejection.
hdt != ref_gnss_rejection.
hdt)
320 if (lever_arm_device != odometer_level_arms)
362 ROS_WARN(
"SBG_DRIVER - [Config] Output is not available for this device : Class [%d] - Id [%d]", ref_log_output.
message_class, ref_log_output.
message_id);
366 std::string error_message(
"[Config] Unable to get output for the device : Class [");
367 error_message.append(std::to_string(ref_log_output.
message_class));
368 error_message.append(
"] - Id [");
369 error_message.append(std::to_string(ref_log_output.
message_id));
370 error_message.append(
"] : ");
375 else if (current_output_mode != ref_log_output.
output_mode)
381 std::string error_message(
"[Config] Unable to set the output configuration : Class[");
382 error_message.append(std::to_string(ref_log_output.
message_class));
383 error_message.append(
"] - Id [");
384 error_message.append(std::to_string(ref_log_output.
message_id));
385 error_message.append(
"] : ");
426 const std::vector<ConfigStore::SbgLogOutput>& ref_output_modes = ref_config_store.
getOutputModes();
454 ROS_INFO(
"SBG_DRIVER - Settings saved and device rebooted.");
SbgErrorCode sbgEComCmdSensorSetAlignmentAndLeverArm(SbgEComHandle *pHandle, const SbgEComSensorAlignmentInfo *pAlignConf, const float leverArm[3])
SbgErrorCode sbgEComCmdMagGetModelInfo(SbgEComHandle *pHandle, SbgEComModelInfo *pModelInfo)
SbgEComAxisDirection axisDirectionX
SbgErrorCode sbgEComCmdGnss1SetRejection(SbgEComHandle *pHandle, const SbgEComGnssRejectionConf *pRejectConf)
void configureImuAlignement(const SbgEComSensorAlignmentInfo &ref_sensor_align, const SbgVector3< float > &ref_level_arms)
SbgEComRejectionMode velocity
SbgErrorCode sbgEComCmdOdoGetConf(SbgEComHandle *pHandle, SbgEComOdoConf *pOdometerConf)
void configureMotionProfile(const SbgEComModelInfo &ref_motion_profile)
SbgEComOutputMode output_mode
Apply configuration to the device.
SbgEComModulePortAssignment gps1Port
const SbgEComModelInfo & getGnssModel(void) const
SbgErrorCode sbgEComCmdSettingsAction(SbgEComHandle *pHandle, SbgEComSettingsAction action)
void configureOutput(SbgEComOutputPort output_port, const ConfigStore::SbgLogOutput &ref_log_output)
const SbgEComMagRejectionConf & getMagnetometerRejection(void) const
SbgErrorCode sbgEComCmdSensorGetAidingAssignment(SbgEComHandle *pHandle, SbgEComAidingAssignConf *pConf)
void configureOdometerLevelArm(const SbgVector3< float > &odometer_level_arms)
static const char * sbgErrorCodeToString(SbgErrorCode errorCode)
SbgErrorCode sbgEComCmdOutputSetConf(SbgEComHandle *pHandle, SbgEComOutputPort outputPort, SbgEComClass classId, SbgEComMsgId msgId, SbgEComOutputMode conf)
SbgEComAxisDirection axisDirectionY
SbgErrorCode sbgEComCmdSensorGetMotionProfileInfo(SbgEComHandle *pHandle, SbgEComModelInfo *pModelInfo)
const SbgEComGnssInstallation & getGnssInstallation(void) const
void configureMagRejection(const SbgEComMagRejectionConf &ref_mag_rejection)
SbgErrorCode sbgEComCmdGnss1SetModelId(SbgEComHandle *pHandle, uint32_t id)
SbgErrorCode sbgEComCmdOdoGetLeverArm(SbgEComHandle *pHandle, float leverArm[3])
SbgEComRejectionMode velocity
SbgEComHandle & m_ref_sbg_com_handle
const T * data(void) const
const SbgEComInitConditionConf & getInitialConditions(void) const
SbgEComGnssInstallationMode leverArmSecondaryMode
SbgEComModuleSyncAssignment gps1Sync
void configureOdometerRejection(const SbgEComOdoRejectionConf &ref_odometer_rejection)
SbgErrorCode sbgEComCmdSensorSetAidingAssignment(SbgEComHandle *pHandle, const SbgEComAidingAssignConf *pConf)
const SbgVector3< float > & getSensorLevelArms(void) const
SbgEComOutputPort getOutputPort(void) const
SbgEComModulePortAssignment rtcmPort
SbgErrorCode sbgEComCmdGnss1GetRejection(SbgEComHandle *pHandle, SbgEComGnssRejectionConf *pRejectConf)
float leverArmSecondary[3]
void saveConfiguration(void)
bool leverArmPrimaryPrecise
SbgErrorCode sbgEComCmdGnss1InstallationSet(SbgEComHandle *pHandle, const SbgEComGnssInstallation *pGnssInstallation)
const SbgEComOdoRejectionConf & getOdometerRejection(void) const
void configureGnssModel(const SbgEComModelInfo &ref_gnss_model)
const SbgVector3< float > & getOdometerLevelArms(void) const
SbgErrorCode sbgEComCmdOdoSetRejection(SbgEComHandle *pHandle, const SbgEComOdoRejectionConf *pRejectConf)
const SbgEComModelInfo & getMagnetometerModel(void) const
bool areEquals(T firstValue, T secondValue)
SbgErrorCode sbgEComCmdSensorGetInitCondition(SbgEComHandle *pHandle, SbgEComInitConditionConf *pConf)
SbgEComOdometerPinAssignment odometerPinsConf
const SbgEComGnssRejectionConf & getGnssRejection(void) const
SbgErrorCode sbgEComCmdOdoGetRejection(SbgEComHandle *pHandle, SbgEComOdoRejectionConf *pRejectConf)
SbgErrorCode sbgEComCmdMagSetModelId(SbgEComHandle *pHandle, uint32_t id)
SbgErrorCode sbgEComCmdOutputGetConf(SbgEComHandle *pHandle, SbgEComOutputPort outputPort, SbgEComClass classId, SbgEComMsgId msgId, SbgEComOutputMode *pConf)
SbgErrorCode sbgEComCmdGnss1InstallationGet(SbgEComHandle *pHandle, SbgEComGnssInstallation *pGnssInstallation)
const SbgEComOdoConf & getOdometerConf(void) const
const std::vector< SbgLogOutput > & getOutputModes(void) const
void configureGnssRejection(const SbgEComGnssRejectionConf &ref_gnss_rejection)
SbgErrorCode sbgEComCmdGnss1GetModelInfo(SbgEComHandle *pHandle, SbgEComModelInfo *pModelInfo)
void applyConfiguration(const ConfigStore &ref_config_store)
void configureOdometer(const SbgEComOdoConf &ref_odometer)
void configureInitCondition(const SbgEComInitConditionConf &ref_init_condition)
enum _SbgEComOutputPort SbgEComOutputPort
void checkConfigurationGet(const SbgErrorCode &ref_sbg_error_code, const std::string &ref_conf_title) const
SbgEComClass message_class
void configureAidingAssignement(const SbgEComAidingAssignConf &ref_aiding_assign)
const SbgEComModelInfo & getMotionProfile(void) const
SbgEComRejectionMode magneticField
SbgErrorCode sbgEComCmdOdoSetLeverArm(SbgEComHandle *pHandle, const float leverArm[3])
SbgErrorCode sbgEComCmdOdoSetConf(SbgEComHandle *pHandle, const SbgEComOdoConf *pOdometerConf)
SbgErrorCode sbgEComCmdMagGetRejection(SbgEComHandle *pHandle, SbgEComMagRejectionConf *pRejectConf)
SbgEComRejectionMode position
enum _SbgEComOutputMode SbgEComOutputMode
SbgErrorCode sbgEComCmdSensorSetMotionProfileId(SbgEComHandle *pHandle, uint32_t id)
void configureGnssInstallation(const SbgEComGnssInstallation &ref_gnss_installation)
void configureMagModel(const SbgEComModelInfo &ref_mag_model)
const SbgEComAidingAssignConf & getAidingAssignement(void) const
SbgErrorCode sbgEComCmdSensorSetInitCondition(SbgEComHandle *pHandle, const SbgEComInitConditionConf *pConf)
SbgErrorCode sbgEComCmdMagSetRejection(SbgEComHandle *pHandle, const SbgEComMagRejectionConf *pRejectConf)
enum _SbgErrorCode SbgErrorCode
const SbgEComSensorAlignmentInfo & getSensorAlignement(void) const
SbgErrorCode sbgEComCmdSensorGetAlignmentAndLeverArm(SbgEComHandle *pHandle, SbgEComSensorAlignmentInfo *pAlignConf, float leverArm[3])
void checkConfigurationApplied(const SbgErrorCode &ref_sbg_error_code, const std::string &ref_conf_title)