#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) |
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_ |
Class to handle a connected SBG device.
Definition at line 56 of file sbg_device.h.
SbgDevice::SbgDevice | ( | ros::NodeHandle & | ref_node_handle | ) |
Default constructor.
[in] | ref_node_handle | ROS 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.
|
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.
Unable | to configure the connected device. |
Definition at line 204 of file sbg_device.cpp.
|
private |
Create the connection to the SBG device.
Unable | to connect to the SBG device. |
Definition at line 129 of file sbg_device.cpp.
|
private |
Display magnetometers calibration status result.
Definition at line 356 of file sbg_device.cpp.
|
private |
End the magnetometer calibration process.
Definition at line 308 of file sbg_device.cpp.
|
private |
Export magnetometers calibration results.
Definition at line 408 of file sbg_device.cpp.
uint32_t SbgDevice::getUpdateFrequency | ( | void | ) | const |
Get the frequency to update the main rate loop for device handling.
Definition at line 452 of file sbg_device.cpp.
|
private |
Get the SBG version as a string.
[in] | sbg_version_enc | SBG version encoded. |
Definition at line 189 of file sbg_device.cpp.
void SbgDevice::initDeviceForMagCalibration | ( | void | ) |
Initialize the device for magnetometers calibration.
Definition at line 475 of file sbg_device.cpp.
void SbgDevice::initDeviceForReceivingData | ( | void | ) |
Initialize the SBG device for receiving data.
Unable | to initialize the SBG device. |
Definition at line 461 of file sbg_device.cpp.
|
private |
Initialize the publishers according to the configuration.
Definition at line 197 of file sbg_device.cpp.
|
private |
Load the parameters.
Definition at line 120 of file sbg_device.cpp.
|
private |
Function to handle the received log.
[in] | msg_class | Class of the message we have received |
[in] | msg | Message ID of the log received. |
[in] | ref_sbg_data | Contains the received log data as an union. |
Definition at line 112 of file sbg_device.cpp.
|
staticprivate |
Callback definition called each time a new log is received.
[in] | pHandle | Valid handle on the sbgECom instance that has called this callback. |
[in] | msg_class | Class of the message we have received |
[in] | msg | Message ID of the log received. |
[in] | p_log_data | Contains the received log data as an union. |
[in] | p_user_arg | Optional user supplied argument. |
Definition at line 98 of file sbg_device.cpp.
void SbgDevice::periodicHandle | ( | void | ) |
Periodic handle of the connected SBG device.
Definition at line 483 of file sbg_device.cpp.
|
private |
Process the magnetometer calibration.
[in] | ref_ros_request | ROS service request. |
[in] | ref_ros_response | ROS service response. |
Definition at line 213 of file sbg_device.cpp.
|
private |
Read the device informations.
Unable | to read the device information. |
Definition at line 165 of file sbg_device.cpp.
|
private |
Save the magnetometer calibration.
[in] | ref_ros_request | ROS service request. |
[in] | ref_ros_response | ROS service response. |
Definition at line 252 of file sbg_device.cpp.
|
private |
Start the magnetometer calibration process.
Definition at line 283 of file sbg_device.cpp.
|
private |
Upload the magnetometers calibration results to the device.
Definition at line 328 of file sbg_device.cpp.
|
staticprivate |
Definition at line 67 of file sbg_device.h.
|
staticprivate |
Definition at line 65 of file sbg_device.h.
|
staticprivate |
Definition at line 66 of file sbg_device.h.
|
staticprivate |
Definition at line 64 of file sbg_device.h.
|
private |
Definition at line 85 of file sbg_device.h.
|
private |
Definition at line 84 of file sbg_device.h.
|
private |
Definition at line 73 of file sbg_device.h.
|
private |
Definition at line 77 of file sbg_device.h.
|
private |
Definition at line 82 of file sbg_device.h.
|
private |
Definition at line 81 of file sbg_device.h.
|
private |
Definition at line 83 of file sbg_device.h.
|
private |
Definition at line 76 of file sbg_device.h.
|
private |
Definition at line 79 of file sbg_device.h.
|
private |
Definition at line 75 of file sbg_device.h.
|
private |
Definition at line 74 of file sbg_device.h.