#include <config_store.h>
Classes | |
struct | SbgLogOutput |
Private Member Functions | |
template<typename T > | |
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) |
Class to handle the device configuration.
Definition at line 60 of file config_store.h.
ConfigStore::ConfigStore | ( | ) |
Default constructor.
Class to handle the device configuration.
Definition at line 13 of file config_store.cpp.
bool ConfigStore::checkConfigWithRos | ( | ) | const |
Check if the configuration should be done with ROS.
Definition at line 224 of file config_store.cpp.
bool ConfigStore::checkRosStandardMessages | ( | ) | const |
Check if the ROS standard outputs are defined.
Definition at line 349 of file config_store.cpp.
const SbgEComAidingAssignConf & ConfigStore::getAidingAssignement | ( | ) | const |
Get the aiding assignement configuration.
Definition at line 289 of file config_store.cpp.
uint32_t ConfigStore::getBaudRate | ( | ) | const |
Get the UART baudrate communication.
Definition at line 239 of file config_store.cpp.
const std::string & ConfigStore::getFrameId | ( | ) | const |
const SbgEComGnssInstallation & ConfigStore::getGnssInstallation | ( | ) | const |
Get the Gnss installation configuration.
Definition at line 319 of file config_store.cpp.
const SbgEComModelInfo & ConfigStore::getGnssModel | ( | ) | const |
Get the Gnss model configuration.
Definition at line 314 of file config_store.cpp.
const SbgEComGnssRejectionConf & ConfigStore::getGnssRejection | ( | ) | const |
Get the Gnss rejection configuration.
Definition at line 324 of file config_store.cpp.
const SbgEComInitConditionConf & ConfigStore::getInitialConditions | ( | ) | const |
Get the initial conditions configuration.
Definition at line 269 of file config_store.cpp.
uint32_t ConfigStore::getInputPortAddress | ( | ) | const |
sbgIpAddress ConfigStore::getIpAddress | ( | ) | const |
Get the Ip address of the interface.
Definition at line 254 of file config_store.cpp.
const SbgEComMagCalibBandwidth & ConfigStore::getMagnetometerCalibBandwidth | ( | ) | const |
Get the magnetometer calibration bandwidth.
Definition at line 309 of file config_store.cpp.
const SbgEComMagCalibMode & ConfigStore::getMagnetometerCalibMode | ( | ) | const |
Get the magnetometer calibration mode.
Definition at line 304 of file config_store.cpp.
const SbgEComModelInfo & ConfigStore::getMagnetometerModel | ( | ) | const |
Get the magnetometer model configuration.
Definition at line 294 of file config_store.cpp.
const SbgEComMagRejectionConf & ConfigStore::getMagnetometerRejection | ( | ) | const |
Get the magnetometer rejection configuration.
Definition at line 299 of file config_store.cpp.
const SbgEComModelInfo & ConfigStore::getMotionProfile | ( | ) | const |
Get the motion profile configuration.
Definition at line 274 of file config_store.cpp.
const std::string & ConfigStore::getNmeaFullTopic | ( | ) | const |
Get NMEA full topic.
Definition at line 414 of file config_store.cpp.
const std::string & ConfigStore::getOdomBaseFrameId | ( | ) | const |
Get the odometry base frame ID.
Definition at line 389 of file config_store.cpp.
bool ConfigStore::getOdomEnable | ( | ) | const |
Get odom enable.
Definition at line 374 of file config_store.cpp.
const SbgEComOdoConf & ConfigStore::getOdometerConf | ( | ) | const |
Get the odometer configuration.
Definition at line 329 of file config_store.cpp.
const sbg::SbgVector3< float > & ConfigStore::getOdometerLevelArms | ( | ) | const |
Get the odometer level arms.
Definition at line 334 of file config_store.cpp.
const SbgEComOdoRejectionConf & ConfigStore::getOdometerRejection | ( | ) | const |
Get the odometer rejection.
Definition at line 339 of file config_store.cpp.
const std::string & ConfigStore::getOdomFrameId | ( | ) | const |
Get the odometry frame ID.
Definition at line 384 of file config_store.cpp.
const std::string & ConfigStore::getOdomInitFrameId | ( | ) | const |
Get the odometry init frame ID.
Definition at line 394 of file config_store.cpp.
bool ConfigStore::getOdomPublishTf | ( | ) | const |
Get odom publish_tf.
Definition at line 379 of file config_store.cpp.
const std::vector< ConfigStore::SbgLogOutput > & ConfigStore::getOutputModes | ( | ) | const |
Get all the output modes.
Definition at line 344 of file config_store.cpp.
SbgEComOutputPort ConfigStore::getOutputPort | ( | ) | const |
Get the output port of the device.
Definition at line 244 of file config_store.cpp.
uint32_t ConfigStore::getOutputPortAddress | ( | ) | 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.
[in] | ref_node_handle | ROS NodeHandle. |
[in] | param_key | Parameter key. |
[in] | default_value | Default value for the parameter. |
Definition at line 145 of file config_store.h.
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.
Definition at line 354 of file config_store.cpp.
const std::string & ConfigStore::getRtcmFullTopic | ( | ) | const |
Get RTCM full topic.
Definition at line 404 of file config_store.cpp.
const SbgEComSensorAlignmentInfo & ConfigStore::getSensorAlignement | ( | ) | const |
Get the sensor alignement configuration.
Definition at line 279 of file config_store.cpp.
const sbg::SbgVector3< float > & ConfigStore::getSensorLevelArms | ( | ) | const |
Get the sensor level arms.
Definition at line 284 of file config_store.cpp.
sbg::TimeReference ConfigStore::getTimeReference | ( | ) | const |
const std::string & ConfigStore::getUartPortName | ( | ) | const |
Get the UART port name.
Definition at line 234 of file config_store.cpp.
bool ConfigStore::getUseEnu | ( | ) | const |
Get use ENU.
Definition at line 364 of file config_store.cpp.
bool ConfigStore::isInterfaceSerial | ( | ) | const |
Check if the interface configuration is a serial interface.
Definition at line 229 of file config_store.cpp.
bool ConfigStore::isInterfaceUdp | ( | ) | const |
Check if the interface configuration is a UDP interface.
Definition at line 249 of file config_store.cpp.
|
private |
Load aiding assignement parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 100 of file config_store.cpp.
|
private |
Load interface communication parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 42 of file config_store.cpp.
|
private |
Load driver parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 28 of file config_store.cpp.
void ConfigStore::loadFromRosNodeHandle | ( | const ros::NodeHandle & | ref_node_handle | ) |
Load the configuration from a ros parameter handle.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 423 of file config_store.cpp.
|
private |
Load Gnss parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 117 of file config_store.cpp.
|
private |
Load IMU alignement parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 83 of file config_store.cpp.
|
private |
Load magnetometers parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 108 of file config_store.cpp.
|
private |
Load NMEA parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 208 of file config_store.cpp.
|
private |
Load odometer parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 135 of file config_store.cpp.
|
private |
Load odometry parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 33 of file config_store.cpp.
|
private |
Load the output configuration.
[in] | ref_node_handle | ROS nodeHandle. |
[in] | ref_key | String key for the output config. |
[in] | sbg_msg_class | SBG message class. |
[in] | sbg_msg_id | ID of the SBG log. |
Definition at line 151 of file config_store.cpp.
|
private |
Load frame parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 162 of file config_store.cpp.
|
private |
Load output time reference.
[in] | ref_node_handle | ROS nodeHandle. |
[in] | ref_key | String key for the output config. |
Definition at line 176 of file config_store.cpp.
|
private |
Load RTCM parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 196 of file config_store.cpp.
|
private |
Load sensor parameters.
[in] | ref_node_handle | ROS nodeHandle. |
Definition at line 70 of file config_store.cpp.
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.
Definition at line 409 of file config_store.cpp.
bool ConfigStore::shouldSubscribeToRtcm | ( | ) | const |
Returns if the node should subscribe to RTCM publisher
Definition at line 399 of file config_store.cpp.
|
private |
Definition at line 94 of file config_store.h.
|
private |
Definition at line 86 of file config_store.h.
|
private |
Definition at line 115 of file config_store.h.
|
private |
Definition at line 102 of file config_store.h.
|
private |
Definition at line 101 of file config_store.h.
|
private |
Definition at line 103 of file config_store.h.
|
private |
Definition at line 83 of file config_store.h.
|
private |
Definition at line 88 of file config_store.h.
|
private |
Definition at line 99 of file config_store.h.
|
private |
Definition at line 98 of file config_store.h.
|
private |
Definition at line 96 of file config_store.h.
|
private |
Definition at line 97 of file config_store.h.
|
private |
Definition at line 89 of file config_store.h.
|
private |
Definition at line 128 of file config_store.h.
|
private |
Definition at line 127 of file config_store.h.
|
private |
Definition at line 121 of file config_store.h.
|
private |
Definition at line 118 of file config_store.h.
|
private |
Definition at line 120 of file config_store.h.
|
private |
Definition at line 122 of file config_store.h.
|
private |
Definition at line 119 of file config_store.h.
|
private |
Definition at line 105 of file config_store.h.
|
private |
Definition at line 106 of file config_store.h.
|
private |
Definition at line 107 of file config_store.h.
|
private |
Definition at line 82 of file config_store.h.
|
private |
Definition at line 109 of file config_store.h.
|
private |
Definition at line 77 of file config_store.h.
|
private |
Definition at line 114 of file config_store.h.
|
private |
Definition at line 110 of file config_store.h.
|
private |
Definition at line 125 of file config_store.h.
|
private |
Definition at line 124 of file config_store.h.
|
private |
Definition at line 81 of file config_store.h.
|
private |
Definition at line 91 of file config_store.h.
|
private |
Definition at line 92 of file config_store.h.
|
private |
Definition at line 79 of file config_store.h.
|
private |
Definition at line 112 of file config_store.h.
|
private |
Definition at line 78 of file config_store.h.
|
private |
Definition at line 76 of file config_store.h.
|
private |
Definition at line 84 of file config_store.h.
|
private |
Definition at line 116 of file config_store.h.