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

#include <config_store.h>

Classes

struct  SbgLogOutput
 

Public Member Functions

bool checkConfigWithRos (void) const
 
bool checkRosStandardMessages (void) const
 
 ConfigStore (void)
 
const SbgEComAidingAssignConfgetAidingAssignement (void) const
 
uint32_t getBaudRate (void) const
 
const SbgEComGnssInstallationgetGnssInstallation (void) const
 
const SbgEComModelInfogetGnssModel (void) const
 
const SbgEComGnssRejectionConfgetGnssRejection (void) const
 
const SbgEComInitConditionConfgetInitialConditions (void) const
 
uint32_t getInputPortAddress (void) const
 
sbgIpAddress getIpAddress (void) const
 
const SbgEComMagCalibBandwidthgetMagnetometerCalibBandwidth (void) const
 
const SbgEComMagCalibModegetMagnetometerCalibMode (void) const
 
const SbgEComModelInfogetMagnetometerModel (void) const
 
const SbgEComMagRejectionConfgetMagnetometerRejection (void) const
 
const SbgEComModelInfogetMotionProfile (void) const
 
const SbgEComOdoConfgetOdometerConf (void) const
 
const SbgVector3< float > & getOdometerLevelArms (void) const
 
const SbgEComOdoRejectionConfgetOdometerRejection (void) const
 
const std::vector< SbgLogOutput > & getOutputModes (void) const
 
SbgEComOutputPort getOutputPort (void) const
 
uint32_t getOutputPortAddress (void) const
 
uint32_t getReadingRateFrequency (void) const
 
const SbgEComSensorAlignmentInfogetSensorAlignement (void) const
 
const SbgVector3< float > & getSensorLevelArms (void) const
 
const std::string & getUartPortName (void) const
 
bool isInterfaceSerial (void) const
 
bool isInterfaceUdp (void) const
 
void loadFromRosNodeHandle (const ros::NodeHandle &ref_node_handle)
 

Private Member Functions

template<typename T >
getParameter (const ros::NodeHandle &ref_node_handle, std::string param_key, int default_value) const
 
void loadAidingAssignementParameters (const ros::NodeHandle &ref_node_handle)
 
void loadCommunicationParameters (const ros::NodeHandle &ref_node_handle)
 
void loadGnssParameters (const ros::NodeHandle &ref_node_handle)
 
void loadImuAlignementParameters (const ros::NodeHandle &ref_node_handle)
 
void loadMagnetometersParameters (const ros::NodeHandle &ref_node_handle)
 
void loadOdometerParameters (const ros::NodeHandle &ref_node_handle)
 
void loadOutputConfiguration (const ros::NodeHandle &ref_node_handle, const std::string &ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id)
 
void loadSensorParameters (const ros::NodeHandle &ref_node_handle)
 

Private Attributes

SbgEComAidingAssignConf m_aiding_assignement_conf_
 
bool m_configure_through_ros_
 
SbgEComGnssInstallation m_gnss_installation_
 
SbgEComModelInfo m_gnss_model_info_
 
SbgEComGnssRejectionConf m_gnss_rejection_conf_
 
uint32_t m_in_port_address_
 
SbgEComInitConditionConf m_init_condition_conf_
 
SbgEComMagCalibBandwidth m_mag_calib_bandwidth_
 
SbgEComMagCalibMode m_mag_calib_mode_
 
SbgEComModelInfo m_mag_model_info_
 
SbgEComMagRejectionConf m_mag_rejection_conf_
 
SbgEComModelInfo m_motion_profile_model_info_
 
SbgEComOdoConf m_odometer_conf_
 
SbgVector3< float > m_odometer_level_arm_
 
SbgEComOdoRejectionConf m_odometer_rejection_conf_
 
uint32_t m_out_port_address_
 
std::vector< SbgLogOutputm_output_modes_
 
SbgEComOutputPort m_output_port_
 
uint32_t m_rate_frequency_
 
bool m_ros_standard_output_
 
sbgIpAddress m_sbg_ip_address_
 
SbgEComSensorAlignmentInfo m_sensor_alignement_info_
 
SbgVector3< float > m_sensor_lever_arm_
 
bool m_serial_communication_
 
uint32_t m_uart_baud_rate_
 
std::string m_uart_port_name_
 
bool m_upd_communication_
 

Detailed Description

Class to handle the device configuration.

Definition at line 51 of file config_store.h.

Constructor & Destructor Documentation

ConfigStore::ConfigStore ( void  )

Default constructor.

Class to handle the device configuration.

Definition at line 13 of file config_store.cpp.

Member Function Documentation

bool ConfigStore::checkConfigWithRos ( void  ) const

Check if the configuration should be done with ROS.

Returns
True if the ROS driver has to configure the device.

Definition at line 150 of file config_store.cpp.

bool ConfigStore::checkRosStandardMessages ( void  ) const

Check if the ROS standard outputs are defined.

Returns
True if standard ROS messages output are defined.

Definition at line 275 of file config_store.cpp.

const SbgEComAidingAssignConf & ConfigStore::getAidingAssignement ( void  ) const

Get the aiding assignement configuration.

Returns
Aiding assignement configuration.

Definition at line 215 of file config_store.cpp.

uint32_t ConfigStore::getBaudRate ( void  ) const

Get the UART baudrate communication.

Returns
UART serial baudrate.

Definition at line 165 of file config_store.cpp.

const SbgEComGnssInstallation & ConfigStore::getGnssInstallation ( void  ) const

Get the Gnss installation configuration.

Returns
Gnss installation configuration.

Definition at line 245 of file config_store.cpp.

const SbgEComModelInfo & ConfigStore::getGnssModel ( void  ) const

Get the Gnss model configuration.

Returns
Gnss model configuration.

Definition at line 240 of file config_store.cpp.

const SbgEComGnssRejectionConf & ConfigStore::getGnssRejection ( void  ) const

Get the Gnss rejection configuration.

Returns
Gnss rejection configuration.

Definition at line 250 of file config_store.cpp.

const SbgEComInitConditionConf & ConfigStore::getInitialConditions ( void  ) const

Get the initial conditions configuration.

Returns
Initial conditions configuration.

Definition at line 195 of file config_store.cpp.

uint32_t ConfigStore::getInputPortAddress ( void  ) const

Get the input port.

Returns
Input port.

Definition at line 190 of file config_store.cpp.

sbgIpAddress ConfigStore::getIpAddress ( void  ) const

Get the Ip address of the interface.

Returns
Ip address.

Definition at line 180 of file config_store.cpp.

const SbgEComMagCalibBandwidth & ConfigStore::getMagnetometerCalibBandwidth ( void  ) const

Get the magnetometer calibration bandwidth.

Returns
Magnetometer calibration bandwidth.

Definition at line 235 of file config_store.cpp.

const SbgEComMagCalibMode & ConfigStore::getMagnetometerCalibMode ( void  ) const

Get the magnetometer calibration mode.

Returns
Magnetometer calibration mode.

Definition at line 230 of file config_store.cpp.

const SbgEComModelInfo & ConfigStore::getMagnetometerModel ( void  ) const

Get the magnetometer model configuration.

Returns
Magnetometer model configuration.

Definition at line 220 of file config_store.cpp.

const SbgEComMagRejectionConf & ConfigStore::getMagnetometerRejection ( void  ) const

Get the magnetometer rejection configuration.

Returns
Magnetometer rejection configuration.

Definition at line 225 of file config_store.cpp.

const SbgEComModelInfo & ConfigStore::getMotionProfile ( void  ) const

Get the motion profile configuration.

Returns
Motion profile configuration.

Definition at line 200 of file config_store.cpp.

const SbgEComOdoConf & ConfigStore::getOdometerConf ( void  ) const

Get the odometer configuration.

Returns
Odometer configuration.

Definition at line 255 of file config_store.cpp.

const sbg::SbgVector3< float > & ConfigStore::getOdometerLevelArms ( void  ) const

Get the odometer level arms.

Returns
Odometer level arms vector (in meters).

Definition at line 260 of file config_store.cpp.

const SbgEComOdoRejectionConf & ConfigStore::getOdometerRejection ( void  ) const

Get the odometer rejection.

Returns
Odometer rejection configuration.

Definition at line 265 of file config_store.cpp.

const std::vector< ConfigStore::SbgLogOutput > & ConfigStore::getOutputModes ( void  ) const

Get all the output modes.

Returns
Output mode for this config store.

Definition at line 270 of file config_store.cpp.

SbgEComOutputPort ConfigStore::getOutputPort ( void  ) const

Get the output port of the device.

Returns
SBG device output port.

Definition at line 170 of file config_store.cpp.

uint32_t ConfigStore::getOutputPortAddress ( void  ) const

Get the output port.

Returns
Output port.

Definition at line 185 of file config_store.cpp.

template<typename T >
T sbg::ConfigStore::getParameter ( const ros::NodeHandle ref_node_handle,
std::string  param_key,
int  default_value 
) const
inlineprivate

Get the ROS integer parameter casted in the T type. This function has the same behavior as the param base function, however it enables an implicit cast, and the use of const NodeHandle.

T Template type to cast the ROS param to.

Parameters
[in]ref_node_handleROS NodeHandle.
[in]param_keyParameter key.
[in]default_valueDefault value for the parameter.
Returns
ROS integer parameter casted.

Definition at line 119 of file config_store.h.

uint32_t ConfigStore::getReadingRateFrequency ( void  ) const

Get the reading frequency defined in settings. If this frequency is null, the driver will automatically configure the max output frequency according to the outputs.

Returns
Rate frequency parameter (in Hz).

Definition at line 280 of file config_store.cpp.

const SbgEComSensorAlignmentInfo & ConfigStore::getSensorAlignement ( void  ) const

Get the sensor alignement configuration.

Returns
Sensor alignement configuration.

Definition at line 205 of file config_store.cpp.

const sbg::SbgVector3< float > & ConfigStore::getSensorLevelArms ( void  ) const

Get the sensor level arms.

Returns
Sensor level arms vector (in meters).

Definition at line 210 of file config_store.cpp.

const std::string & ConfigStore::getUartPortName ( void  ) const

Get the UART port name.

Returns
UART serial port name.

Definition at line 160 of file config_store.cpp.

bool ConfigStore::isInterfaceSerial ( void  ) const

Check if the interface configuration is a serial interface.

Returns
True if the interface is serial, False otherwise.

Definition at line 155 of file config_store.cpp.

bool ConfigStore::isInterfaceUdp ( void  ) const

Check if the interface configuration is a UDP interface.

Returns
True if the interface is UDP, False otherwise.

Definition at line 175 of file config_store.cpp.

void ConfigStore::loadAidingAssignementParameters ( const ros::NodeHandle ref_node_handle)
private

Load aiding assignement parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 84 of file config_store.cpp.

void ConfigStore::loadCommunicationParameters ( const ros::NodeHandle ref_node_handle)
private

Load interface communication parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 26 of file config_store.cpp.

void ConfigStore::loadFromRosNodeHandle ( const ros::NodeHandle ref_node_handle)

Load the configuration from a ros parameter handle.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 289 of file config_store.cpp.

void ConfigStore::loadGnssParameters ( const ros::NodeHandle ref_node_handle)
private

Load Gnss parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 101 of file config_store.cpp.

void ConfigStore::loadImuAlignementParameters ( const ros::NodeHandle ref_node_handle)
private

Load IMU alignement parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 67 of file config_store.cpp.

void ConfigStore::loadMagnetometersParameters ( const ros::NodeHandle ref_node_handle)
private

Load magnetometers parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 92 of file config_store.cpp.

void ConfigStore::loadOdometerParameters ( const ros::NodeHandle ref_node_handle)
private

Load odometer parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 119 of file config_store.cpp.

void ConfigStore::loadOutputConfiguration ( const ros::NodeHandle ref_node_handle,
const std::string &  ref_key,
SbgEComClass  sbg_msg_class,
SbgEComMsgId  sbg_msg_id 
)
private

Load the output configuration.

Parameters
[in]ref_node_handleROS nodeHandle.
[in]ref_keyString key for the output config.
[in]sbg_msg_classSBG message class.
[in]sbg_msg_idID of the SBG log.

Definition at line 135 of file config_store.cpp.

void ConfigStore::loadSensorParameters ( const ros::NodeHandle ref_node_handle)
private

Load sensor parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 54 of file config_store.cpp.

Member Data Documentation

SbgEComAidingAssignConf sbg::ConfigStore::m_aiding_assignement_conf_
private

Definition at line 85 of file config_store.h.

bool sbg::ConfigStore::m_configure_through_ros_
private

Definition at line 77 of file config_store.h.

SbgEComGnssInstallation sbg::ConfigStore::m_gnss_installation_
private

Definition at line 93 of file config_store.h.

SbgEComModelInfo sbg::ConfigStore::m_gnss_model_info_
private

Definition at line 92 of file config_store.h.

SbgEComGnssRejectionConf sbg::ConfigStore::m_gnss_rejection_conf_
private

Definition at line 94 of file config_store.h.

uint32_t sbg::ConfigStore::m_in_port_address_
private

Definition at line 74 of file config_store.h.

SbgEComInitConditionConf sbg::ConfigStore::m_init_condition_conf_
private

Definition at line 79 of file config_store.h.

SbgEComMagCalibBandwidth sbg::ConfigStore::m_mag_calib_bandwidth_
private

Definition at line 90 of file config_store.h.

SbgEComMagCalibMode sbg::ConfigStore::m_mag_calib_mode_
private

Definition at line 89 of file config_store.h.

SbgEComModelInfo sbg::ConfigStore::m_mag_model_info_
private

Definition at line 87 of file config_store.h.

SbgEComMagRejectionConf sbg::ConfigStore::m_mag_rejection_conf_
private

Definition at line 88 of file config_store.h.

SbgEComModelInfo sbg::ConfigStore::m_motion_profile_model_info_
private

Definition at line 80 of file config_store.h.

SbgEComOdoConf sbg::ConfigStore::m_odometer_conf_
private

Definition at line 96 of file config_store.h.

SbgVector3<float> sbg::ConfigStore::m_odometer_level_arm_
private

Definition at line 97 of file config_store.h.

SbgEComOdoRejectionConf sbg::ConfigStore::m_odometer_rejection_conf_
private

Definition at line 98 of file config_store.h.

uint32_t sbg::ConfigStore::m_out_port_address_
private

Definition at line 73 of file config_store.h.

std::vector<SbgLogOutput> sbg::ConfigStore::m_output_modes_
private

Definition at line 100 of file config_store.h.

SbgEComOutputPort sbg::ConfigStore::m_output_port_
private

Definition at line 68 of file config_store.h.

uint32_t sbg::ConfigStore::m_rate_frequency_
private

Definition at line 102 of file config_store.h.

bool sbg::ConfigStore::m_ros_standard_output_
private

Definition at line 101 of file config_store.h.

sbgIpAddress sbg::ConfigStore::m_sbg_ip_address_
private

Definition at line 72 of file config_store.h.

SbgEComSensorAlignmentInfo sbg::ConfigStore::m_sensor_alignement_info_
private

Definition at line 82 of file config_store.h.

SbgVector3<float> sbg::ConfigStore::m_sensor_lever_arm_
private

Definition at line 83 of file config_store.h.

bool sbg::ConfigStore::m_serial_communication_
private

Definition at line 70 of file config_store.h.

uint32_t sbg::ConfigStore::m_uart_baud_rate_
private

Definition at line 69 of file config_store.h.

std::string sbg::ConfigStore::m_uart_port_name_
private

Definition at line 67 of file config_store.h.

bool sbg::ConfigStore::m_upd_communication_
private

Definition at line 75 of file config_store.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