Go to the documentation of this file.
31 auto rmsg = boost::make_shared<mavros_msgs::Mavlink>();
40 mavlink::mavlink_message_t mmsg;
43 gcs_link->send_message_ignore_drop(&mmsg);
48 int main(
int argc,
char *argv[])
57 priv_nh.
param<std::string>(
"gcs_url", gcs_url,
"udp://@");
73 .unreliable().maxDatagramSize(1024)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void set_connection_status(bool connected)
std::shared_ptr< MAVConnInterface const > ConstPtr
bool convert(const mavlink_message_t &mmsg, mavros_msgs::Mavlink &rmsg, uint8_t framing_status=mavros_msgs::Mavlink::FRAMING_OK)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
int main(int argc, char *argv[])
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())
ros::Publisher mavlink_pub
void set_mavconn(const mavconn::MAVConnInterface::Ptr &link)
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())
static constexpr auto MAV_COMP_ID_UDP_BRIDGE
std::shared_ptr< MAVConnInterface > Ptr
void mavlink_pub_cb(const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
T param(const std::string ¶m_name, const T &default_val) const
ros::Subscriber mavlink_sub
MAVConnInterface::Ptr gcs_link
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void mavlink_sub_cb(const mavros_msgs::Mavlink::ConstPtr &rmsg)
constexpr std::underlying_type< _T >::type enum_value(_T e)
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03