Goby3  3.1.5
2024.05.14
udp_point_to_point.h
Go to the documentation of this file.
1 // Copyright 2019-2023:
2 // GobySoft, LLC (2013-)
3 // Community contributors (see AUTHORS file)
4 // File authors:
5 // Toby Schneider <toby@gobysoft.org>
6 //
7 //
8 // This file is part of the Goby Underwater Autonomy Project Libraries
9 // ("The Goby Libraries").
10 //
11 // The Goby Libraries are free software: you can redistribute them and/or modify
12 // them under the terms of the GNU Lesser General Public License as published by
13 // the Free Software Foundation, either version 2.1 of the License, or
14 // (at your option) any later version.
15 //
16 // The Goby Libraries are distributed in the hope that they will be useful,
17 // but WITHOUT ANY WARRANTY; without even the implied warranty of
18 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
19 // GNU Lesser General Public License for more details.
20 //
21 // You should have received a copy of the GNU Lesser General Public License
22 // along with Goby. If not, see <http://www.gnu.org/licenses/>.
23 
24 #ifndef GOBY_MIDDLEWARE_IO_UDP_POINT_TO_POINT_H
25 #define GOBY_MIDDLEWARE_IO_UDP_POINT_TO_POINT_H
26 
27 #include <iosfwd> // for size_t
28 #include <memory> // for shared_ptr, __sh...
29 #include <string> // for to_string
30 
31 #include <boost/asio/buffer.hpp> // for buffer
32 #include <boost/asio/ip/udp.hpp> // for udp, udp::endpoint
33 #include <boost/system/error_code.hpp> // for error_code
34 
35 #include "goby/middleware/io/detail/io_interface.h" // for PubSubLayer, Pub...
36 #include "goby/middleware/protobuf/io.pb.h" // for IOData
37 
38 #include "udp_one_to_many.h"
39 
40 namespace goby
41 {
42 namespace middleware
43 {
44 class Group;
45 }
46 } // namespace goby
47 namespace goby
48 {
49 namespace middleware
50 {
51 namespace protobuf
52 {
53 class UDPPointToPointConfig;
54 }
55 } // namespace middleware
56 } // namespace goby
57 
58 namespace goby
59 {
60 namespace middleware
61 {
62 namespace io
63 {
64 template <const goby::middleware::Group& line_in_group,
65  const goby::middleware::Group& line_out_group,
66  // by default publish all incoming traffic to interprocess for logging
67  PubSubLayer publish_layer = PubSubLayer::INTERPROCESS,
68  // but only subscribe on interthread for outgoing traffic
69  PubSubLayer subscribe_layer = PubSubLayer::INTERTHREAD,
70  template <class> class ThreadType = goby::middleware::SimpleThread,
71  bool use_indexed_groups = false>
73  : public UDPOneToManyThread<line_in_group, line_out_group, publish_layer, subscribe_layer,
74  goby::middleware::protobuf::UDPPointToPointConfig, ThreadType,
75  use_indexed_groups>
76 {
77  using Base = UDPOneToManyThread<line_in_group, line_out_group, publish_layer, subscribe_layer,
79  use_indexed_groups>;
80 
81  public:
85  int index = -1)
86  : Base(config, index, false)
87  {
88  boost::asio::ip::udp::resolver resolver(this->mutable_io());
89  remote_endpoint_ = *resolver.resolve(
90  {this->cfg().remote_address(), std::to_string(this->cfg().remote_port()),
91  boost::asio::ip::resolver_query_base::numeric_service});
92 
94  this->interthread().template publish<line_in_group>(ready);
95  }
96 
97  ~UDPPointToPointThread() override {}
98 
99  private:
101  void async_write(std::shared_ptr<const goby::middleware::protobuf::IOData> io_msg) override;
102 
103  private:
104  boost::asio::ip::udp::endpoint remote_endpoint_;
105 };
106 } // namespace io
107 } // namespace middleware
108 } // namespace goby
109 
110 template <const goby::middleware::Group& line_in_group,
111  const goby::middleware::Group& line_out_group,
112  goby::middleware::io::PubSubLayer publish_layer,
113  goby::middleware::io::PubSubLayer subscribe_layer, template <class> class ThreadType,
114  bool use_indexed_groups>
115 void goby::middleware::io::UDPPointToPointThread<line_in_group, line_out_group, publish_layer,
116  subscribe_layer, ThreadType, use_indexed_groups>::
117  async_write(std::shared_ptr<const goby::middleware::protobuf::IOData> io_msg)
118 {
119  this->mutable_socket().async_send_to(
120  boost::asio::buffer(io_msg->data()), remote_endpoint_,
121  [this, io_msg](const boost::system::error_code& ec, std::size_t bytes_transferred)
122  {
123  if (!ec && bytes_transferred > 0)
124  {
125  this->handle_write_success(bytes_transferred);
126  }
127  else
128  {
129  this->handle_write_error(ec);
130  }
131  });
132 }
133 
134 #endif
goby::middleware::io::UDPOneToManyThread
Definition: udp_one_to_many.h:65
io.pb.h
goby
The global namespace for the Goby project.
Definition: acomms_constants.h:33
goby::middleware::Thread< goby::middleware::protobuf::UDPPointToPointConfig, InterVehicleForwarder< InterProcessForwarder< InterThreadTransporter > > >::cfg
const goby::middleware::protobuf::UDPPointToPointConfig & cfg() const
Definition: thread.h:201
goby::middleware::io::detail::IOThread< line_in_group, line_out_group, publish_layer, subscribe_layer, goby::middleware::protobuf::UDPPointToPointConfig, boost::asio::ip::udp::socket, goby::middleware::SimpleThread, use_indexed_groups >::mutable_io
boost::asio::io_context & mutable_io()
Definition: io_interface.h:220
goby::acomms::abc::protobuf::config
extern ::google::protobuf::internal::ExtensionIdentifier< ::goby::acomms::protobuf::DriverConfig, ::google::protobuf::internal::MessageTypeTraits< ::goby::acomms::abc::protobuf::Config >, 11, false > config
Definition: abc_driver.pb.h:203
goby::middleware::Thread< goby::middleware::protobuf::UDPPointToPointConfig, InterVehicleForwarder< InterProcessForwarder< InterThreadTransporter > > >::index
int index() const
Definition: thread.h:145
goby::middleware::SimpleThread
Implements Thread for a three layer middleware setup ([ intervehicle [ interprocess [ interthread ] ]...
Definition: simple_thread.h:43
goby::middleware::io::PubSubLayer
PubSubLayer
Definition: io_transporters.h:38
goby::middleware::protobuf::IOData::data
const ::std::string & data() const
Definition: io.pb.h:2103
to_string
NLOHMANN_BASIC_JSON_TPL_DECLARATION std::string to_string(const NLOHMANN_BASIC_JSON_TPL &j)
user-defined to_string function for JSON values
Definition: json.hpp:24301
goby::middleware::protobuf::UDPPointToPointConfig
Definition: udp_config.pb.h:224
udp_one_to_many.h
goby::middleware::Group
Class for grouping publications in the Goby middleware. Analogous to "topics" in ROS,...
Definition: group.h:58
goby::middleware::io::UDPPointToPointThread::~UDPPointToPointThread
~UDPPointToPointThread() override
Definition: udp_point_to_point.h:97
goby::middleware::SimpleThread< goby::middleware::protobuf::UDPPointToPointConfig >::interthread
InterThreadTransporter & interthread()
Access the transporter on the interthread layer (this is the innermost transporter)
Definition: simple_thread.h:96
goby::middleware::protobuf::UDPPointToPointConfig::remote_address
const ::std::string & remote_address() const
Definition: udp_config.pb.h:546
io_interface.h
goby::middleware::io::PubSubLayer::INTERPROCESS
@ INTERPROCESS
goby::middleware::io::ThreadState::SUBSCRIPTIONS_COMPLETE
@ SUBSCRIPTIONS_COMPLETE
goby::middleware::io::UDPPointToPointThread::UDPPointToPointThread
UDPPointToPointThread(const goby::middleware::protobuf::UDPPointToPointConfig &config, int index=-1)
Constructs the thread.
Definition: udp_point_to_point.h:84
goby::middleware::io::PubSubLayer::INTERTHREAD
@ INTERTHREAD
goby::middleware::io::UDPPointToPointThread
Definition: udp_point_to_point.h:72