20 #include <mavlink/config.h> 21 #include <mavconn/mavlink_dialect.h> 26 using mavlink::mavlink_message_t;
32 mavlink_nh(
"mavlink"),
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{}
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;
44 double conn_timeout_d;
50 nh.
param<std::string>(
"fcu_url", fcu_url,
"serial:///dev/ttyACM0");
51 nh.
param<std::string>(
"gcs_url", gcs_url,
"udp://@");
53 nh.
param(
"conn/timeout", conn_timeout_d, 30.0);
55 nh.
param<std::string>(
"fcu_protocol", fcu_protocol,
"v2.0");
56 nh.
param(
"system_id", system_id, 1);
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);
73 system_id = fcu_link->get_system_id();
74 component_id = fcu_link->get_component_id();
85 if (fcu_protocol ==
"v1.0") {
88 else if (fcu_protocol ==
"v2.0") {
95 ROS_WARN(
"Unknown FCU protocol: \"%s\", should be: \"v1.0\" or \"v2.0\". Used default v1.0.", fcu_protocol.c_str());
121 .unreliable().maxDatagramSize(1024)
133 if (plugin_blacklist.empty() and !plugin_whitelist.empty())
134 plugin_blacklist.emplace_back(
"*");
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)) {
152 gcs_link->send_message_ignore_drop(msg);
156 fcu_link->port_closed_cb = []() {
157 ROS_ERROR(
"FCU connection closed, mavros will be terminated.");
165 fcu_link->send_message_ignore_drop(msg);
174 std::stringstream ss;
178 ROS_INFO(
"Built-in SIMD instructions: %s", Eigen::SimdInstructionSetsInUse());
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);
209 auto rmsg = boost::make_shared<mavros_msgs::Mavlink>();
226 ROS_ERROR(
"Drop mavlink packet: convert error.");
235 for (
auto &info : it->second)
236 std::get<3>(info)(mmsg, framing);
241 int cmp = fnmatch(pattern.c_str(), pl_name.c_str(), FNM_CASEFOLD);
244 else if (cmp != FNM_NOMATCH) {
246 ROS_FATAL(
"Plugin list check error! fnmatch('%s', '%s', FNM_CASEFOLD) -> %d",
247 pattern.c_str(), pl_name.c_str(), cmp);
268 for (
auto &bl_pattern : blacklist) {
270 for (
auto &wl_pattern : whitelist) {
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);
308 std::string log_msgname;
311 log_msgname =
utils::format(
"MSG-ID (%u) <%zu>", msgid, type_hash_);
313 log_msgname =
utils::format(
"%s (%u) <%zu>", msgname, msgid, type_hash_);
328 if (!append_allowed) {
329 append_allowed =
true;
330 for (
auto &
e : it->second) {
331 auto t2 = std::get<2>(
e);
333 ROS_ERROR_STREAM(log_msgname <<
" routed to different message type (hash: " <<
t2 <<
")");
334 append_allowed =
false;
339 if (append_allowed) {
341 it->second.emplace_back(info);
344 ROS_ERROR_STREAM(log_msgname <<
" handler dropped because this ID are used for another message type");
360 const uint8_t init[] = {0x0d, 0x0d, 0x0d, 0};
361 const uint8_t nsh[] =
"sh /etc/init.d/rc.usb\n";
363 ROS_INFO(
"Autostarting mavlink via USB on PX4");
375 ROS_INFO(
"CON: Got HEARTBEAT, connected. FCU: %s", ap.c_str());
377 ROS_WARN(
"CON: Lost connection, HEARTBEAT timed out.");
UAS mav_uas
UAS object passed to all plugins.
MAVROS Plugin base class.
static bool pattern_match(std::string &pattern, std::string &pl_name)
void add_plugin(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
load plugin
std::shared_ptr< MAVConnInterface const > ConstPtr
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.
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
bool convert(const mavros_msgs::Mavlink &rmsg, mavlink_message_t &mmsg)
MavRos node implementation class.
void log_connect_change(bool connected)
void add(const std::string &name, TaskFunction f)
ros::Subscriber mavlink_sub
#define UAS_DIAG(uasobjptr)
helper accessor to diagnostic updater
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
std::unordered_map< mavlink::msgid_t, plugin::PluginBase::Subscriptions > plugin_subscriptions
FCU link -> router -> plugin handler.
void mavlink_sub_cb(const mavros_msgs::Mavlink::ConstPtr &rmsg)
ros -> fcu link
void set_connection_status(bool connected)
void mavlink_pub_cb(const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
fcu link -> ros
std::vector< std::string > V_string
ros::Publisher mavlink_pub
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
mavconn::MAVConnInterface::Ptr gcs_link
std::vector< std::string > getDeclaredClasses()
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
ros::Duration conn_timeout
bool is_mavlink_message_t(const size_t rt)
void set_tgt(uint8_t sys, uint8_t comp)
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
#define ROS_DEBUG_STREAM(args)
ros::Time last_message_received_from_gcs
static bool is_blacklisted(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
Checks that plugin blacklisted.
struct __mavlink_message mavlink_message_t
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
bool getParam(const std::string &key, std::string &s) const
pluginlib::ClassLoader< plugin::PluginBase > plugin_loader
std::vector< plugin::PluginBase::Ptr > loaded_plugins
MavlinkDiag gcs_link_diag
ROSCPP_DECL void shutdown()
#define ROS_ERROR_STREAM(args)
MavlinkDiag fcu_link_diag
ros::NodeHandle mavlink_nh
void set_mavconn(const mavconn::MAVConnInterface::Ptr &link)
ROSCPP_DECL void waitForShutdown()
constexpr std::underlying_type< _T >::type enum_value(_T e)
std::shared_ptr< MAVConnInterface > Ptr