mount_control.cpp
Go to the documentation of this file.
1 
10 /*
11  * Copyright 2019 Jaeyoung Lim.
12  * Copyright 2021 Dr.-Ing. Amilcar do Carmo Lucas <amilcar.lucas@iav.de>.
13  *
14  * This file is part of the mavros package and subject to the license terms
15  * in the top-level LICENSE file of the mavros repository.
16  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
17  */
18 
19 #include <mavros/mavros_plugin.h>
20 
21 #include <mavros_msgs/CommandLong.h>
22 #include <mavros_msgs/MountControl.h>
23 #include <geometry_msgs/Quaternion.h>
24 #include <geometry_msgs/Vector3Stamped.h>
25 #include <mavros_msgs/MountConfigure.h>
26 
27 namespace mavros {
28 namespace extra_plugins {
30 using mavlink::common::MAV_MOUNT_MODE;
31 using mavlink::common::MAV_CMD;
32 using utils::enum_value;
33 
38 {
39 public:
40  MountStatusDiag(const std::string &name) :
43  _debounce_s(NAN),
44  _roll_deg(NAN),
45  _pitch_deg(NAN),
46  _yaw_deg(NAN),
47  _setpoint_roll_deg(NAN),
49  _setpoint_yaw_deg(NAN),
50  _err_threshold_deg(NAN),
51  _error_detected(false),
52  _mode(255)
53  { }
54 
55  void set_err_threshold_deg(float threshold_deg) {
56  std::lock_guard<std::mutex> lock(mutex);
57  _err_threshold_deg = threshold_deg;
58  }
59 
60  void set_debounce_s(double debounce_s) {
61  std::lock_guard<std::mutex> lock(mutex);
62  _debounce_s = debounce_s;
63  }
64 
65  void set_status(float roll_deg, float pitch_deg, float yaw_deg, ros::Time timestamp) {
66  std::lock_guard<std::mutex> lock(mutex);
67  _roll_deg = roll_deg;
68  _pitch_deg = pitch_deg;
69  _yaw_deg = yaw_deg;
70  _last_orientation_update = timestamp;
71  }
72 
73  void set_setpoint(float roll_deg, float pitch_deg, float yaw_deg, uint8_t mode) {
74  std::lock_guard<std::mutex> lock(mutex);
75  _setpoint_roll_deg = roll_deg;
76  _setpoint_pitch_deg = pitch_deg;
77  _setpoint_yaw_deg = yaw_deg;
78  _mode = mode;
79  }
80 
82  {
83  float roll_err_deg;
84  float pitch_err_deg;
85  float yaw_err_deg;
86  bool error_detected = false;
87  bool stale = false;
88 
89  if (_mode != mavros_msgs::MountControl::MAV_MOUNT_MODE_MAVLINK_TARGETING) {
90  // Can only directly compare the MAV_CMD_DO_MOUNT_CONTROL angles with the MOUNT_ORIENTATION angles when in MAVLINK_TARGETING mode
91  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Can not diagnose in this targeting mode");
92  stat.addf("Mode", "%d", _mode);
93  return;
94  }
95 
96  const ros::Time now = ros::Time::now();
97  {
98  std::lock_guard<std::mutex> lock(mutex);
99  roll_err_deg = _setpoint_roll_deg - _roll_deg;
100  pitch_err_deg = _setpoint_pitch_deg - _pitch_deg;
101  yaw_err_deg = _setpoint_yaw_deg - _yaw_deg;
102 
103  // detect errors (setpoint != current angle)
104  if (fabs(roll_err_deg) > _err_threshold_deg) {
105  error_detected = true;
106  }
107  if (fabs(pitch_err_deg) > _err_threshold_deg) {
108  error_detected = true;
109  }
110  if (fabs(yaw_err_deg) > _err_threshold_deg) {
111  error_detected = true;
112  }
113  if (now - _last_orientation_update > ros::Duration(5, 0)) {
114  stale = true;
115  }
116  // accessing the _debounce_s variable should be done inside this mutex,
117  // but we can treat it as an atomic variable, and save the trouble
118  }
119 
120  // detect error state changes
121  if (!_error_detected && error_detected) {
122  _error_started = now;
123  _error_detected = true;
124  }
125  if (_error_detected && !error_detected) {
126  _error_detected = false;
127  }
128 
129  // debounce errors
130  if (stale) {
131  stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "No MOUNT_ORIENTATION received in the last 5 s");
132  } else if (_error_detected && (now - _error_started > ros::Duration(_debounce_s))) {
133  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "angle error too high");
134  } else {
135  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Normal");
136  }
137 
138  stat.addf("Roll err (deg)", "%.1f", roll_err_deg);
139  stat.addf("Pitch err (deg)", "%.1f", pitch_err_deg);
140  stat.addf("Yaw err (deg)", "%.1f", yaw_err_deg);
141  }
142 
143 private:
147  double _debounce_s;
148  float _roll_deg;
149  float _pitch_deg;
150  float _yaw_deg;
156  uint8_t _mode;
157 };
158 
166 public:
168  nh("~"),
169  mount_nh("~mount_control"),
170  mount_diag("Mount")
171  { }
172 
173  void initialize(UAS &uas_) override
174  {
176 
178  mount_orientation_pub = mount_nh.advertise<geometry_msgs::Quaternion>("orientation", 10);
179  mount_status_pub = mount_nh.advertise<geometry_msgs::Vector3Stamped>("status", 10);
181 
182  // some gimbals send negated/inverted angle measurements
183  // these parameters correct that to obey the MAVLink frame convention
184  mount_nh.param<bool>("negate_measured_roll", negate_measured_roll, false);
185  mount_nh.param<bool>("negate_measured_pitch", negate_measured_pitch, false);
186  mount_nh.param<bool>("negate_measured_yaw", negate_measured_yaw, false);
187  if (!mount_nh.getParam("negate_measured_roll", negate_measured_roll)) {
188  ROS_WARN("Could not retrive negate_measured_roll parameter value, using default (%d)", negate_measured_roll);
189  }
190  if (!mount_nh.getParam("negate_measured_pitch", negate_measured_pitch)) {
191  ROS_WARN("Could not retrive negate_measured_pitch parameter value, using default (%d)", negate_measured_pitch);
192  }
193  if (!mount_nh.getParam("negate_measured_yaw", negate_measured_yaw)) {
194  ROS_WARN("Could not retrive negate_measured_yaw parameter value, using default (%d)", negate_measured_yaw);
195  }
196 
197  bool disable_diag;
198  if (nh.getParam("sys/disable_diag", disable_diag) && !disable_diag) {
199  double debounce_s;
200  double err_threshold_deg;
201  mount_nh.param("debounce_s", debounce_s, 4.0);
202  mount_nh.param("err_threshold_deg", err_threshold_deg, 10.0);
203  if (!mount_nh.getParam("debounce_s", debounce_s)) {
204  ROS_WARN("Could not retrive debounce_s parameter value, using default (%f)", debounce_s);
205  }
206  if (!mount_nh.getParam("err_threshold_deg", err_threshold_deg)) {
207  ROS_WARN("Could not retrive err_threshold_deg parameter value, using default (%f)", err_threshold_deg);
208  }
209  mount_diag.set_debounce_s(debounce_s);
210  mount_diag.set_err_threshold_deg(err_threshold_deg);
211  UAS_DIAG(m_uas).add(mount_diag);
212  }
213  }
214 
216  {
217  return {
220  };
221  }
222 
223 private:
230 
235 
243  void handle_mount_orientation(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MOUNT_ORIENTATION &mo)
244  {
245  const auto timestamp = ros::Time::now();
246  // some gimbals send negated/inverted angle measurements, correct that to obey the MAVLink frame convention
247  if (negate_measured_roll) {
248  mo.roll = -mo.roll;
249  }
250  if (negate_measured_pitch) {
251  mo.pitch = -mo.pitch;
252  }
253  if (negate_measured_yaw) {
254  mo.yaw = -mo.yaw;
255  mo.yaw_absolute = -mo.yaw_absolute;
256  }
257  const auto q = ftf::quaternion_from_rpy(Eigen::Vector3d(mo.roll, mo.pitch, mo.yaw) * M_PI / 180.0);
258  geometry_msgs::Quaternion quaternion_msg;
259  tf::quaternionEigenToMsg(q, quaternion_msg);
260  mount_orientation_pub.publish(quaternion_msg);
261 
262  mount_diag.set_status(mo.roll, mo.pitch, mo.yaw_absolute, timestamp);
263  }
264 
271  void handle_mount_status(const mavlink::mavlink_message_t *, mavlink::ardupilotmega::msg::MOUNT_STATUS &ms)
272  {
273  geometry_msgs::Vector3Stamped publish_msg;
274 
275  publish_msg.header.stamp = ros::Time::now();
276 
277  publish_msg.header.frame_id = std::to_string(ms.target_component);
278 
279  auto vec = Eigen::Vector3d(ms.pointing_b, ms.pointing_a, ms.pointing_c) * M_PI / 18000.0;
280  tf::vectorEigenToMsg(vec, publish_msg.vector);
281 
282  mount_status_pub.publish(publish_msg);
283 
284  // pointing_X is cdeg
285  auto q = ftf::quaternion_from_rpy(Eigen::Vector3d(ms.pointing_b, ms.pointing_a, ms.pointing_c) * M_PI / 18000.0);
286  geometry_msgs::Quaternion quaternion_msg;
287  tf::quaternionEigenToMsg(q, quaternion_msg);
288  mount_orientation_pub.publish(quaternion_msg);
289  }
290 
298  {
299  mavlink::common::msg::COMMAND_LONG cmd {};
300 
301  cmd.target_system = m_uas->get_tgt_system();
302  cmd.target_component = m_uas->get_tgt_component();
303  cmd.command = enum_value(MAV_CMD::DO_MOUNT_CONTROL);
304  cmd.param1 = req->pitch;
305  cmd.param2 = req->roll;
306  cmd.param3 = req->yaw;
307  cmd.param4 = req->altitude; //
308  cmd.param5 = req->latitude; // latitude in degrees * 1E7
309  cmd.param6 = req->longitude; // longitude in degrees * 1E7
310  cmd.param7 = req->mode; // MAV_MOUNT_MODE
311 
312  UAS_FCU(m_uas)->send_message_ignore_drop(cmd);
313 
314  mount_diag.set_setpoint(req->roll*0.01f, req->pitch*0.01f, req->yaw*0.01f, req->mode);
315  }
316 
317  bool mount_configure_cb(mavros_msgs::MountConfigure::Request &req,
318  mavros_msgs::MountConfigure::Response &res)
319  {
320  using mavlink::common::MAV_CMD;
321 
322  try {
323  auto client = nh.serviceClient<mavros_msgs::CommandLong>("cmd/command");
324 
325  mavros_msgs::CommandLong cmd{};
326 
327  cmd.request.broadcast = false;
328  cmd.request.command = enum_value(MAV_CMD::DO_MOUNT_CONFIGURE);
329  cmd.request.confirmation = false;
330  cmd.request.param1 = req.mode;
331  cmd.request.param2 = req.stabilize_roll;
332  cmd.request.param3 = req.stabilize_pitch;
333  cmd.request.param4 = req.stabilize_yaw;
334  cmd.request.param5 = req.roll_input;
335  cmd.request.param6 = req.pitch_input;
336  cmd.request.param7 = req.yaw_input;
337 
338  ROS_DEBUG_NAMED("mount", "MountConfigure: Request mode %u ", req.mode);
339  client.call(cmd);
340  res.success = cmd.response.success;
341  }
342  catch (ros::InvalidNameException &ex) {
343  ROS_ERROR_NAMED("mount", "MountConfigure: %s", ex.what());
344  }
345 
346  ROS_ERROR_COND_NAMED(!res.success, "mount", "MountConfigure: command plugin service call failed!");
347 
348  return res.success;
349  }
350 };
351 } // namespace extra_plugins
352 } // namespace mavros
353 
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::extra_plugins::MountStatusDiag::_error_detected
bool _error_detected
Definition: mount_control.cpp:155
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
ros::Publisher
mavros::extra_plugins::MountControlPlugin::negate_measured_roll
bool negate_measured_roll
Definition: mount_control.cpp:232
mavros::extra_plugins::MountStatusDiag::_setpoint_pitch_deg
float _setpoint_pitch_deg
Definition: mount_control.cpp:152
mavros::plugin::PluginBase::PluginBase
PluginBase()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
UAS_FCU
#define UAS_FCU(uasobjptr)
mavros::UAS
mavros::extra_plugins::MountControlPlugin::mount_orientation_pub
ros::Publisher mount_orientation_pub
Definition: mount_control.cpp:227
mavros::extra_plugins::MountStatusDiag::run
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: mount_control.cpp:81
diagnostic_updater::DiagnosticTask::DiagnosticTask
DiagnosticTask(const std::string name)
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
mutex
std::recursive_mutex mutex
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
mavros::extra_plugins::MountControlPlugin::negate_measured_yaw
bool negate_measured_yaw
Definition: mount_control.cpp:234
mavros::extra_plugins::MountControlPlugin::command_cb
void command_cb(const mavros_msgs::MountControl::ConstPtr &req)
Send mount control commands to vehicle.
Definition: mount_control.cpp:297
mavros::extra_plugins::MountControlPlugin::handle_mount_orientation
void handle_mount_orientation(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MOUNT_ORIENTATION &mo)
Publish the mount orientation.
Definition: mount_control.cpp:243
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
mavros::extra_plugins::MountStatusDiag::set_debounce_s
void set_debounce_s(double debounce_s)
Definition: mount_control.cpp:60
mavros::extra_plugins::MountStatusDiag
Mount diagnostic updater.
Definition: mount_control.cpp:37
ROS_ERROR_COND_NAMED
#define ROS_ERROR_COND_NAMED(cond, name,...)
mavros::extra_plugins::MountControlPlugin::nh
ros::NodeHandle nh
Definition: mount_control.cpp:224
mavros::UAS::get_tgt_component
uint8_t get_tgt_component()
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
mavros::extra_plugins::MountControlPlugin::command_sub
ros::Subscriber command_sub
Definition: mount_control.cpp:226
mavros::extra_plugins::MountControlPlugin::MountControlPlugin
MountControlPlugin()
Definition: mount_control.cpp:167
mavros::extra_plugins::MountStatusDiag::set_status
void set_status(float roll_deg, float pitch_deg, float yaw_deg, ros::Time timestamp)
Definition: mount_control.cpp:65
mavros::extra_plugins::MountControlPlugin
Mount Control plugin.
Definition: mount_control.cpp:165
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ServiceServer
diagnostic_updater::DiagnosticTask
mavros::extra_plugins::MountStatusDiag::_mode
uint8_t _mode
Definition: mount_control.cpp:156
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
tf::vectorEigenToMsg
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros::extra_plugins::MountStatusDiag::_error_started
ros::Time _error_started
Definition: mount_control.cpp:145
mavros_plugin.h
mavros::extra_plugins::MountStatusDiag::_err_threshold_deg
float _err_threshold_deg
Definition: mount_control.cpp:154
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
diagnostic_updater
to_string
std::string to_string(ADSB_ALTITUDE_TYPE e)
mavros::extra_plugins::MountStatusDiag::_setpoint_roll_deg
float _setpoint_roll_deg
Definition: mount_control.cpp:151
UAS_DIAG
#define UAS_DIAG(uasobjptr)
mode
std::string mode
mavros::extra_plugins::MountStatusDiag::_last_orientation_update
ros::Time _last_orientation_update
Definition: mount_control.cpp:146
ROS_WARN
#define ROS_WARN(...)
mavros::extra_plugins::MountStatusDiag::_debounce_s
double _debounce_s
Definition: mount_control.cpp:147
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mavros::extra_plugins::MountStatusDiag::_roll_deg
float _roll_deg
Definition: mount_control.cpp:148
mavros
mavros::extra_plugins::MountControlPlugin::mount_configure_cb
bool mount_configure_cb(mavros_msgs::MountConfigure::Request &req, mavros_msgs::MountConfigure::Response &res)
Definition: mount_control.cpp:317
mavros::extra_plugins::MountControlPlugin::get_subscriptions
Subscriptions get_subscriptions() override
Definition: mount_control.cpp:215
ros::Time
mavros::UAS::get_tgt_system
uint8_t get_tgt_system()
tf::quaternionEigenToMsg
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
mavros::extra_plugins::MountStatusDiag::_pitch_deg
float _pitch_deg
Definition: mount_control.cpp:149
mavros::extra_plugins::MountStatusDiag::MountStatusDiag
MountStatusDiag(const std::string &name)
Definition: mount_control.cpp:40
mavros::extra_plugins::MountControlPlugin::initialize
void initialize(UAS &uas_) override
Definition: mount_control.cpp:173
class_list_macros.hpp
mavros::extra_plugins::MountStatusDiag::set_setpoint
void set_setpoint(float roll_deg, float pitch_deg, float yaw_deg, uint8_t mode)
Definition: mount_control.cpp:73
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
disable_diag
bool disable_diag
mavros::extra_plugins::MountStatusDiag::_yaw_deg
float _yaw_deg
Definition: mount_control.cpp:150
ros::InvalidNameException
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mavros::extra_plugins::MountControlPlugin::mount_status_pub
ros::Publisher mount_status_pub
Definition: mount_control.cpp:228
diagnostic_updater::DiagnosticStatusWrapper
mavros::extra_plugins::MountStatusDiag::mutex
std::mutex mutex
Definition: mount_control.cpp:144
mavros::ftf::quaternion_from_rpy
Eigen::Quaterniond quaternion_from_rpy(const double roll, const double pitch, const double yaw)
mavros::extra_plugins::MountControlPlugin::negate_measured_pitch
bool negate_measured_pitch
Definition: mount_control.cpp:233
cmd
string cmd
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))
mavros::extra_plugins::MountControlPlugin::configure_srv
ros::ServiceServer configure_srv
Definition: mount_control.cpp:229
mavros::extra_plugins::MountControlPlugin::mount_diag
MountStatusDiag mount_diag
Definition: mount_control.cpp:231
ros::Duration
mavros::utils::enum_value
constexpr std::underlying_type< _T >::type enum_value(_T e)
mavros::extra_plugins::MountControlPlugin::mount_nh
ros::NodeHandle mount_nh
Definition: mount_control.cpp:225
mavros::extra_plugins::MountStatusDiag::set_err_threshold_deg
void set_err_threshold_deg(float threshold_deg)
Definition: mount_control.cpp:55
ros::NodeHandle
ros::Subscriber
mavros::extra_plugins::MountControlPlugin::handle_mount_status
void handle_mount_status(const mavlink::mavlink_message_t *, mavlink::ardupilotmega::msg::MOUNT_STATUS &ms)
Publish the mount status.
Definition: mount_control.cpp:271
ros::Time::now
static Time now()
mavros::extra_plugins::MountStatusDiag::_setpoint_yaw_deg
float _setpoint_yaw_deg
Definition: mount_control.cpp:153


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