gcs_bridge.cpp
Go to the documentation of this file.
1 
6 /*
7  * Copyright 2014,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/ros.h>
15 #include <ros/console.h>
16 
17 #include <mavros/utils.h>
18 #include <mavros/mavlink_diag.h>
19 #include <mavconn/interface.h>
20 
21 using namespace mavros;
22 using namespace mavconn;
23 
27 
28 
29 void mavlink_pub_cb(const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
30 {
31  auto rmsg = boost::make_shared<mavros_msgs::Mavlink>();
32 
33  rmsg->header.stamp = ros::Time::now();
35  mavlink_pub.publish(rmsg);
36 }
37 
39 {
40  mavlink::mavlink_message_t mmsg;
41 
42  if (mavros_msgs::mavlink::convert(*rmsg, mmsg))
43  gcs_link->send_message_ignore_drop(&mmsg);
44  else
45  ROS_ERROR("Packet drop: convert error.");
46 }
47 
48 int main(int argc, char *argv[])
49 {
50  ros::init(argc, argv, "gcs_bridge");
51  ros::NodeHandle priv_nh("~");
52  ros::NodeHandle mavlink_nh("mavlink");
54  mavros::MavlinkDiag gcs_link_diag("GCS bridge");
55 
56  std::string gcs_url;
57  priv_nh.param<std::string>("gcs_url", gcs_url, "udp://@");
58 
59  try {
60  mavlink_pub = mavlink_nh.advertise<mavros_msgs::Mavlink>("to", 10);
62  gcs_link_diag.set_mavconn(gcs_link);
63  gcs_link_diag.set_connection_status(true);
64  }
65  catch (mavconn::DeviceError &ex) {
66  ROS_FATAL("GCS: %s", ex.what());
67  return 1;
68  }
69 
70  // prefer UDPROS, but allow TCPROS too
71  mavlink_sub = mavlink_nh.subscribe("from", 10, mavlink_sub_cb,
73  .unreliable().maxDatagramSize(1024)
74  .reliable());
75 
76  // setup updater
77  updater.setHardwareID(gcs_url);
78  updater.add(gcs_link_diag);
79 
80  // updater spinner
81  auto diag_timer = priv_nh.createTimer(ros::Duration(0.5),
82  [&](const ros::TimerEvent &evt) {
83  updater.update();
84  });
85  diag_timer.start();
86 
87  ros::spin();
88  return 0;
89 }
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
mavros::MavlinkDiag::set_connection_status
void set_connection_status(bool connected)
Definition: mavlink_diag.h:34
mavconn::DeviceError
diagnostic_updater::Updater
ros::TransportHints
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
main
int main(int argc, char *argv[])
Definition: gcs_bridge.cpp:48
console.h
utils.h
some useful utils
open_url
static Ptr open_url(std::string url, uint8_t system_id=1, uint8_t component_id=MAV_COMP_ID_UDP_BRIDGE, const ReceivedCb &cb_handle_message=ReceivedCb(), const ClosedCb &cb_handle_closed_port=ClosedCb())
updater
updater
mavconn::Framing
Framing
mavros::MavlinkDiag
Definition: mavlink_diag.h:23
mavlink_pub
ros::Publisher mavlink_pub
Definition: gcs_bridge.cpp:24
mavros::MavlinkDiag::set_mavconn
void set_mavconn(const mavconn::MAVConnInterface::Ptr &link)
Definition: mavlink_diag.h:30
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())
MAV_COMP_ID_UDP_BRIDGE
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
ros::TimerEvent
mavconn::MAVConnInterface::Ptr
std::shared_ptr< MAVConnInterface > Ptr
ROS_FATAL
#define ROS_FATAL(...)
mavros
Definition: frame_tf.h:34
ROS_ERROR
#define ROS_ERROR(...)
mavconn
mavlink_pub_cb
void mavlink_pub_cb(const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
Definition: gcs_bridge.cpp:29
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
mavlink_sub
ros::Subscriber mavlink_sub
Definition: gcs_bridge.cpp:25
ros::Timer::start
void start()
gcs_link
MAVConnInterface::Ptr gcs_link
Definition: gcs_bridge.cpp:26
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
interface.h
ros::Duration
mavlink_sub_cb
void mavlink_sub_cb(const mavros_msgs::Mavlink::ConstPtr &rmsg)
Definition: gcs_bridge.cpp:38
mavros::utils::enum_value
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03