Class ConfigStore

Nested Relationships

Nested Types

Class Documentation

class ConfigStore

Class to handle the device configuration.

Public Functions

ConfigStore()

Default constructor.

bool checkConfigWithRos() const

Check if the configuration should be done with ROS.

Returns:

True if the ROS driver has to configure the device.

bool isInterfaceSerial() const

Check if the interface configuration is a serial interface.

Returns:

True if the interface is serial, False otherwise.

const std::string &getUartPortName() const

Get the UART port name.

Returns:

UART serial port name.

uint32_t getBaudRate() const

Get the UART baudrate communication.

Returns:

UART serial baudrate.

SbgEComOutputPort getOutputPort() const

Get the output port of the device.

Returns:

SBG device output port.

bool isInterfaceUdp() const

Check if the interface configuration is a UDP interface.

Returns:

True if the interface is UDP, False otherwise.

sbgIpAddress getIpAddress() const

Get the Ip address of the interface.

Returns:

Ip address.

uint32_t getOutputPortAddress() const

Get the output port.

Returns:

Output port.

uint32_t getInputPortAddress() const

Get the input port.

Returns:

Input port.

const SbgEComInitConditionConf &getInitialConditions() const

Get the initial conditions configuration.

Returns:

Initial conditions configuration.

const SbgEComMotionProfileStdIds &getMotionProfile() const

Get the motion profile configuration.

Returns:

Motion profile configuration.

const SbgEComSensorAlignmentInfo &getSensorAlignement() const

Get the sensor alignement configuration.

Returns:

Sensor alignement configuration.

const SbgVector3<float> &getSensorLeverArm() const

Get the sensor lever arm.

Returns:

Sensor lever arm vector (in meters).

const SbgEComAidingAssignConf &getAidingAssignement() const

Get the aiding assignement configuration.

Returns:

Aiding assignement configuration.

const SbgEComMagModelsStdId &getMagnetometerModel() const

Get the magnetometer model configuration.

Returns:

Magnetometer model configuration.

const SbgEComMagRejectionConf &getMagnetometerRejection() const

Get the magnetometer rejection configuration.

Returns:

Magnetometer rejection configuration.

const SbgEComMagCalibMode &getMagnetometerCalibMode() const

Get the magnetometer calibration mode.

Returns:

Magnetometer calibration mode.

const SbgEComMagCalibBandwidth &getMagnetometerCalibBandwidth() const

Get the magnetometer calibration bandwidth.

Returns:

Magnetometer calibration bandwidth.

const SbgEComGnssModelsStdIds &getGnssModel() const

Get the Gnss model configuration.

Returns:

Gnss model configuration.

const SbgEComGnssInstallation &getGnssInstallation() const

Get the Gnss installation configuration.

Returns:

Gnss installation configuration.

const SbgEComGnssRejectionConf &getGnssRejection() const

Get the Gnss rejection configuration.

Returns:

Gnss rejection configuration.

const SbgEComOdoConf &getOdometerConf() const

Get the odometer configuration.

Returns:

Odometer configuration.

const SbgVector3<float> &getOdometerLeverArm() const

Get the odometer lever arm.

Returns:

Odometer lever arm vector (in meters).

const SbgEComOdoRejectionConf &getOdometerRejection() const

Get the odometer rejection.

Returns:

Odometer rejection configuration.

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

Get all the output modes.

Returns:

Output mode for this config store.

bool checkRosStandardMessages() const

Check if the ROS standard outputs are defined.

Returns:

True if standard ROS messages output are defined.

uint32_t 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).

const std::string &getFrameId() const

Get the frame ID.

Returns:

Frame ID.

bool getUseEnu() const

Get use ENU.

Returns:

True if the frame convention to use is ENU.

bool getOdomEnable() const

Get odom enable.

Returns:

True if the odometry is enabled.

bool getOdomPublishTf() const

Get odom publish_tf.

Returns:

If true publish odometry transforms.

const std::string &getOdomFrameId() const

Get the odometry frame ID.

Returns:

Odometry frame ID.

const std::string &getOdomBaseFrameId() const

Get the odometry base frame ID.

Returns:

Odometry base frame ID.

const std::string &getOdomInitFrameId() const

Get the odometry init frame ID.

Returns:

Odometry init frame ID.

TimeReference getTimeReference() const

Get the time reference.

Returns:

Time reference.

bool shouldSubscribeToRtcm() const

Returns if the node should subscribe to RTCM publisher

Returns:

True to subscribe to RTCM messages.

const std::string &getRtcmFullTopic() const

Get RTCM full topic.

Returns:

String with RTCM namespace + topic.

bool 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.

const std::string &getNmeaFullTopic() const

Get NMEA full topic.

Returns:

String with NMEA namespace + topic.

void loadFromRosNodeHandle(const rclcpp::Node &ref_node_handle)

Load the configuration from a ros parameter handle.

Parameters:

ref_node_handle[in] ROS nodeHandle.

struct SbgLogOutput

Structure to define the SBG log output.

Public Members

SbgEComClass message_class
SbgEComMsgId message_id
SbgEComOutputMode output_mode