udp_board.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
37 #ifndef ROSFLIGHT_FIRMWARE_UDP_BOARD_H
38 #define ROSFLIGHT_FIRMWARE_UDP_BOARD_H
39 
40 #include <list>
41 #include <string>
42 
43 #include <boost/asio.hpp>
44 #include <boost/thread.hpp>
45 
46 #include "board.h"
47 #include "mavlink/mavlink.h"
48 
49 namespace rosflight_firmware
50 {
51 class UDPBoard : public Board
52 {
53 public:
54  UDPBoard(std::string bind_host = "localhost",
55  uint16_t bind_port = 14525,
56  std::string remote_host = "localhost",
57  uint16_t remote_port = 14520);
58  ~UDPBoard();
59 
60  void serial_init(uint32_t baud_rate, uint32_t dev) override;
61  void serial_write(const uint8_t* src, size_t len) override;
62  uint16_t serial_bytes_available(void) override;
63  uint8_t serial_read(void) override;
64  void serial_flush() override;
65 
66  void set_ports(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port);
67 
68 private:
69  struct Buffer
70  {
72  size_t len;
73  size_t pos;
74 
75  Buffer() : len(0), pos(0) {}
76 
77  Buffer(const uint8_t* src, size_t length) : len(length), pos(0)
78  {
79  assert(length <= MAVLINK_MAX_PACKET_LEN);
80  memcpy(data, src, length);
81  }
82 
83  const uint8_t* dpos() const { return data + pos; }
84  size_t nbytes() const { return len - pos; }
85  void add_byte(uint8_t byte) { data[len++] = byte; }
86  uint8_t consume_byte() { return data[pos++]; }
87  bool empty() const { return pos >= len; }
88  bool full() const { return len >= MAVLINK_MAX_PACKET_LEN; }
89  };
90 
91  typedef boost::lock_guard<boost::recursive_mutex> MutexLock;
92 
93  void async_read();
94  void async_read_end(const boost::system::error_code& error, size_t bytes_transferred);
95 
96  void async_write(bool check_write_state);
97  void async_write_end(const boost::system::error_code& error, size_t bytes_transferred);
98 
99  std::string bind_host_;
100  uint16_t bind_port_;
101 
102  std::string remote_host_;
103  uint16_t remote_port_;
104 
105  boost::thread io_thread_;
106  boost::recursive_mutex write_mutex_;
107  boost::recursive_mutex read_mutex_;
108 
109  boost::asio::io_service io_service_;
110 
111  boost::asio::ip::udp::socket socket_;
112  boost::asio::ip::udp::endpoint bind_endpoint_;
113  boost::asio::ip::udp::endpoint remote_endpoint_;
114 
116  std::list<Buffer*> read_queue_;
117 
118  std::list<Buffer*> write_queue_;
120 };
121 
122 } // namespace rosflight_firmware
123 
124 #endif // ROSFLIGHT_FIRMWARE_UDP_BOARD_H
void serial_flush() override
Definition: udp_board.cpp:99
boost::asio::ip::udp::socket socket_
Definition: udp_board.h:111
std::list< Buffer * > write_queue_
Definition: udp_board.h:118
static volatile bool error
Definition: drv_i2c.c:92
void serial_init(uint32_t baud_rate, uint32_t dev) override
Definition: udp_board.cpp:75
void serial_write(const uint8_t *src, size_t len) override
Definition: udp_board.cpp:101
UDPBoard(std::string bind_host="localhost", uint16_t bind_port=14525, std::string remote_host="localhost", uint16_t remote_port=14520)
Definition: udp_board.cpp:44
boost::asio::ip::udp::endpoint bind_endpoint_
Definition: udp_board.h:112
boost::asio::ip::udp::endpoint remote_endpoint_
Definition: udp_board.h:113
void async_write(bool check_write_state)
Definition: udp_board.cpp:158
void async_read_end(const boost::system::error_code &error, size_t bytes_transferred)
Definition: udp_board.cpp:148
boost::lock_guard< boost::recursive_mutex > MutexLock
Definition: udp_board.h:91
boost::recursive_mutex write_mutex_
Definition: udp_board.h:106
uint16_t serial_bytes_available(void) override
Definition: udp_board.cpp:113
const uint8_t * dpos() const
Definition: udp_board.h:83
void set_ports(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port)
Definition: udp_board.cpp:67
uint8_t serial_read(void) override
Definition: udp_board.cpp:119
boost::recursive_mutex read_mutex_
Definition: udp_board.h:107
uint8_t data[MAVLINK_MAX_PACKET_LEN]
Definition: udp_board.h:71
boost::asio::io_service io_service_
Definition: udp_board.h:109
std::list< Buffer * > read_queue_
Definition: udp_board.h:116
Buffer(const uint8_t *src, size_t length)
Definition: udp_board.h:77
void async_write_end(const boost::system::error_code &error, size_t bytes_transferred)
Definition: udp_board.cpp:174
uint8_t read_buffer_[MAVLINK_MAX_PACKET_LEN]
Definition: udp_board.h:115


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:49