12 #include <std_msgs/UInt8.h>
13 #include <mavros_msgs/MagnetometerReporter.h>
17 namespace std_plugins {
62 void handle_status(
const mavlink::mavlink_message_t *, mavlink::ardupilotmega::msg::MAG_CAL_PROGRESS &mp) {
63 auto mcs = boost::make_shared<std_msgs::UInt8>();
66 std::bitset<8> compass_calibrating = mp.cal_mask;
68 if (compass_calibrating[mp.compass_id]) {
70 if (mp.completion_pct < 95) {
77 uint16_t total_percentage = 0;
78 for (
size_t i = 0; i < 8 && (compass_calibrating >> i).any(); i++) {
79 if (compass_calibrating[i]) {
84 mcs->data = total_percentage / compass_calibrating.count();
90 void handle_report(
const mavlink::mavlink_message_t *, mavlink::common::msg::MAG_CAL_REPORT &mr) {
92 auto mcr = boost::make_shared<mavros_msgs::MagnetometerReporter>();
95 mcr->report = mr.cal_status;
96 mcr->confidence = mr.orientation_confidence;