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 () const
 
bool checkRosStandardMessages () const
 
 ConfigStore ()
 
const SbgEComAidingAssignConfgetAidingAssignement () const
 
uint32_t getBaudRate () const
 
const std::string & getFrameId () const
 
const SbgEComGnssInstallationgetGnssInstallation () const
 
const SbgEComModelInfogetGnssModel () const
 
const SbgEComGnssRejectionConfgetGnssRejection () const
 
const SbgEComInitConditionConfgetInitialConditions () const
 
uint32_t getInputPortAddress () const
 
sbgIpAddress getIpAddress () const
 
const SbgEComMagCalibBandwidthgetMagnetometerCalibBandwidth () const
 
const SbgEComMagCalibModegetMagnetometerCalibMode () const
 
const SbgEComModelInfogetMagnetometerModel () const
 
const SbgEComMagRejectionConfgetMagnetometerRejection () const
 
const SbgEComModelInfogetMotionProfile () const
 
const std::string & getNmeaFullTopic () const
 
const std::string & getOdomBaseFrameId () const
 
bool getOdomEnable () const
 
const SbgEComOdoConfgetOdometerConf () const
 
const SbgVector3< float > & getOdometerLevelArms () const
 
const SbgEComOdoRejectionConfgetOdometerRejection () const
 
const std::string & getOdomFrameId () const
 
const std::string & getOdomInitFrameId () const
 
bool getOdomPublishTf () const
 
const std::vector< SbgLogOutput > & getOutputModes () const
 
SbgEComOutputPort getOutputPort () const
 
uint32_t getOutputPortAddress () const
 
uint32_t getReadingRateFrequency () const
 
const std::string & getRtcmFullTopic () const
 
const SbgEComSensorAlignmentInfogetSensorAlignement () const
 
const SbgVector3< float > & getSensorLevelArms () const
 
TimeReference getTimeReference () const
 
const std::string & getUartPortName () const
 
bool getUseEnu () const
 
bool isInterfaceSerial () const
 
bool isInterfaceUdp () const
 
void loadFromRosNodeHandle (const ros::NodeHandle &ref_node_handle)
 
bool shouldPublishNmea () const
 
bool shouldSubscribeToRtcm () const
 

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 loadDriverParameters (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 loadNmeaParameters (const ros::NodeHandle &ref_node_handle)
 
void loadOdometerParameters (const ros::NodeHandle &ref_node_handle)
 
void loadOdomParameters (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 loadOutputFrameParameters (const ros::NodeHandle &ref_node_handle)
 
void loadOutputTimeReference (const ros::NodeHandle &ref_node_handle, const std::string &ref_key)
 
void loadRtcmParameters (const ros::NodeHandle &ref_node_handle)
 
void loadSensorParameters (const ros::NodeHandle &ref_node_handle)
 

Private Attributes

SbgEComAidingAssignConf aiding_assignement_conf_
 
bool configure_through_ros_
 
std::string frame_id_
 
SbgEComGnssInstallation gnss_installation_
 
SbgEComModelInfo gnss_model_info_
 
SbgEComGnssRejectionConf gnss_rejection_conf_
 
uint32_t in_port_address_
 
SbgEComInitConditionConf init_condition_conf_
 
SbgEComMagCalibBandwidth mag_calib_bandwidth_
 
SbgEComMagCalibMode mag_calib_mode_
 
SbgEComModelInfo mag_model_info_
 
SbgEComMagRejectionConf mag_rejection_conf_
 
SbgEComModelInfo motion_profile_model_info_
 
std::string nmea_full_topic_
 
bool nmea_publish_
 
std::string odom_base_frame_id_
 
bool odom_enable_
 
std::string odom_frame_id_
 
std::string odom_init_frame_id_
 
bool odom_publish_tf_
 
SbgEComOdoConf odometer_conf_
 
SbgVector3< float > odometer_level_arm_
 
SbgEComOdoRejectionConf odometer_rejection_conf_
 
uint32_t out_port_address_
 
std::vector< SbgLogOutputoutput_modes_
 
SbgEComOutputPort output_port_
 
uint32_t rate_frequency_
 
bool ros_standard_output_
 
std::string rtcm_full_topic_
 
bool rtcm_subscribe_
 
sbgIpAddress sbg_ip_address_
 
SbgEComSensorAlignmentInfo sensor_alignement_info_
 
SbgVector3< float > sensor_lever_arm_
 
bool serial_communication_
 
TimeReference time_reference_
 
uint32_t uart_baud_rate_
 
std::string uart_port_name_
 
bool upd_communication_
 
bool use_enu_
 

Detailed Description

Class to handle the device configuration.

Definition at line 60 of file config_store.h.

Constructor & Destructor Documentation

◆ ConfigStore()

ConfigStore::ConfigStore ( )

Default constructor.

Class to handle the device configuration.

Definition at line 13 of file config_store.cpp.

Member Function Documentation

◆ checkConfigWithRos()

bool ConfigStore::checkConfigWithRos ( ) const

Check if the configuration should be done with ROS.

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

Definition at line 224 of file config_store.cpp.

◆ checkRosStandardMessages()

bool ConfigStore::checkRosStandardMessages ( ) const

Check if the ROS standard outputs are defined.

Returns
True if standard ROS messages output are defined.

Definition at line 349 of file config_store.cpp.

◆ getAidingAssignement()

const SbgEComAidingAssignConf & ConfigStore::getAidingAssignement ( ) const

Get the aiding assignement configuration.

Returns
Aiding assignement configuration.

Definition at line 289 of file config_store.cpp.

◆ getBaudRate()

uint32_t ConfigStore::getBaudRate ( ) const

Get the UART baudrate communication.

Returns
UART serial baudrate.

Definition at line 239 of file config_store.cpp.

◆ getFrameId()

const std::string & ConfigStore::getFrameId ( ) const

Get the frame ID.

Returns
Frame ID.

Definition at line 359 of file config_store.cpp.

◆ getGnssInstallation()

const SbgEComGnssInstallation & ConfigStore::getGnssInstallation ( ) const

Get the Gnss installation configuration.

Returns
Gnss installation configuration.

Definition at line 319 of file config_store.cpp.

◆ getGnssModel()

const SbgEComModelInfo & ConfigStore::getGnssModel ( ) const

Get the Gnss model configuration.

Returns
Gnss model configuration.

Definition at line 314 of file config_store.cpp.

◆ getGnssRejection()

const SbgEComGnssRejectionConf & ConfigStore::getGnssRejection ( ) const

Get the Gnss rejection configuration.

Returns
Gnss rejection configuration.

Definition at line 324 of file config_store.cpp.

◆ getInitialConditions()

const SbgEComInitConditionConf & ConfigStore::getInitialConditions ( ) const

Get the initial conditions configuration.

Returns
Initial conditions configuration.

Definition at line 269 of file config_store.cpp.

◆ getInputPortAddress()

uint32_t ConfigStore::getInputPortAddress ( ) const

Get the input port.

Returns
Input port.

Definition at line 264 of file config_store.cpp.

◆ getIpAddress()

sbgIpAddress ConfigStore::getIpAddress ( ) const

Get the Ip address of the interface.

Returns
Ip address.

Definition at line 254 of file config_store.cpp.

◆ getMagnetometerCalibBandwidth()

const SbgEComMagCalibBandwidth & ConfigStore::getMagnetometerCalibBandwidth ( ) const

Get the magnetometer calibration bandwidth.

Returns
Magnetometer calibration bandwidth.

Definition at line 309 of file config_store.cpp.

◆ getMagnetometerCalibMode()

const SbgEComMagCalibMode & ConfigStore::getMagnetometerCalibMode ( ) const

Get the magnetometer calibration mode.

Returns
Magnetometer calibration mode.

Definition at line 304 of file config_store.cpp.

◆ getMagnetometerModel()

const SbgEComModelInfo & ConfigStore::getMagnetometerModel ( ) const

Get the magnetometer model configuration.

Returns
Magnetometer model configuration.

Definition at line 294 of file config_store.cpp.

◆ getMagnetometerRejection()

const SbgEComMagRejectionConf & ConfigStore::getMagnetometerRejection ( ) const

Get the magnetometer rejection configuration.

Returns
Magnetometer rejection configuration.

Definition at line 299 of file config_store.cpp.

◆ getMotionProfile()

const SbgEComModelInfo & ConfigStore::getMotionProfile ( ) const

Get the motion profile configuration.

Returns
Motion profile configuration.

Definition at line 274 of file config_store.cpp.

◆ getNmeaFullTopic()

const std::string & ConfigStore::getNmeaFullTopic ( ) const

Get NMEA full topic.

Returns
String with NMEA namespace + topic.

Definition at line 414 of file config_store.cpp.

◆ getOdomBaseFrameId()

const std::string & ConfigStore::getOdomBaseFrameId ( ) const

Get the odometry base frame ID.

Returns
Odometry base frame ID.

Definition at line 389 of file config_store.cpp.

◆ getOdomEnable()

bool ConfigStore::getOdomEnable ( ) const

Get odom enable.

Returns
True if the odometry is enabled.

Definition at line 374 of file config_store.cpp.

◆ getOdometerConf()

const SbgEComOdoConf & ConfigStore::getOdometerConf ( ) const

Get the odometer configuration.

Returns
Odometer configuration.

Definition at line 329 of file config_store.cpp.

◆ getOdometerLevelArms()

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

Get the odometer level arms.

Returns
Odometer level arms vector (in meters).

Definition at line 334 of file config_store.cpp.

◆ getOdometerRejection()

const SbgEComOdoRejectionConf & ConfigStore::getOdometerRejection ( ) const

Get the odometer rejection.

Returns
Odometer rejection configuration.

Definition at line 339 of file config_store.cpp.

◆ getOdomFrameId()

const std::string & ConfigStore::getOdomFrameId ( ) const

Get the odometry frame ID.

Returns
Odometry frame ID.

Definition at line 384 of file config_store.cpp.

◆ getOdomInitFrameId()

const std::string & ConfigStore::getOdomInitFrameId ( ) const

Get the odometry init frame ID.

Returns
Odometry init frame ID.

Definition at line 394 of file config_store.cpp.

◆ getOdomPublishTf()

bool ConfigStore::getOdomPublishTf ( ) const

Get odom publish_tf.

Returns
If true publish odometry transforms.

Definition at line 379 of file config_store.cpp.

◆ getOutputModes()

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

Get all the output modes.

Returns
Output mode for this config store.

Definition at line 344 of file config_store.cpp.

◆ getOutputPort()

SbgEComOutputPort ConfigStore::getOutputPort ( ) const

Get the output port of the device.

Returns
SBG device output port.

Definition at line 244 of file config_store.cpp.

◆ getOutputPortAddress()

uint32_t ConfigStore::getOutputPortAddress ( ) const

Get the output port.

Returns
Output port.

Definition at line 259 of file config_store.cpp.

◆ getParameter()

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.

\template 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 145 of file config_store.h.

◆ getReadingRateFrequency()

uint32_t ConfigStore::getReadingRateFrequency ( ) 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 354 of file config_store.cpp.

◆ getRtcmFullTopic()

const std::string & ConfigStore::getRtcmFullTopic ( ) const

Get RTCM full topic.

Returns
String with RTCM namespace + topic.

Definition at line 404 of file config_store.cpp.

◆ getSensorAlignement()

const SbgEComSensorAlignmentInfo & ConfigStore::getSensorAlignement ( ) const

Get the sensor alignement configuration.

Returns
Sensor alignement configuration.

Definition at line 279 of file config_store.cpp.

◆ getSensorLevelArms()

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

Get the sensor level arms.

Returns
Sensor level arms vector (in meters).

Definition at line 284 of file config_store.cpp.

◆ getTimeReference()

sbg::TimeReference ConfigStore::getTimeReference ( ) const

Get the time reference.

Returns
Time reference.

Definition at line 369 of file config_store.cpp.

◆ getUartPortName()

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

Get the UART port name.

Returns
UART serial port name.

Definition at line 234 of file config_store.cpp.

◆ getUseEnu()

bool ConfigStore::getUseEnu ( ) const

Get use ENU.

Returns
True if the frame convention to use is ENU.

Definition at line 364 of file config_store.cpp.

◆ isInterfaceSerial()

bool ConfigStore::isInterfaceSerial ( ) const

Check if the interface configuration is a serial interface.

Returns
True if the interface is serial, False otherwise.

Definition at line 229 of file config_store.cpp.

◆ isInterfaceUdp()

bool ConfigStore::isInterfaceUdp ( ) const

Check if the interface configuration is a UDP interface.

Returns
True if the interface is UDP, False otherwise.

Definition at line 249 of file config_store.cpp.

◆ loadAidingAssignementParameters()

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

Load aiding assignement parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 100 of file config_store.cpp.

◆ loadCommunicationParameters()

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

Load interface communication parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 42 of file config_store.cpp.

◆ loadDriverParameters()

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

Load driver parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 28 of file config_store.cpp.

◆ loadFromRosNodeHandle()

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 423 of file config_store.cpp.

◆ loadGnssParameters()

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

Load Gnss parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 117 of file config_store.cpp.

◆ loadImuAlignementParameters()

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

Load IMU alignement parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 83 of file config_store.cpp.

◆ loadMagnetometersParameters()

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

Load magnetometers parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 108 of file config_store.cpp.

◆ loadNmeaParameters()

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

Load NMEA parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 208 of file config_store.cpp.

◆ loadOdometerParameters()

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

Load odometer parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 135 of file config_store.cpp.

◆ loadOdomParameters()

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

Load odometry parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 33 of file config_store.cpp.

◆ loadOutputConfiguration()

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 151 of file config_store.cpp.

◆ loadOutputFrameParameters()

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

Load frame parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 162 of file config_store.cpp.

◆ loadOutputTimeReference()

void ConfigStore::loadOutputTimeReference ( const ros::NodeHandle ref_node_handle,
const std::string &  ref_key 
)
private

Load output time reference.

Parameters
[in]ref_node_handleROS nodeHandle.
[in]ref_keyString key for the output config.

Definition at line 176 of file config_store.cpp.

◆ loadRtcmParameters()

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

Load RTCM parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 196 of file config_store.cpp.

◆ loadSensorParameters()

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

Load sensor parameters.

Parameters
[in]ref_node_handleROS nodeHandle.

Definition at line 70 of file config_store.cpp.

◆ shouldPublishNmea()

bool ConfigStore::shouldPublishNmea ( ) const

Returns if a specific NMEA GGA message should be published or not.

This GGA message is dedicated for NTRIP VRS operations and not for navigation.

Returns
True if NMEA is enabled.

Definition at line 409 of file config_store.cpp.

◆ shouldSubscribeToRtcm()

bool ConfigStore::shouldSubscribeToRtcm ( ) const

Returns if the node should subscribe to RTCM publisher

Returns
True to subscribe to RTCM messages.

Definition at line 399 of file config_store.cpp.

Member Data Documentation

◆ aiding_assignement_conf_

SbgEComAidingAssignConf sbg::ConfigStore::aiding_assignement_conf_
private

Definition at line 94 of file config_store.h.

◆ configure_through_ros_

bool sbg::ConfigStore::configure_through_ros_
private

Definition at line 86 of file config_store.h.

◆ frame_id_

std::string sbg::ConfigStore::frame_id_
private

Definition at line 115 of file config_store.h.

◆ gnss_installation_

SbgEComGnssInstallation sbg::ConfigStore::gnss_installation_
private

Definition at line 102 of file config_store.h.

◆ gnss_model_info_

SbgEComModelInfo sbg::ConfigStore::gnss_model_info_
private

Definition at line 101 of file config_store.h.

◆ gnss_rejection_conf_

SbgEComGnssRejectionConf sbg::ConfigStore::gnss_rejection_conf_
private

Definition at line 103 of file config_store.h.

◆ in_port_address_

uint32_t sbg::ConfigStore::in_port_address_
private

Definition at line 83 of file config_store.h.

◆ init_condition_conf_

SbgEComInitConditionConf sbg::ConfigStore::init_condition_conf_
private

Definition at line 88 of file config_store.h.

◆ mag_calib_bandwidth_

SbgEComMagCalibBandwidth sbg::ConfigStore::mag_calib_bandwidth_
private

Definition at line 99 of file config_store.h.

◆ mag_calib_mode_

SbgEComMagCalibMode sbg::ConfigStore::mag_calib_mode_
private

Definition at line 98 of file config_store.h.

◆ mag_model_info_

SbgEComModelInfo sbg::ConfigStore::mag_model_info_
private

Definition at line 96 of file config_store.h.

◆ mag_rejection_conf_

SbgEComMagRejectionConf sbg::ConfigStore::mag_rejection_conf_
private

Definition at line 97 of file config_store.h.

◆ motion_profile_model_info_

SbgEComModelInfo sbg::ConfigStore::motion_profile_model_info_
private

Definition at line 89 of file config_store.h.

◆ nmea_full_topic_

std::string sbg::ConfigStore::nmea_full_topic_
private

Definition at line 128 of file config_store.h.

◆ nmea_publish_

bool sbg::ConfigStore::nmea_publish_
private

Definition at line 127 of file config_store.h.

◆ odom_base_frame_id_

std::string sbg::ConfigStore::odom_base_frame_id_
private

Definition at line 121 of file config_store.h.

◆ odom_enable_

bool sbg::ConfigStore::odom_enable_
private

Definition at line 118 of file config_store.h.

◆ odom_frame_id_

std::string sbg::ConfigStore::odom_frame_id_
private

Definition at line 120 of file config_store.h.

◆ odom_init_frame_id_

std::string sbg::ConfigStore::odom_init_frame_id_
private

Definition at line 122 of file config_store.h.

◆ odom_publish_tf_

bool sbg::ConfigStore::odom_publish_tf_
private

Definition at line 119 of file config_store.h.

◆ odometer_conf_

SbgEComOdoConf sbg::ConfigStore::odometer_conf_
private

Definition at line 105 of file config_store.h.

◆ odometer_level_arm_

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

Definition at line 106 of file config_store.h.

◆ odometer_rejection_conf_

SbgEComOdoRejectionConf sbg::ConfigStore::odometer_rejection_conf_
private

Definition at line 107 of file config_store.h.

◆ out_port_address_

uint32_t sbg::ConfigStore::out_port_address_
private

Definition at line 82 of file config_store.h.

◆ output_modes_

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

Definition at line 109 of file config_store.h.

◆ output_port_

SbgEComOutputPort sbg::ConfigStore::output_port_
private

Definition at line 77 of file config_store.h.

◆ rate_frequency_

uint32_t sbg::ConfigStore::rate_frequency_
private

Definition at line 114 of file config_store.h.

◆ ros_standard_output_

bool sbg::ConfigStore::ros_standard_output_
private

Definition at line 110 of file config_store.h.

◆ rtcm_full_topic_

std::string sbg::ConfigStore::rtcm_full_topic_
private

Definition at line 125 of file config_store.h.

◆ rtcm_subscribe_

bool sbg::ConfigStore::rtcm_subscribe_
private

Definition at line 124 of file config_store.h.

◆ sbg_ip_address_

sbgIpAddress sbg::ConfigStore::sbg_ip_address_
private

Definition at line 81 of file config_store.h.

◆ sensor_alignement_info_

SbgEComSensorAlignmentInfo sbg::ConfigStore::sensor_alignement_info_
private

Definition at line 91 of file config_store.h.

◆ sensor_lever_arm_

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

Definition at line 92 of file config_store.h.

◆ serial_communication_

bool sbg::ConfigStore::serial_communication_
private

Definition at line 79 of file config_store.h.

◆ time_reference_

TimeReference sbg::ConfigStore::time_reference_
private

Definition at line 112 of file config_store.h.

◆ uart_baud_rate_

uint32_t sbg::ConfigStore::uart_baud_rate_
private

Definition at line 78 of file config_store.h.

◆ uart_port_name_

std::string sbg::ConfigStore::uart_port_name_
private

Definition at line 76 of file config_store.h.

◆ upd_communication_

bool sbg::ConfigStore::upd_communication_
private

Definition at line 84 of file config_store.h.

◆ use_enu_

bool sbg::ConfigStore::use_enu_
private

Definition at line 116 of file config_store.h.


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


sbg_driver
Author(s): SBG Systems
autogenerated on Fri Oct 11 2024 02:13:41