24#ifndef GOBY_MIDDLEWARE_IO_MAVLINK_UDP_H
25#define GOBY_MIDDLEWARE_IO_MAVLINK_UDP_H
29#include <boost/asio/buffer.hpp>
30#include <boost/asio/ip/udp.hpp>
31#include <boost/system/error_code.hpp>
50class UDPPointToPointConfig;
63 PubSubLayer subscribe_layer,
template <
class>
class ThreadType>
65 IOThreadMAVLink<line_in_group, line_out_group, publish_layer, subscribe_layer,
67 subscribe_layer, ThreadType>,
79 subscribe_layer, ThreadType>
91 void async_read()
override;
94 boost::asio::ip::udp::endpoint sender_endpoint_;
105 subscribe_layer, ThreadType>::async_read()
107 this->mutable_socket().async_receive_from(
108 boost::asio::buffer(this->buffer()), sender_endpoint_,
109 [
this](
const boost::system::error_code& ec, std::size_t bytes_transferred) {
110 if (!ec && bytes_transferred > 0)
112 this->try_parse(bytes_transferred);
117 this->handle_read_error(ec);
Class for grouping publications in the Goby middleware. Analogous to "topics" in ROS,...
Implements Thread for a three layer middleware setup ([ intervehicle [ interprocess [ interthread ] ]...
Reads/Writes MAVLink message packages from/to udp socket.
UDPThreadMAVLink(const goby::middleware::protobuf::UDPPointToPointConfig &config)
The global namespace for the Goby project.