serial.cpp
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 
38 #include <serial.h>
39 
40 
41 using boost::asio::serial_port_base;
42 
43 Serial::Serial(std::string port, int baud_rate) :
44  io_service_(),
45  write_in_progress_(false),
46  serial_port_(io_service_),
47  port_(port),
48  baud_rate_(baud_rate)
49 {
50  listener_ = NULL;
51 }
52 
54 {
55 }
56 
58 {
59  // open the port
60  try
61  {
62  serial_port_.open(port_);
63  serial_port_.set_option(serial_port_base::baud_rate(baud_rate_));
64  serial_port_.set_option(serial_port_base::character_size(8));
65  serial_port_.set_option(serial_port_base::parity(serial_port_base::parity::none));
66  serial_port_.set_option(serial_port_base::stop_bits(serial_port_base::stop_bits::one));
67  serial_port_.set_option(serial_port_base::flow_control(serial_port_base::flow_control::none));
68  }
69  catch (boost::system::system_error e)
70  {
71  throw SerialException(e);
72  }
73 
74  // start reading from the port
75  async_read();
76  io_thread_ = boost::thread(boost::bind(&boost::asio::io_service::run, &this->io_service_));
77 }
78 
80 {
81  mutex_lock lock(mutex_);
82 
83  io_service_.stop();
84  serial_port_.close();
85 
86  if (io_thread_.joinable())
87  {
88  io_thread_.join();
89  }
90 }
91 
93 {
94  if (listener == NULL || listener_ != NULL)
95  return;
96  else
97  listener_ = listener;
98 }
99 
101 {
102  if (!serial_port_.is_open()) return;
103 
104  serial_port_.async_read_some(
105  boost::asio::buffer(read_buf_raw_, BUFFER_SIZE),
106  boost::bind(
108  this,
109  boost::asio::placeholders::error,
110  boost::asio::placeholders::bytes_transferred));
111 }
112 
113 void Serial::async_read_end(const boost::system::error_code &error, size_t bytes_transferred)
114 {
115  if (!serial_port_.is_open()) return;
116 
117  if (error)
118  {
119  close();
120  return;
121  }
122 
123  listener_->handle_bytes(read_buf_raw_, bytes_transferred);
124 
125  async_read();
126 }
127 
128 void Serial::write(const uint8_t* bytes, uint8_t len)
129 {
130  assert(len <= BUFFER_SIZE);
131 
132  WriteBuffer *buffer = new WriteBuffer();
133  buffer->len = len;
134  for (int i = 0; i < len; i++)
135  {
136  buffer->data[i] = bytes[i];
137  }
138 
139  {
140  mutex_lock lock(mutex_);
141  write_queue_.push_back(buffer);
142  }
143 
144  async_write(true);
145 }
146 
147 void Serial::async_write(bool check_write_state)
148 {
149  if (check_write_state && write_in_progress_)
150  return;
151 
152  mutex_lock lock(mutex_);
153  if (write_queue_.empty())
154  return;
155 
156  write_in_progress_ = true;
157  WriteBuffer *buffer = write_queue_.front();
158  serial_port_.async_write_some(
159  boost::asio::buffer(buffer->dpos(), buffer->nbytes()),
160  boost::bind(
162  this,
163  boost::asio::placeholders::error,
164  boost::asio::placeholders::bytes_transferred));
165 
166 }
167 
168 void Serial::async_write_end(const boost::system::error_code &error, std::size_t bytes_transferred)
169 {
170  if (error)
171  {
172  std::cerr << error.message() << std::endl;
173  close();
174  return;
175  }
176 
177  mutex_lock lock(mutex_);
178  if (write_queue_.empty())
179  {
180  write_in_progress_ = false;
181  return;
182  }
183 
184  WriteBuffer *buffer = write_queue_.front();
185  buffer->pos += bytes_transferred;
186  if (buffer->nbytes() == 0)
187  {
188  write_queue_.pop_front();
189  delete buffer;
190  }
191 
192  if (write_queue_.empty())
193  write_in_progress_ = false;
194  else
195  async_write(false);
196 }
boost::asio::serial_port serial_port_
boost serial port object
void async_read_end(const boost::system::error_code &error, size_t bytes_transferred)
Handler for end of asynchronous read operation.
Definition: serial.cpp:113
boost::asio::io_service io_service_
boost io service provider
void async_write(bool check_write_state)
Initialize an asynchronous write operation.
Definition: serial.cpp:147
#define NULL
Definition: nm_bsp.h:52
void close()
Stops communication and closes the port.
Definition: serial.cpp:79
bool write_in_progress_
flag for whether async_write is already running
void write(const uint8_t *buffer, uint8_t len)
write data
Definition: serial.cpp:128
int baud_rate_
void async_read()
Initiate an asynchronous read operation.
Definition: serial.cpp:100
Struct for buffering the contents of a mavlink message.
NMI_API sint8 bind(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen)
Definition: socket.c:563
virtual void handle_bytes(const uint8_t *bytes, uint8_t len)=0
void register_listener(SerialListener *const listener)
Register a listener for received bytes.
Definition: serial.cpp:92
boost::recursive_mutex mutex_
mutex for threadsafe operation
std::string port_
boost::lock_guard< boost::recursive_mutex > mutex_lock
Convenience typedef for mutex lock.
#define false
Definition: compiler.h:424
uint8_t read_buf_raw_[BUFFER_SIZE]
size_t nbytes() const
#define BUFFER_SIZE
std::list< WriteBuffer * > write_queue_
queue of buffers to be written to the serial port
std::ostream & cerr()
uint8_t data[BUFFER_SIZE]
Serial(std::__cxx11::string port, int baud_rate)
Instantiates the class and begins communication on the specified serial port.
Definition: serial.cpp:43
void open()
Opens the port and begins communication.
Definition: serial.cpp:57
const uint8_t * dpos() const
void async_write_end(const boost::system::error_code &error, size_t bytes_transferred)
Handler for end of asynchronous write operation.
Definition: serial.cpp:168
SerialListener * listener_
Pointer to byte listener.
boost::thread io_thread_
thread on which the io service runs
~Serial()
Stops communication and closes the serial port before the object is destroyed.
Definition: serial.cpp:53


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