mag_calibration_status.cpp
Go to the documentation of this file.
1 
11 #include <mavros/mavros_plugin.h>
12 #include <std_msgs/UInt8.h>
13 #include <mavros_msgs/MagnetometerReporter.h>
14 #include <bitset>
15 
16 namespace mavros {
17 namespace std_plugins {
24 public:
26  mcs_nh("~mag_calibration")
27  { }
28 
32  void initialize(UAS &uas_)
33  {
35  mcs_pub = mcs_nh.advertise<std_msgs::UInt8>("status", 2, true);
36  mcr_pub = mcs_nh.advertise<mavros_msgs::MagnetometerReporter>("report", 2, true);
37  }
38 
48  return {
49  /* automatic message deduction by second argument */
52  };
53  }
54 
55 private:
59  std::array<bool, 8> calibration_show;
60  std::array<uint8_t, 8> _rg_compass_cal_progress;
61  //Send progress of magnetometer calibration
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>();
64 
65  // How many compasses are we calibrating?
66  std::bitset<8> compass_calibrating = mp.cal_mask;
67 
68  if (compass_calibrating[mp.compass_id]) {
69  // Each compass gets a portion of the overall progress
70  if (mp.completion_pct < 95) {
71  calibration_show[mp.compass_id] = true;
72  }
73  _rg_compass_cal_progress[mp.compass_id] = mp.completion_pct;
74  }
75 
76  // Prevent data over 100% after cal_mask reset bit assigned to compass_id
77  uint16_t total_percentage = 0;
78  for (size_t i = 0; i < 8 && (compass_calibrating >> i).any(); i++) {
79  if (compass_calibrating[i]) {
80  total_percentage += static_cast<uint8_t>(_rg_compass_cal_progress[i]);
81  }
82  }
83 
84  mcs->data = total_percentage / compass_calibrating.count();
85 
86  mcs_pub.publish(mcs);
87  }
88 
89  //Send report after calibration is done
90  void handle_report(const mavlink::mavlink_message_t *, mavlink::common::msg::MAG_CAL_REPORT &mr) {
91  if (calibration_show[mr.compass_id]) {
92  auto mcr = boost::make_shared<mavros_msgs::MagnetometerReporter>();
93  mcr->header.stamp = ros::Time::now();
94  mcr->header.frame_id = std::to_string(mr.compass_id);
95  mcr->report = mr.cal_status;
96  mcr->confidence = mr.orientation_confidence;
97  mcr_pub.publish(mcr);
98  calibration_show[mr.compass_id] = false;
99  }
100  }
101 };
102 } // namespace std_plugins
103 } // namespace mavros
104 
mavros::std_plugins::MagCalStatusPlugin::initialize
void initialize(UAS &uas_)
Definition: mag_calibration_status.cpp:32
mavros::std_plugins::MagCalStatusPlugin::mcr_pub
ros::Publisher mcr_pub
Definition: mag_calibration_status.cpp:58
mavros::std_plugins::MagCalStatusPlugin
MagCalStatus plugin.
Definition: mag_calibration_status.cpp:23
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
mavros::std_plugins::MagCalStatusPlugin::_rg_compass_cal_progress
std::array< uint8_t, 8 > _rg_compass_cal_progress
Definition: mag_calibration_status.cpp:60
ros::Publisher
mavros::std_plugins::MagCalStatusPlugin::handle_report
void handle_report(const mavlink::mavlink_message_t *, mavlink::common::msg::MAG_CAL_REPORT &mr)
Definition: mag_calibration_status.cpp:90
mavros::plugin::PluginBase::PluginBase
PluginBase()
mavros::UAS
mavros::std_plugins::MagCalStatusPlugin::get_subscriptions
Subscriptions get_subscriptions()
Definition: mag_calibration_status.cpp:47
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
mavros::std_plugins::MagCalStatusPlugin::mcs_nh
ros::NodeHandle mcs_nh
Definition: mag_calibration_status.cpp:56
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros_plugin.h
mavros::std_plugins::MagCalStatusPlugin::MagCalStatusPlugin
MagCalStatusPlugin()
Definition: mag_calibration_status.cpp:25
to_string
std::string to_string(ADSB_ALTITUDE_TYPE e)
mavros
mavros::std_plugins::MagCalStatusPlugin::mcs_pub
ros::Publisher mcs_pub
Definition: mag_calibration_status.cpp:57
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
class_list_macros.hpp
mavros::std_plugins::MagCalStatusPlugin::handle_status
void handle_status(const mavlink::mavlink_message_t *, mavlink::ardupilotmega::msg::MAG_CAL_PROGRESS &mp)
Definition: mag_calibration_status.cpp:62
mavros::std_plugins::MagCalStatusPlugin::calibration_show
std::array< bool, 8 > calibration_show
Definition: mag_calibration_status.cpp:59
mavros::plugin::PluginBase::make_handler
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
ros::NodeHandle
ros::Time::now
static Time now()


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08