mavros.cpp
Go to the documentation of this file.
1 
6 /*
7  * Copyright 2013,2014,2015,2016 Vladimir Ermakov.
8  *
9  * This file is part of the mavros package and subject to the license terms
10  * in the top-level LICENSE file of the mavros repository.
11  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
12  */
13 
14 #include <ros/console.h>
15 #include <mavros/mavros.h>
16 #include <mavros/utils.h>
17 #include <fnmatch.h>
18 
19 // MAVLINK_VERSION string
20 #include <mavlink/config.h>
21 #include <mavconn/mavlink_dialect.h>
22 
23 using namespace mavros;
25 using mavconn::Framing;
26 using mavlink::mavlink_message_t;
27 using plugin::PluginBase;
28 using utils::enum_value;
29 
30 
32  mavlink_nh("mavlink"), // allow to namespace it
33  fcu_link_diag("FCU connection"),
34  gcs_link_diag("GCS bridge"),
35  plugin_loader("mavros", "mavros::plugin::PluginBase"),
36  last_message_received_from_gcs(0),
37  plugin_subscriptions{}
38 {
39  std::string fcu_url, gcs_url;
40  std::string fcu_protocol;
41  int system_id, component_id;
42  int tgt_system_id, tgt_component_id;
43  bool px4_usb_quirk;
44  double conn_timeout_d;
45  ros::V_string plugin_blacklist{}, plugin_whitelist{};
46  MAVConnInterface::Ptr fcu_link;
47 
48  ros::NodeHandle nh("~");
49 
50  nh.param<std::string>("fcu_url", fcu_url, "serial:///dev/ttyACM0");
51  nh.param<std::string>("gcs_url", gcs_url, "udp://@");
52  nh.param<bool>("gcs_quiet_mode", gcs_quiet_mode, false);
53  nh.param("conn/timeout", conn_timeout_d, 30.0);
54 
55  nh.param<std::string>("fcu_protocol", fcu_protocol, "v2.0");
56  nh.param("system_id", system_id, 1);
57  nh.param<int>("component_id", component_id, mavconn::MAV_COMP_ID_UDP_BRIDGE);
58  nh.param("target_system_id", tgt_system_id, 1);
59  nh.param("target_component_id", tgt_component_id, 1);
60  nh.param("startup_px4_usb_quirk", px4_usb_quirk, false);
61  nh.getParam("plugin_blacklist", plugin_blacklist);
62  nh.getParam("plugin_whitelist", plugin_whitelist);
63 
64  conn_timeout = ros::Duration(conn_timeout_d);
65 
66  // Now we use FCU URL as a hardware Id
67  UAS_DIAG(&mav_uas).setHardwareID(fcu_url);
68 
69  ROS_INFO_STREAM("FCU URL: " << fcu_url);
70  try {
71  fcu_link = MAVConnInterface::open_url(fcu_url, system_id, component_id);
72  // may be overridden by URL
73  system_id = fcu_link->get_system_id();
74  component_id = fcu_link->get_component_id();
75 
76  fcu_link_diag.set_mavconn(fcu_link);
78  }
79  catch (mavconn::DeviceError &ex) {
80  ROS_FATAL("FCU: %s", ex.what());
81  ros::shutdown();
82  return;
83  }
84 
85  if (fcu_protocol == "v1.0") {
86  fcu_link->set_protocol_version(mavconn::Protocol::V10);
87  }
88  else if (fcu_protocol == "v2.0") {
89  fcu_link->set_protocol_version(mavconn::Protocol::V20);
90  }
91  //else if (fcu_protocol == "auto") { // XXX TODO
92  // fcu_link->set_protocol_version(mavconn::Protocol::V20);
93  //}
94  else {
95  ROS_WARN("Unknown FCU protocol: \"%s\", should be: \"v1.0\" or \"v2.0\". Used default v1.0.", fcu_protocol.c_str());
96  fcu_link->set_protocol_version(mavconn::Protocol::V10);
97  }
98 
99  if (gcs_url != "") {
100  ROS_INFO_STREAM("GCS URL: " << gcs_url);
101  try {
102  gcs_link = MAVConnInterface::open_url(gcs_url, system_id, component_id);
103 
107  }
108  catch (mavconn::DeviceError &ex) {
109  ROS_FATAL("GCS: %s", ex.what());
110  ros::shutdown();
111  return;
112  }
113  }
114  else
115  ROS_INFO("GCS bridge disabled");
116 
117  // ROS mavlink bridge
118  mavlink_pub = mavlink_nh.advertise<mavros_msgs::Mavlink>("from", 100);
121  .unreliable().maxDatagramSize(1024)
122  .reliable());
123 
124  // setup UAS and diag
125  mav_uas.set_tgt(tgt_system_id, tgt_component_id);
126  UAS_FCU(&mav_uas) = fcu_link;
127 
129  mav_uas.add_connection_change_handler(std::bind(&MavRos::log_connect_change, this, std::placeholders::_1));
130 
131  // prepare plugin lists
132  // issue #257 2: assume that all plugins blacklisted
133  if (plugin_blacklist.empty() and !plugin_whitelist.empty())
134  plugin_blacklist.emplace_back("*");
135 
136  for (auto &name : plugin_loader.getDeclaredClasses())
137  add_plugin(name, plugin_blacklist, plugin_whitelist);
138 
139  // connect FCU link
140 
141  // XXX TODO: move workers to ROS Spinner, let mavconn threads to do only IO
142  fcu_link->message_received_cb = [this](const mavlink_message_t *msg, const Framing framing) {
143  mavlink_pub_cb(msg, framing);
144  plugin_route_cb(msg, framing);
145 
146  if (gcs_link) {
147  if (this->gcs_quiet_mode && msg->msgid != mavlink::common::msg::HEARTBEAT::MSG_ID &&
148  (ros::Time::now() - this->last_message_received_from_gcs > this->conn_timeout)) {
149  return;
150  }
151 
152  gcs_link->send_message_ignore_drop(msg);
153  }
154  };
155 
156  fcu_link->port_closed_cb = []() {
157  ROS_ERROR("FCU connection closed, mavros will be terminated.");
159  };
160 
161  if (gcs_link) {
162  // setup GCS link bridge
163  gcs_link->message_received_cb = [this, fcu_link](const mavlink_message_t *msg, const Framing framing) {
165  fcu_link->send_message_ignore_drop(msg);
166  };
167 
169  }
170 
171  if (px4_usb_quirk)
173 
174  std::stringstream ss;
176  ss << " " << s;
177 
178  ROS_INFO("Built-in SIMD instructions: %s", Eigen::SimdInstructionSetsInUse());
179  ROS_INFO("Built-in MAVLink package version: %s", MAVLINK_VERSION);
180  ROS_INFO("Known MAVLink dialects:%s", ss.str().c_str());
181  ROS_INFO("MAVROS started. MY ID %u.%u, TARGET ID %u.%u",
182  system_id, component_id,
183  tgt_system_id, tgt_component_id);
184 }
185 
187 {
188  ros::AsyncSpinner spinner(4 /* threads */);
189 
190  auto diag_timer = mavlink_nh.createTimer(
191  ros::Duration(0.5),
192  [&](const ros::TimerEvent &) {
193  UAS_DIAG(&mav_uas).update();
194 
195  if (gcs_link)
197  });
198  diag_timer.start();
199 
200  spinner.start();
202 
203  ROS_INFO("Stopping mavros...");
204  spinner.stop();
205 }
206 
207 void MavRos::mavlink_pub_cb(const mavlink_message_t *mmsg, Framing framing)
208 {
209  auto rmsg = boost::make_shared<mavros_msgs::Mavlink>();
210 
211  if (mavlink_pub.getNumSubscribers() == 0)
212  return;
213 
214  rmsg->header.stamp = ros::Time::now();
215  mavros_msgs::mavlink::convert(*mmsg, *rmsg, enum_value(framing));
216  mavlink_pub.publish(rmsg);
217 }
218 
220 {
221  mavlink_message_t mmsg;
222 
223  if (mavros_msgs::mavlink::convert(*rmsg, mmsg))
224  UAS_FCU(&mav_uas)->send_message_ignore_drop(&mmsg);
225  else
226  ROS_ERROR("Drop mavlink packet: convert error.");
227 }
228 
229 void MavRos::plugin_route_cb(const mavlink_message_t *mmsg, const Framing framing)
230 {
231  auto it = plugin_subscriptions.find(mmsg->msgid);
232  if (it == plugin_subscriptions.end())
233  return;
234 
235  for (auto &info : it->second)
236  std::get<3>(info)(mmsg, framing);
237 }
238 
239 static bool pattern_match(std::string &pattern, std::string &pl_name)
240 {
241  int cmp = fnmatch(pattern.c_str(), pl_name.c_str(), FNM_CASEFOLD);
242  if (cmp == 0)
243  return true;
244  else if (cmp != FNM_NOMATCH) {
245  // never see that, i think that it is fatal error.
246  ROS_FATAL("Plugin list check error! fnmatch('%s', '%s', FNM_CASEFOLD) -> %d",
247  pattern.c_str(), pl_name.c_str(), cmp);
248  ros::shutdown();
249  }
250 
251  return false;
252 }
253 
266 static bool is_blacklisted(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
267 {
268  for (auto &bl_pattern : blacklist) {
269  if (pattern_match(bl_pattern, pl_name)) {
270  for (auto &wl_pattern : whitelist) {
271  if (pattern_match(wl_pattern, pl_name))
272  return false;
273  }
274 
275  return true;
276  }
277  }
278 
279  return false;
280 }
281 
282 inline bool is_mavlink_message_t(const size_t rt)
283 {
284  static const auto h = typeid(mavlink_message_t).hash_code();
285  return h == rt;
286 }
287 
291 void MavRos::add_plugin(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
292 {
293  if (is_blacklisted(pl_name, blacklist, whitelist)) {
294  ROS_INFO_STREAM("Plugin " << pl_name << " blacklisted");
295  return;
296  }
297 
298  try {
299  auto plugin = plugin_loader.createInstance(pl_name);
300 
301  ROS_INFO_STREAM("Plugin " << pl_name << " loaded");
302 
303  for (auto &info : plugin->get_subscriptions()) {
304  auto msgid = std::get<0>(info);
305  auto msgname = std::get<1>(info);
306  auto type_hash_ = std::get<2>(info);
307 
308  std::string log_msgname;
309 
310  if (is_mavlink_message_t(type_hash_))
311  log_msgname = utils::format("MSG-ID (%u) <%zu>", msgid, type_hash_);
312  else
313  log_msgname = utils::format("%s (%u) <%zu>", msgname, msgid, type_hash_);
314 
315  ROS_DEBUG_STREAM("Route " << log_msgname << " to " << pl_name);
316 
317  auto it = plugin_subscriptions.find(msgid);
318  if (it == plugin_subscriptions.end()) {
319  // new entry
320 
321  ROS_DEBUG_STREAM(log_msgname << " - new element");
322  plugin_subscriptions[msgid] = PluginBase::Subscriptions{{info}};
323  }
324  else {
325  // existing: check handler message type
326 
327  bool append_allowed = is_mavlink_message_t(type_hash_);
328  if (!append_allowed) {
329  append_allowed = true;
330  for (auto &e : it->second) {
331  auto t2 = std::get<2>(e);
332  if (!is_mavlink_message_t(t2) && t2 != type_hash_) {
333  ROS_ERROR_STREAM(log_msgname << " routed to different message type (hash: " << t2 << ")");
334  append_allowed = false;
335  }
336  }
337  }
338 
339  if (append_allowed) {
340  ROS_DEBUG_STREAM(log_msgname << " - emplace");
341  it->second.emplace_back(info);
342  }
343  else
344  ROS_ERROR_STREAM(log_msgname << " handler dropped because this ID are used for another message type");
345  }
346  }
347 
348  plugin->initialize(mav_uas);
349  loaded_plugins.push_back(plugin);
350 
351  ROS_INFO_STREAM("Plugin " << pl_name << " initialized");
352  } catch (pluginlib::PluginlibException &ex) {
353  ROS_ERROR_STREAM("Plugin " << pl_name << " load exception: " << ex.what());
354  }
355 }
356 
358 {
359  /* sample code from QGC */
360  const uint8_t init[] = {0x0d, 0x0d, 0x0d, 0};
361  const uint8_t nsh[] = "sh /etc/init.d/rc.usb\n";
362 
363  ROS_INFO("Autostarting mavlink via USB on PX4");
364  UAS_FCU(&mav_uas)->send_bytes(init, 3);
365  UAS_FCU(&mav_uas)->send_bytes(nsh, sizeof(nsh) - 1);
366  UAS_FCU(&mav_uas)->send_bytes(init, 4); /* NOTE in original init[3] */
367 }
368 
369 void MavRos::log_connect_change(bool connected)
370 {
372 
373  /* note: sys_status plugin required */
374  if (connected)
375  ROS_INFO("CON: Got HEARTBEAT, connected. FCU: %s", ap.c_str());
376  else
377  ROS_WARN("CON: Lost connection, HEARTBEAT timed out.");
378 }
msg
UAS mav_uas
UAS object passed to all plugins.
Definition: mavros.h:64
MAVROS Plugin base class.
Definition: mavros_plugin.h:37
static bool pattern_match(std::string &pattern, std::string &pl_name)
Definition: mavros.cpp:239
void add_plugin(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
load plugin
Definition: mavros.cpp:291
std::shared_ptr< MAVConnInterface const > ConstPtr
#define ROS_FATAL(...)
h
std::string format(const std::string &fmt, Args...args)
void publish(const boost::shared_ptr< M > &message) const
MAV_AUTOPILOT get_autopilot()
Returns autopilot type.
Definition: mavros_uas.h:127
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setHardwareID(const std::string &hwid)
diagnostic_updater::Updater gcs_diag_updater
Definition: mavros.h:53
MavRos node implementation class.
void log_connect_change(bool connected)
Definition: mavros.cpp:369
bool gcs_quiet_mode
Definition: mavros.h:46
void start()
void add(const std::string &name, TaskFunction f)
ros::Subscriber mavlink_sub
Definition: mavros.h:51
#define UAS_DIAG(uasobjptr)
helper accessor to diagnostic updater
Definition: mavros_uas.h:47
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
std::unordered_map< mavlink::msgid_t, plugin::PluginBase::Subscriptions > plugin_subscriptions
FCU link -> router -> plugin handler.
Definition: mavros.h:61
#define ROS_WARN(...)
void spinner()
void mavlink_sub_cb(const mavros_msgs::Mavlink::ConstPtr &rmsg)
ros -> fcu link
Definition: mavros.cpp:219
void set_connection_status(bool connected)
Definition: mavlink_diag.h:34
void mavlink_pub_cb(const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
fcu link -> ros
Definition: mavros.cpp:207
std::vector< std::string > V_string
ros::Publisher mavlink_pub
Definition: mavros.h:50
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
mavconn::MAVConnInterface::Ptr gcs_link
Definition: mavros.h:45
std::vector< std::string > getDeclaredClasses()
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
Definition: uas_data.cpp:81
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
Definition: mavros_uas.h:41
ros::Duration conn_timeout
Definition: mavros.h:48
bool is_mavlink_message_t(const size_t rt)
Definition: mavros.cpp:282
void set_tgt(uint8_t sys, uint8_t comp)
Definition: mavros_uas.h:166
std::string to_string(timesync_mode e)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
MAVConnInterface(const MAVConnInterface &)=delete
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void plugin_route_cb(const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
message router
Definition: mavros.cpp:229
#define ROS_DEBUG_STREAM(args)
ros::Time last_message_received_from_gcs
Definition: mavros.h:47
static bool is_blacklisted(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
Checks that plugin blacklisted.
Definition: mavros.cpp:266
static std::vector< std::string > get_known_dialects()
static Ptr open_url(std::string url, uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE)
ROSCPP_DECL void requestShutdown()
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
void startup_px4_usb_quirk()
start mavlink app on USB
Definition: mavros.cpp:357
bool getParam(const std::string &key, std::string &s) const
pluginlib::ClassLoader< plugin::PluginBase > plugin_loader
Definition: mavros.h:57
std::vector< plugin::PluginBase::Ptr > loaded_plugins
Definition: mavros.h:58
static Time now()
MavlinkDiag gcs_link_diag
Definition: mavros.h:55
ROSCPP_DECL void shutdown()
#define ROS_ERROR_STREAM(args)
MavlinkDiag fcu_link_diag
Definition: mavros.h:54
#define ROS_ERROR(...)
ros::NodeHandle mavlink_nh
Definition: mavros.h:43
void set_mavconn(const mavconn::MAVConnInterface::Ptr &link)
Definition: mavlink_diag.h:30
void spin()
Definition: mavros.cpp:186
ROSCPP_DECL void waitForShutdown()
#define MAVLINK_VERSION
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
std::shared_ptr< MAVConnInterface > Ptr


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11