Public Member Functions | Private Member Functions | Private Attributes | List of all members
sbg::ConfigApplier Class Reference

#include <config_applier.h>

Public Member Functions

void applyConfiguration (const ConfigStore &ref_config_store)
 
 ConfigApplier (SbgEComHandle &ref_sbg_com_handle)
 
void saveConfiguration (void)
 

Private Member Functions

void checkConfigurationApplied (const SbgErrorCode &ref_sbg_error_code, const std::string &ref_conf_title)
 
void checkConfigurationGet (const SbgErrorCode &ref_sbg_error_code, const std::string &ref_conf_title) const
 
void configureAidingAssignement (const SbgEComAidingAssignConf &ref_aiding_assign)
 
void configureGnssInstallation (const SbgEComGnssInstallation &ref_gnss_installation)
 
void configureGnssModel (const SbgEComModelInfo &ref_gnss_model)
 
void configureGnssRejection (const SbgEComGnssRejectionConf &ref_gnss_rejection)
 
void configureImuAlignement (const SbgEComSensorAlignmentInfo &ref_sensor_align, const SbgVector3< float > &ref_level_arms)
 
void configureInitCondition (const SbgEComInitConditionConf &ref_init_condition)
 
void configureMagModel (const SbgEComModelInfo &ref_mag_model)
 
void configureMagRejection (const SbgEComMagRejectionConf &ref_mag_rejection)
 
void configureMotionProfile (const SbgEComModelInfo &ref_motion_profile)
 
void configureOdometer (const SbgEComOdoConf &ref_odometer)
 
void configureOdometerLevelArm (const SbgVector3< float > &odometer_level_arms)
 
void configureOdometerRejection (const SbgEComOdoRejectionConf &ref_odometer_rejection)
 
void configureOutput (SbgEComOutputPort output_port, const ConfigStore::SbgLogOutput &ref_log_output)
 

Private Attributes

bool m_reboot_needed_
 
SbgEComHandlem_ref_sbg_com_handle
 

Detailed Description

Class to apply configuration to a device.

Definition at line 51 of file config_applier.h.

Constructor & Destructor Documentation

ConfigApplier::ConfigApplier ( SbgEComHandle ref_sbg_com_handle)

Default constructor.

Parameters
[in]ref_com_handleSBG communication handle.

Class to apply configuration to a device.

Definition at line 13 of file config_applier.cpp.

Member Function Documentation

void ConfigApplier::applyConfiguration ( const ConfigStore ref_config_store)

Apply a configuration to the SBG device.

Parameters
[in]ref_config_storeConfiguration to apply.

Definition at line 405 of file config_applier.cpp.

void ConfigApplier::checkConfigurationApplied ( const SbgErrorCode ref_sbg_error_code,
const std::string &  ref_conf_title 
)
private

Check if the configuration has been applied correctly. This function will log if the configuration has been applied. It will log a warning if the parameter is not available for this device. It will be the user responsability to check.

Parameters
[in]ref_sbg_error_codeError code from the configuration getter.
[in]ref_conf_titleString to identify the configuration.
Exceptions
Unableto configure.

Definition at line 41 of file config_applier.cpp.

void ConfigApplier::checkConfigurationGet ( const SbgErrorCode ref_sbg_error_code,
const std::string &  ref_conf_title 
) const
private

Check if the configuration getter worked properly. This function will log a warning information if the parameter is not available for this device.

Parameters
[in]ref_sbg_error_codeError code from the configuration getter.
[in]ref_conf_titleString to identify the configuration.
Exceptions
Unableto get the configuration.

Definition at line 24 of file config_applier.cpp.

void ConfigApplier::configureAidingAssignement ( const SbgEComAidingAssignConf ref_aiding_assign)
private

Configure the aiding assignement.

Parameters
[in]ref_aiding_assignAiding assignement configuration to apply.

Definition at line 139 of file config_applier.cpp.

void ConfigApplier::configureGnssInstallation ( const SbgEComGnssInstallation ref_gnss_installation)
private

Configure the Gnss installation.

Parameters
[in]ref_gnss_installationGnss installation configuration to apply.

Definition at line 226 of file config_applier.cpp.

void ConfigApplier::configureGnssModel ( const SbgEComModelInfo ref_gnss_model)
private

Configure the Gnss model.

Parameters
[in]ref_gnss_modelGnss model configuration to apply.

Definition at line 205 of file config_applier.cpp.

void ConfigApplier::configureGnssRejection ( const SbgEComGnssRejectionConf ref_gnss_rejection)
private

Configure the Gnss rejection.

Parameters
[in]ref_gnss_rejectionGnss rejection configuration to apply.

Definition at line 259 of file config_applier.cpp.

void ConfigApplier::configureImuAlignement ( const SbgEComSensorAlignmentInfo ref_sensor_align,
const SbgVector3< float > &  ref_level_arms 
)
private

Configure the IMU alignement.

Parameters
[in]ref_sensor_alignSensor IMU alignement configuration to apply.
[in]ref_level_armsX, Y, Z level arms to apply.

Definition at line 110 of file config_applier.cpp.

void ConfigApplier::configureInitCondition ( const SbgEComInitConditionConf ref_init_condition)
private

Configure the initial condition parameters.

Parameters
[in]ref_init_conditionInitial condition conf to apply.

Definition at line 63 of file config_applier.cpp.

void ConfigApplier::configureMagModel ( const SbgEComModelInfo ref_mag_model)
private

Configure the magnetometers model.

Parameters
[in]ref_mag_modelMagnetometers model configuration to apply.

Definition at line 163 of file config_applier.cpp.

void ConfigApplier::configureMagRejection ( const SbgEComMagRejectionConf ref_mag_rejection)
private

Configure the magnetometers rejection.

Parameters
[in]ref_mag_rejectionMagnetometers rejection configuration to apply.

Definition at line 184 of file config_applier.cpp.

void ConfigApplier::configureMotionProfile ( const SbgEComModelInfo ref_motion_profile)
private

Configure the motion profile.

Parameters
[in]ref_motion_profileMotion profile configuration to apply.

Definition at line 89 of file config_applier.cpp.

void ConfigApplier::configureOdometer ( const SbgEComOdoConf ref_odometer)
private

Configure the odometer.

Parameters
[in]ref_odometerOdometer configuration to apply.

Definition at line 282 of file config_applier.cpp.

void ConfigApplier::configureOdometerLevelArm ( const SbgVector3< float > &  odometer_level_arms)
private

Configure the odometer level arm.

Parameters
[in]odometer_level_armsX,Y,Z odometer level arms to apply.

Definition at line 305 of file config_applier.cpp.

void ConfigApplier::configureOdometerRejection ( const SbgEComOdoRejectionConf ref_odometer_rejection)
private

Configure the odometer rejection.

Parameters
[in]ref_odometer_rejectionOdometer rejection configuration to apply.

Definition at line 328 of file config_applier.cpp.

void ConfigApplier::configureOutput ( SbgEComOutputPort  output_port,
const ConfigStore::SbgLogOutput ref_log_output 
)
private

Configure the output for the SBG log. If a Log is not available for the connected device, a warning will be logged. It will be user responsability to check.

Parameters
[in]output_portOutput communication port.
[in]ref_log_outputLog output to configure.
Exceptions
Unableto configure the output.

Definition at line 349 of file config_applier.cpp.

void ConfigApplier::saveConfiguration ( void  )

Save the configuration to the device.

Definition at line 442 of file config_applier.cpp.

Member Data Documentation

bool sbg::ConfigApplier::m_reboot_needed_
private

Definition at line 55 of file config_applier.h.

SbgEComHandle& sbg::ConfigApplier::m_ref_sbg_com_handle
private

Definition at line 56 of file config_applier.h.


The documentation for this class was generated from the following files:


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