34 #ifndef SBG_ROS_SBG_DEVICE_H 35 #define SBG_ROS_SBG_DEVICE_H 43 #include <std_srvs/SetBool.h> 44 #include <std_srvs/Trigger.h> 160 bool processMagCalibration(std_srvs::Trigger::Request& ref_ros_request, std_srvs::Trigger::Response& ref_ros_response);
169 bool saveMagCalibration(std_srvs::Trigger::Request& ref_ros_request, std_srvs::Trigger::Response& ref_ros_response);
254 #endif // SBG_ROS_SBG_DEVICE_H Apply configuration to the device.
MessagePublisher m_message_publisher_
ros::ServiceServer m_calib_save_service_
bool processMagCalibration(std_srvs::Trigger::Request &ref_ros_request, std_srvs::Trigger::Response &ref_ros_response)
void exportMagCalibrationResults(void) const
void periodicHandle(void)
void onLogReceived(SbgEComClass msg_class, SbgEComMsgId msg, const SbgBinaryLogData &ref_sbg_data)
Manage publishment of messages from logs.
bool uploadMagCalibrationToDevice(void)
uint32_t getUpdateFrequency(void) const
ros::NodeHandle & m_ref_node_
void displayMagCalibrationStatusResult(void) const
SbgInterface m_sbg_interface_
static std::map< SbgEComMagCalibQuality, std::string > g_mag_calib_quality_
ConfigStore m_config_store_
Class to handle the device configuration.
SbgEComHandle m_com_handle_
void loadParameters(void)
std::string getVersionAsString(uint32 sbg_version_enc) const
void readDeviceInfo(void)
bool startMagCalibration(void)
static std::map< SbgEComMagCalibConfidence, std::string > g_mag_calib_confidence_
SbgEComMagCalibResults m_magCalibResults
static std::map< SbgEComMagCalibMode, std::string > g_mag_calib_mode_
uint32_t m_rate_frequency_
bool endMagCalibration(void)
SbgDevice(ros::NodeHandle &ref_node_handle)
static std::map< SbgEComMagCalibBandwidth, std::string > g_mag_calib_bandwidth
enum _SbgEComClass SbgEComClass
bool saveMagCalibration(std_srvs::Trigger::Request &ref_ros_request, std_srvs::Trigger::Response &ref_ros_response)
bool m_mag_calibration_done_
void initDeviceForReceivingData(void)
void initDeviceForMagCalibration(void)
bool m_mag_calibration_ongoing_
void initPublishers(void)
enum _SbgErrorCode SbgErrorCode
static SbgErrorCode onLogReceivedCallback(SbgEComHandle *p_handle, SbgEComClass msg_class, SbgEComMsgId msg, const SbgBinaryLogData *p_log_data, void *p_user_arg)
ros::ServiceServer m_calib_service_