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 (void) const
 
void initDeviceForMagCalibration (void)
 
void initDeviceForReceivingData (void)
 
void periodicHandle (void)
 
 SbgDevice (ros::NodeHandle &ref_node_handle)
 
 ~SbgDevice (void)
 

Private Member Functions

void configure (void)
 
void connect (void)
 
void displayMagCalibrationStatusResult (void) const
 
bool endMagCalibration (void)
 
void exportMagCalibrationResults (void) const
 
std::string getVersionAsString (uint32 sbg_version_enc) const
 
void initPublishers (void)
 
void loadParameters (void)
 
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 (void)
 
bool saveMagCalibration (std_srvs::Trigger::Request &ref_ros_request, std_srvs::Trigger::Response &ref_ros_response)
 
bool startMagCalibration (void)
 
bool uploadMagCalibrationToDevice (void)
 

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 m_calib_save_service_
 
ros::ServiceServer m_calib_service_
 
SbgEComHandle m_com_handle_
 
ConfigStore m_config_store_
 
bool m_mag_calibration_done_
 
bool m_mag_calibration_ongoing_
 
SbgEComMagCalibResults m_magCalibResults
 
MessagePublisher m_message_publisher_
 
uint32_t m_rate_frequency_
 
ros::NodeHandlem_ref_node_
 
ros::Time m_ros_processing_time_
 
SbgInterface m_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 56 of file sbg_device.h.

Constructor & Destructor Documentation

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 59 of file sbg_device.cpp.

SbgDevice::~SbgDevice ( void  )

Default destructor.

Definition at line 68 of file sbg_device.cpp.

Member Function Documentation

void SbgDevice::configure ( void  )
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 212 of file sbg_device.cpp.

void SbgDevice::connect ( void  )
private

Create the connection to the SBG device.

Exceptions
Unableto connect to the SBG device.

Definition at line 129 of file sbg_device.cpp.

void SbgDevice::displayMagCalibrationStatusResult ( void  ) const
private

Display magnetometers calibration status result.

Definition at line 364 of file sbg_device.cpp.

bool SbgDevice::endMagCalibration ( void  )
private

End the magnetometer calibration process.

Returns
True if the calibration process has ended successfully.

Definition at line 316 of file sbg_device.cpp.

void SbgDevice::exportMagCalibrationResults ( void  ) const
private

Export magnetometers calibration results.

Definition at line 416 of file sbg_device.cpp.

uint32_t SbgDevice::getUpdateFrequency ( void  ) 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 460 of file sbg_device.cpp.

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 187 of file sbg_device.cpp.

void SbgDevice::initDeviceForMagCalibration ( void  )

Initialize the device for magnetometers calibration.

Definition at line 483 of file sbg_device.cpp.

void SbgDevice::initDeviceForReceivingData ( void  )

Initialize the SBG device for receiving data.

Exceptions
Unableto initialize the SBG device.

Definition at line 469 of file sbg_device.cpp.

void SbgDevice::initPublishers ( void  )
private

Initialize the publishers according to the configuration.

Definition at line 195 of file sbg_device.cpp.

void SbgDevice::loadParameters ( void  )
private

Load the parameters.

Definition at line 120 of file sbg_device.cpp.

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 112 of file sbg_device.cpp.

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 98 of file sbg_device.cpp.

void SbgDevice::periodicHandle ( void  )

Periodic handle of the connected SBG device.

Definition at line 491 of file sbg_device.cpp.

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 221 of file sbg_device.cpp.

void SbgDevice::readDeviceInfo ( void  )
private

Read the device informations.

Exceptions
Unableto read the device information.

Definition at line 165 of file sbg_device.cpp.

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 260 of file sbg_device.cpp.

bool SbgDevice::startMagCalibration ( void  )
private

Start the magnetometer calibration process.

Returns
True if the calibration process has started successfully.

Definition at line 291 of file sbg_device.cpp.

bool SbgDevice::uploadMagCalibrationToDevice ( void  )
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 336 of file sbg_device.cpp.

Member Data Documentation

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 67 of file sbg_device.h.

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 65 of file sbg_device.h.

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

Definition at line 66 of file sbg_device.h.

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 64 of file sbg_device.h.

ros::ServiceServer sbg::SbgDevice::m_calib_save_service_
private

Definition at line 85 of file sbg_device.h.

ros::ServiceServer sbg::SbgDevice::m_calib_service_
private

Definition at line 84 of file sbg_device.h.

SbgEComHandle sbg::SbgDevice::m_com_handle_
private

Definition at line 73 of file sbg_device.h.

ConfigStore sbg::SbgDevice::m_config_store_
private

Definition at line 77 of file sbg_device.h.

bool sbg::SbgDevice::m_mag_calibration_done_
private

Definition at line 82 of file sbg_device.h.

bool sbg::SbgDevice::m_mag_calibration_ongoing_
private

Definition at line 81 of file sbg_device.h.

SbgEComMagCalibResults sbg::SbgDevice::m_magCalibResults
private

Definition at line 83 of file sbg_device.h.

MessagePublisher sbg::SbgDevice::m_message_publisher_
private

Definition at line 76 of file sbg_device.h.

uint32_t sbg::SbgDevice::m_rate_frequency_
private

Definition at line 79 of file sbg_device.h.

ros::NodeHandle& sbg::SbgDevice::m_ref_node_
private

Definition at line 75 of file sbg_device.h.

ros::Time sbg::SbgDevice::m_ros_processing_time_
private

Definition at line 87 of file sbg_device.h.

SbgInterface sbg::SbgDevice::m_sbg_interface_
private

Definition at line 74 of file sbg_device.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