include/serial.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, 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 MAVROSFLIGHT_MAVLINK_COMM_H
38 #define MAVROSFLIGHT_MAVLINK_COMM_H
39 
40 #include <boost/asio.hpp>
41 #include <boost/thread.hpp>
42 #include <boost/function.hpp>
43 
44 #include <list>
45 #include <string>
46 #include <vector>
47 
48 #include <stdint.h>
49 
50 #define BUFFER_SIZE 2048
51 
53 {
54 public:
55  virtual void handle_bytes(const uint8_t* bytes, uint8_t len) = 0;
56 };
57 
58 
59 class Serial
60 {
61 public:
62 
68  Serial(std::__cxx11::string port, int baud_rate);
69 
73  ~Serial();
74 
78  void open();
79 
83  void close();
84 
90  void write(const uint8_t *buffer, uint8_t len);
91 
96  void register_listener(SerialListener * const listener);
97 
98  boost::asio::io_service io_service_;
99 
100 private:
101 
102  //===========================================================================
103  // definitions
104  //===========================================================================
105 
109  struct WriteBuffer
110  {
111  uint8_t data[BUFFER_SIZE];
112  size_t len;
113  size_t pos;
114 
115  WriteBuffer() : len(0), pos(0) {}
116 
117  WriteBuffer(const uint8_t * buf, uint16_t len) : len(len), pos(0)
118  {
119  assert(len <= BUFFER_SIZE);
120  memcpy(data, buf, len);
121  }
122 
123  const uint8_t * dpos() const { return data + pos; }
124 
125  size_t nbytes() const { return len - pos; }
126  };
127 
132 
133  boost::asio::serial_port serial_port_;
134  std::string port_;
136 
140  typedef boost::lock_guard<boost::recursive_mutex> mutex_lock;
141 
142  //===========================================================================
143  // methods
144  //===========================================================================
145 
149  void async_read();
150 
156  void async_read_end(const boost::system::error_code& error, size_t bytes_transferred);
157 
162  void async_write(bool check_write_state);
163 
169  void async_write_end(const boost::system::error_code& error, size_t bytes_transferred);
170 
171  //===========================================================================
172  // member variables
173  //===========================================================================
174 
175  boost::thread io_thread_;
176  boost::recursive_mutex mutex_;
177 
178  uint8_t sysid_;
179  uint8_t compid_;
180 
181  uint8_t read_buf_raw_[BUFFER_SIZE];
182 
183  std::list<WriteBuffer*> write_queue_;
185 };
186 
187 class SerialException : public std::exception
188 {
189 public:
190  explicit SerialException(const char * const description)
191  {
192  init(description);
193  }
194 
195  explicit SerialException(const std::string &description)
196  {
197  init(description.c_str());
198  }
199 
200  explicit SerialException(const boost::system::system_error &err)
201  {
202  init(err.what());
203  }
204 
205  SerialException(const SerialException &other) : what_(other.what_) {}
206 
207  ~SerialException() throw() {}
208 
209  virtual const char* what() const throw()
210  {
211  return what_.c_str();
212  }
213 
214 private:
215  std::string what_;
216 
217  void init(const char * const description)
218  {
219  std::ostringstream ss;
220  ss << "Serial Error: " << description;
221  what_ = ss.str();
222  }
223 };
224 
225 #endif
boost::asio::serial_port serial_port_
boost serial port object
SerialException(const SerialException &other)
boost::asio::io_service io_service_
boost io service provider
WriteBuffer(const uint8_t *buf, uint16_t len)
bool init(test_data_t &t)
bool write_in_progress_
flag for whether async_write is already running
int baud_rate_
SerialException(const boost::system::system_error &err)
Struct for buffering the contents of a mavlink message.
virtual const char * what() const
SerialException(const char *const description)
virtual void handle_bytes(const uint8_t *bytes, uint8_t len)=0
std::string what_
boost::recursive_mutex mutex_
mutex for threadsafe operation
std::string port_
void init(const char *const description)
uint8_t sysid_
boost::lock_guard< boost::recursive_mutex > mutex_lock
Convenience typedef for mutex lock.
uint8_t compid_
USBInterfaceDescriptor data
NMI_API sint8 close(SOCKET sock)
Definition: socket.c:879
size_t nbytes() const
#define BUFFER_SIZE
std::list< WriteBuffer * > write_queue_
queue of buffers to be written to the serial port
SerialException(const std::string &description)
const uint8_t * dpos() const
SerialListener * listener_
Pointer to byte listener.
boost::thread io_thread_
thread on which the io service runs


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:58