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

#include <sbg_device.h>

Public Member Functions

uint32_t getUpdateFrequency () const
 
void initDeviceForMagCalibration ()
 
void initDeviceForReceivingData ()
 
void periodicHandle ()
 
 SbgDevice (ros::NodeHandle &ref_node_handle)
 
 ~SbgDevice ()
 

Private Member Functions

void configure ()
 
void connect ()
 
void displayMagCalibrationStatusResult () const
 
bool endMagCalibration ()
 
void exportMagCalibrationResults () const
 
std::string getVersionAsString (uint32 sbg_version_enc) const
 
void initPublishers ()
 
void initSubscribers ()
 
void loadParameters ()
 
void onLogReceived (SbgEComClass msg_class, SbgEComMsgId msg, const SbgBinaryLogData &ref_sbg_data)
 
bool processMagCalibration (std_srvs::Trigger::Request &ref_ros_request, std_srvs::Trigger::Response &ref_ros_response)
 
void readDeviceInfo ()
 
bool saveMagCalibration (std_srvs::Trigger::Request &ref_ros_request, std_srvs::Trigger::Response &ref_ros_response)
 
bool startMagCalibration ()
 
bool uploadMagCalibrationToDevice ()
 
void writeRtcmMessageToDevice (const rtcm_msgs::Message::ConstPtr &msg)
 

Static Private Member Functions

static SbgErrorCode onLogReceivedCallback (SbgEComHandle *p_handle, SbgEComClass msg_class, SbgEComMsgId msg, const SbgBinaryLogData *p_log_data, void *p_user_arg)
 

Private Attributes

ros::ServiceServer calib_save_service_
 
ros::ServiceServer calib_service_
 
SbgEComHandle com_handle_
 
ConfigStore config_store_
 
SbgEComMagCalibResults mag_calib_results_
 
bool mag_calibration_done_
 
bool mag_calibration_ongoing_
 
MessagePublisher message_publisher_
 
uint32_t rate_frequency_
 
ros::NodeHandleref_node_
 
ros::Subscriber rtcm_sub_
 
SbgInterface sbg_interface_
 

Static Private Attributes

static std::map< SbgEComMagCalibBandwidth, std::string > g_mag_calib_bandwidth_
 
static std::map< SbgEComMagCalibConfidence, std::string > g_mag_calib_confidence_
 
static std::map< SbgEComMagCalibMode, std::string > g_mag_calib_mode_
 
static std::map< SbgEComMagCalibQuality, std::string > g_mag_calib_quality_
 

Detailed Description

Class to handle a connected SBG device.

Definition at line 55 of file sbg_device.h.

Constructor & Destructor Documentation

◆ SbgDevice()

SbgDevice::SbgDevice ( ros::NodeHandle ref_node_handle)

Default constructor.

Parameters
[in]ref_node_handleROS NodeHandle.

Class to handle a connected SBG device.

Definition at line 60 of file sbg_device.cpp.

◆ ~SbgDevice()

SbgDevice::~SbgDevice ( )

Default destructor.

Definition at line 69 of file sbg_device.cpp.

Member Function Documentation

◆ configure()

void SbgDevice::configure ( )
private

Configure the connected SBG device. This function will configure the device if the config file allows it. It will log warning for unavailable parameters for the connected device.

Exceptions
Unableto configure the connected device.

Definition at line 221 of file sbg_device.cpp.

◆ connect()

void SbgDevice::connect ( )
private

Create the connection to the SBG device.

Exceptions
Unableto connect to the SBG device.

Definition at line 130 of file sbg_device.cpp.

◆ displayMagCalibrationStatusResult()

void SbgDevice::displayMagCalibrationStatusResult ( ) const
private

Display magnetometers calibration status result.

Definition at line 373 of file sbg_device.cpp.

◆ endMagCalibration()

bool SbgDevice::endMagCalibration ( )
private

End the magnetometer calibration process.

Returns
True if the calibration process has ended successfully.

Definition at line 325 of file sbg_device.cpp.

◆ exportMagCalibrationResults()

void SbgDevice::exportMagCalibrationResults ( ) const
private

Export magnetometers calibration results.

Definition at line 425 of file sbg_device.cpp.

◆ getUpdateFrequency()

uint32_t SbgDevice::getUpdateFrequency ( ) const

Get the frequency to update the main rate loop for device handling.

Returns
Device frequency to read the logs (in Hz).

Definition at line 483 of file sbg_device.cpp.

◆ getVersionAsString()

std::string SbgDevice::getVersionAsString ( uint32  sbg_version_enc) const
private

Get the SBG version as a string.

Parameters
[in]sbg_version_encSBG version encoded.
Returns
String version decoded.

Definition at line 194 of file sbg_device.cpp.

◆ initDeviceForMagCalibration()

void SbgDevice::initDeviceForMagCalibration ( )

Initialize the device for magnetometers calibration.

Definition at line 508 of file sbg_device.cpp.

◆ initDeviceForReceivingData()

void SbgDevice::initDeviceForReceivingData ( )

Initialize the SBG device for receiving data.

Exceptions
Unableto initialize the SBG device.

Definition at line 492 of file sbg_device.cpp.

◆ initPublishers()

void SbgDevice::initPublishers ( )
private

Initialize the publishers according to the configuration.

Definition at line 202 of file sbg_device.cpp.

◆ initSubscribers()

void SbgDevice::initSubscribers ( )
private

Initialize the subscribers according to the configuration.

Definition at line 209 of file sbg_device.cpp.

◆ loadParameters()

void SbgDevice::loadParameters ( )
private

Load the parameters.

Definition at line 121 of file sbg_device.cpp.

◆ onLogReceived()

void SbgDevice::onLogReceived ( SbgEComClass  msg_class,
SbgEComMsgId  msg,
const SbgBinaryLogData ref_sbg_data 
)
private

Function to handle the received log.

Parameters
[in]msg_classClass of the message we have received
[in]msgMessage ID of the log received.
[in]ref_sbg_dataContains the received log data as an union.

Definition at line 113 of file sbg_device.cpp.

◆ onLogReceivedCallback()

SbgErrorCode SbgDevice::onLogReceivedCallback ( SbgEComHandle p_handle,
SbgEComClass  msg_class,
SbgEComMsgId  msg,
const SbgBinaryLogData p_log_data,
void *  p_user_arg 
)
staticprivate

Callback definition called each time a new log is received.

Parameters
[in]pHandleValid handle on the sbgECom instance that has called this callback.
[in]msg_classClass of the message we have received
[in]msgMessage ID of the log received.
[in]p_log_dataContains the received log data as an union.
[in]p_user_argOptional user supplied argument.
Returns
SBG_NO_ERROR if the received log has been used successfully.

Definition at line 99 of file sbg_device.cpp.

◆ periodicHandle()

void SbgDevice::periodicHandle ( )

Periodic handle of the connected SBG device.

Definition at line 516 of file sbg_device.cpp.

◆ processMagCalibration()

bool SbgDevice::processMagCalibration ( std_srvs::Trigger::Request &  ref_ros_request,
std_srvs::Trigger::Response &  ref_ros_response 
)
private

Process the magnetometer calibration.

Parameters
[in]ref_ros_requestROS service request.
[in]ref_ros_responseROS service response.
Returns
Return true if the calibration process has been succesfull.

Definition at line 230 of file sbg_device.cpp.

◆ readDeviceInfo()

void SbgDevice::readDeviceInfo ( )
private

Read the device informations.

Exceptions
Unableto read the device information.

Definition at line 170 of file sbg_device.cpp.

◆ saveMagCalibration()

bool SbgDevice::saveMagCalibration ( std_srvs::Trigger::Request &  ref_ros_request,
std_srvs::Trigger::Response &  ref_ros_response 
)
private

Save the magnetometer calibration.

Parameters
[in]ref_ros_requestROS service request.
[in]ref_ros_responseROS service response.
Returns
Return true if the calibration has been saved.

Definition at line 269 of file sbg_device.cpp.

◆ startMagCalibration()

bool SbgDevice::startMagCalibration ( )
private

Start the magnetometer calibration process.

Returns
True if the calibration process has started successfully.

Definition at line 300 of file sbg_device.cpp.

◆ uploadMagCalibrationToDevice()

bool SbgDevice::uploadMagCalibrationToDevice ( )
private

Upload the magnetometers calibration results to the device.

Returns
True if the magnetometers calibration has been successfully uploaded to the device.

Definition at line 345 of file sbg_device.cpp.

◆ writeRtcmMessageToDevice()

void SbgDevice::writeRtcmMessageToDevice ( const rtcm_msgs::Message::ConstPtr &  msg)
private

Handler for subscription to RTCM topic.

Parameters
[in]msgROS RTCM message.

Definition at line 465 of file sbg_device.cpp.

Member Data Documentation

◆ calib_save_service_

ros::ServiceServer sbg::SbgDevice::calib_save_service_
private

Definition at line 84 of file sbg_device.h.

◆ calib_service_

ros::ServiceServer sbg::SbgDevice::calib_service_
private

Definition at line 83 of file sbg_device.h.

◆ com_handle_

SbgEComHandle sbg::SbgDevice::com_handle_
private

Definition at line 72 of file sbg_device.h.

◆ config_store_

ConfigStore sbg::SbgDevice::config_store_
private

Definition at line 76 of file sbg_device.h.

◆ g_mag_calib_bandwidth_

std::map< SbgEComMagCalibBandwidth, std::string > SbgDevice::g_mag_calib_bandwidth_
staticprivate
Initial value:
= {{SBG_ECOM_MAG_CALIB_HIGH_BW, "High Bandwidth"},
{SBG_ECOM_MAG_CALIB_MEDIUM_BW, "Medium Bandwidth"},
{SBG_ECOM_MAG_CALIB_LOW_BW, "Low Bandwidth"}}

Definition at line 66 of file sbg_device.h.

◆ g_mag_calib_confidence_

std::map< SbgEComMagCalibConfidence, std::string > SbgDevice::g_mag_calib_confidence_
staticprivate
Initial value:
= { {SBG_ECOM_MAG_CALIB_TRUST_HIGH, "Confidence: high"},
{SBG_ECOM_MAG_CALIB_TRUST_MEDIUM, "Confidence: medium"},
{SBG_ECOM_MAG_CALIB_TRUST_LOW, "Confidence: low"}}

Definition at line 64 of file sbg_device.h.

◆ g_mag_calib_mode_

std::map< SbgEComMagCalibMode, std::string > SbgDevice::g_mag_calib_mode_
staticprivate
Initial value:

Definition at line 65 of file sbg_device.h.

◆ g_mag_calib_quality_

std::map< SbgEComMagCalibQuality, std::string > SbgDevice::g_mag_calib_quality_
staticprivate
Initial value:
= { {SBG_ECOM_MAG_CALIB_QUAL_OPTIMAL, "Quality: optimal"},
{SBG_ECOM_MAG_CALIB_QUAL_GOOD, "Quality: good"},
{SBG_ECOM_MAG_CALIB_QUAL_POOR, "Quality: poor"},
{SBG_ECOM_MAG_CALIB_QUAL_INVALID, "Quality: invalid"}}

Definition at line 63 of file sbg_device.h.

◆ mag_calib_results_

SbgEComMagCalibResults sbg::SbgDevice::mag_calib_results_
private

Definition at line 82 of file sbg_device.h.

◆ mag_calibration_done_

bool sbg::SbgDevice::mag_calibration_done_
private

Definition at line 81 of file sbg_device.h.

◆ mag_calibration_ongoing_

bool sbg::SbgDevice::mag_calibration_ongoing_
private

Definition at line 80 of file sbg_device.h.

◆ message_publisher_

MessagePublisher sbg::SbgDevice::message_publisher_
private

Definition at line 75 of file sbg_device.h.

◆ rate_frequency_

uint32_t sbg::SbgDevice::rate_frequency_
private

Definition at line 78 of file sbg_device.h.

◆ ref_node_

ros::NodeHandle& sbg::SbgDevice::ref_node_
private

Definition at line 74 of file sbg_device.h.

◆ rtcm_sub_

ros::Subscriber sbg::SbgDevice::rtcm_sub_
private

Definition at line 86 of file sbg_device.h.

◆ sbg_interface_

SbgInterface sbg::SbgDevice::sbg_interface_
private

Definition at line 73 of file sbg_device.h.


The documentation for this class was generated from the following files:
SBG_ECOM_MAG_CALIB_HIGH_BW
@ SBG_ECOM_MAG_CALIB_HIGH_BW
Definition: sbgEComCmdMag.h:49
SBG_ECOM_MAG_CALIB_TRUST_LOW
@ SBG_ECOM_MAG_CALIB_TRUST_LOW
Definition: sbgEComCmdMag.h:70
SBG_ECOM_MAG_CALIB_QUAL_GOOD
@ SBG_ECOM_MAG_CALIB_QUAL_GOOD
Definition: sbgEComCmdMag.h:58
SBG_ECOM_MAG_CALIB_MODE_3D
@ SBG_ECOM_MAG_CALIB_MODE_3D
Definition: sbgEComCmdMag.h:37
SBG_ECOM_MAG_CALIB_QUAL_OPTIMAL
@ SBG_ECOM_MAG_CALIB_QUAL_OPTIMAL
Definition: sbgEComCmdMag.h:57
SBG_ECOM_MAG_CALIB_LOW_BW
@ SBG_ECOM_MAG_CALIB_LOW_BW
Definition: sbgEComCmdMag.h:47
SBG_ECOM_MAG_CALIB_QUAL_POOR
@ SBG_ECOM_MAG_CALIB_QUAL_POOR
Definition: sbgEComCmdMag.h:59
SBG_ECOM_MAG_CALIB_MODE_2D
@ SBG_ECOM_MAG_CALIB_MODE_2D
Definition: sbgEComCmdMag.h:34
SBG_ECOM_MAG_CALIB_QUAL_INVALID
@ SBG_ECOM_MAG_CALIB_QUAL_INVALID
Definition: sbgEComCmdMag.h:60
SBG_ECOM_MAG_CALIB_TRUST_HIGH
@ SBG_ECOM_MAG_CALIB_TRUST_HIGH
Definition: sbgEComCmdMag.h:68
SBG_ECOM_MAG_CALIB_MEDIUM_BW
@ SBG_ECOM_MAG_CALIB_MEDIUM_BW
Definition: sbgEComCmdMag.h:48
SBG_ECOM_MAG_CALIB_TRUST_MEDIUM
@ SBG_ECOM_MAG_CALIB_TRUST_MEDIUM
Definition: sbgEComCmdMag.h:69


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