sick_tim_common_tcp.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013, Freiburg University
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
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Osnabrück University nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: 15.11.2013
30  *
31  * Authors:
32  * Christian Dornhege <c.dornhege@googlemail.com>
33  */
34 
36 #include <boost/asio.hpp>
37 #include <boost/lambda/lambda.hpp>
38 #include <algorithm>
39 #include <iterator>
40 #include <boost/lexical_cast.hpp>
41 
42 namespace sick_tim
43 {
44 
45 SickTimCommonTcp::SickTimCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, AbstractParser* parser)
46 :
47  SickTimCommon(parser),
48  socket_(io_service_),
49  deadline_(io_service_),
50  hostname_(hostname),
51  port_(port),
52  timelimit_(timelimit)
53 {
54  // Set up the deadline actor to implement timeouts.
55  // Based on blocking TCP example on:
56  // http://www.boost.org/doc/libs/1_46_0/doc/html/boost_asio/example/timeouts/blocking_tcp_client.cpp
57  deadline_.expires_at(boost::posix_time::pos_infin);
58  checkDeadline();
59 }
60 
62 {
63  stop_scanner();
64  close_device();
65 }
66 
67 using boost::asio::ip::tcp;
68 using boost::lambda::var;
69 using boost::lambda::_1;
70 
72 {
73  // Resolve the supplied hostname
74  tcp::resolver::iterator iterator;
75  try
76  {
77  tcp::resolver resolver(io_service_);
78  tcp::resolver::query query(hostname_, port_);
79  iterator = resolver.resolve(query);
80  }
81  catch (boost::system::system_error &e)
82  {
83  ROS_FATAL("Could not resolve host: ... (%d)(%s)", e.code().value(), e.code().message().c_str());
84  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Could not resolve host.");
85  return ExitError;
86  }
87 
88  // Try to connect to all possible endpoints
89  boost::system::error_code ec;
90  bool success = false;
91  for ( ; iterator != tcp::resolver::iterator(); ++iterator)
92  {
93  std::string repr = boost::lexical_cast<std::string>(iterator->endpoint());
94  socket_.close();
95 
96  // Set the time out length
97  ROS_INFO("Waiting %i seconds for device to connect.", timelimit_);
98  deadline_.expires_from_now(boost::posix_time::seconds(timelimit_));
99 
100  ec = boost::asio::error::would_block;
101  ROS_DEBUG("Attempting to connect to %s", repr.c_str());
102  socket_.async_connect(iterator->endpoint(), boost::lambda::var(ec) = _1);
103 
104  // Wait until timeout
105  do io_service_.run_one(); while (ec == boost::asio::error::would_block);
106 
107  if (!ec && socket_.is_open())
108  {
109  success = true;
110  ROS_INFO("Succesfully connected to %s", repr.c_str());
111  break;
112  }
113  ROS_ERROR("Failed to connect to %s", repr.c_str());
114  }
115 
116  // Check if connecting succeeded
117  if (!success)
118  {
119  ROS_FATAL("Could not connect to host %s:%s", hostname_.c_str(), port_.c_str());
120  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Could not connect to host.");
121  return ExitError;
122  }
123 
124  input_buffer_.consume(input_buffer_.size());
125 
126  return ExitSuccess;
127 }
128 
130 {
131  if (socket_.is_open())
132  {
133  try
134  {
135  socket_.close();
136  }
137  catch (boost::system::system_error &e)
138  {
139  ROS_ERROR("An error occured during closing of the connection: %d:%s", e.code().value(), e.code().message().c_str());
140  }
141  }
142  return 0;
143 }
144 
146 {
147  if (deadline_.expires_at() <= boost::asio::deadline_timer::traits_type::now())
148  {
149  // The reason the function is called is that the deadline expired. Close
150  // the socket to return all IO operations and reset the deadline
151  socket_.close();
152  deadline_.expires_at(boost::posix_time::pos_infin);
153  }
154 
155  // Nothing bad happened, go back to sleep
156  deadline_.async_wait(boost::bind(&SickTimCommonTcp::checkDeadline, this));
157 }
158 
159 int SickTimCommonTcp::readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read, bool *exception_occured)
160 {
161  // Set up the deadline to the proper timeout, error and delimiters
162  deadline_.expires_from_now(boost::posix_time::milliseconds(timeout_ms));
163  const char end_delim = static_cast<char>(0x03);
164  ec_ = boost::asio::error::would_block;
165  bytes_transfered_ = 0;
166 
167  // Read until 0x03 ending indicator
168  boost::asio::async_read_until(
169  socket_,
171  end_delim,
172  boost::bind(
174  this,
175  boost::asio::placeholders::error,
176  boost::asio::placeholders::bytes_transferred
177  )
178  );
179  do io_service_.run_one(); while (ec_ == boost::asio::error::would_block);
180 
181  if (ec_)
182  {
183  // would_block means the connectio is ok, but nothing came in in time.
184  // If any other error code is set, this means something bad happened.
185  if (ec_ != boost::asio::error::would_block)
186  {
187  ROS_ERROR("sendSOPASCommand: failed attempt to read from socket: %d: %s", ec_.value(), ec_.message().c_str());
188  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "sendSOPASCommand: exception during read_until().");
189  if (exception_occured != 0)
190  *exception_occured = true;
191  }
192 
193  // For would_block, just return and indicate nothing bad happend
194  return ExitError;
195  }
196 
197  // Avoid a buffer overflow by limiting the data we read
198  size_t to_read = bytes_transfered_ > buffer_size - 1 ? buffer_size - 1 : bytes_transfered_;
199  size_t i = 0;
200  std::istream istr(&input_buffer_);
201  if (buffer != 0)
202  {
203  istr.read(buffer, to_read);
204  buffer[to_read] = 0;
205 
206  // Consume the rest of the message if necessary
207  if (to_read < bytes_transfered_)
208  {
209  ROS_WARN("Dropping %zu bytes to avoid buffer overflow", bytes_transfered_ - to_read);
210  input_buffer_.consume(bytes_transfered_ - to_read);
211  }
212  }
213  else
214  // No buffer was provided, just drop the data
216 
217  // Set the return variable to the size of the read message
218  if (bytes_read != 0)
219  *bytes_read = to_read;
220 
221  return ExitSuccess;
222 }
223 
227 int SickTimCommonTcp::sendSOPASCommand(const char* request, std::vector<unsigned char> * reply)
228 {
229  if (!socket_.is_open()) {
230  ROS_ERROR("sendSOPASCommand: socket not open");
231  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "sendSOPASCommand: socket not open.");
232  return ExitError;
233  }
234 
235  /*
236  * Write a SOPAS variable read request to the device.
237  */
238  try
239  {
240  boost::asio::write(socket_, boost::asio::buffer(request, strlen(request)));
241  }
242  catch (boost::system::system_error &e)
243  {
244  ROS_ERROR("write error for command: %s", request);
245  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Write error for sendSOPASCommand.");
246  return ExitError;
247  }
248 
249  // Set timeout in 5 seconds
250  const int BUF_SIZE = 1000;
251  char buffer[BUF_SIZE];
252  int bytes_read;
253  if (readWithTimeout(1000, buffer, BUF_SIZE, &bytes_read, 0) == ExitError)
254  {
255  ROS_ERROR_THROTTLE(1.0, "sendSOPASCommand: no full reply available for read after 1s");
256  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "sendSOPASCommand: no full reply available for read after 5 s.");
257  return ExitError;
258  }
259 
260  if (reply)
261  {
262  reply->resize(bytes_read);
263  std::copy(buffer, buffer + bytes_read, &(*reply)[0]);
264  }
265 
266  return ExitSuccess;
267 }
268 
269 int SickTimCommonTcp::get_datagram(unsigned char* receiveBuffer, int bufferSize, int* actual_length)
270 {
271  if (!socket_.is_open()) {
272  ROS_ERROR("get_datagram: socket not open");
273  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "get_datagram: socket not open.");
274  return ExitError;
275  }
276 
277  /*
278  * Write a SOPAS variable read request to the device.
279  */
280  std::vector<unsigned char> reply;
281 
282  // Wait at most 1000ms for a new scan
283  size_t timeout = 1000;
284  bool exception_occured = false;
285 
286  char *buffer = reinterpret_cast<char *>(receiveBuffer);
287 
288  if (readWithTimeout(timeout, buffer, bufferSize, actual_length, &exception_occured) != ExitSuccess)
289  {
290  ROS_ERROR_THROTTLE(1.0, "get_datagram: no data available for read after %zu ms", timeout);
291  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "get_datagram: no data available for read after timeout.");
292 
293  // Attempt to reconnect when the connection was terminated
294  if (!socket_.is_open())
295  {
296  sleep(1);
297  ROS_INFO("Failure - attempting to reconnect");
298  return init();
299  }
300 
301  return exception_occured ? ExitError : ExitSuccess; // keep on trying
302  }
303 
304  return ExitSuccess;
305 }
306 
307 } /* namespace sick_tim */
int readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read=0, bool *exception_occured=0)
boost::asio::streambuf input_buffer_
#define ROS_FATAL(...)
boost::system::error_code ec_
boost::asio::io_service io_service_
boost::asio::ip::tcp::socket socket_
#define ROS_WARN(...)
virtual int get_datagram(unsigned char *receiveBuffer, int bufferSize, int *actual_length)
Read a datagram from the device.
#define ROS_INFO(...)
#define ROS_ERROR_THROTTLE(period,...)
diagnostic_updater::Updater diagnostics_
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply)
Send a SOPAS command to the device and print out the response to the console.
SickTimCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, AbstractParser *parser)
boost::asio::deadline_timer deadline_
void handleRead(boost::system::error_code error, size_t bytes_transfered)
void broadcast(int lvl, const std::string msg)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther , Sebastian Pütz
autogenerated on Tue May 7 2019 03:13:47