vssp.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, ATR, Atsushi Watanabe
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 the copyright holder 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 
30 #ifndef VSSP_H
31 #define VSSP_H
32 
33 #include <boost/asio.hpp>
34 #include <boost/array.hpp>
35 #include <boost/format.hpp>
36 #include <boost/bind.hpp>
37 #include <boost/serialization/access.hpp>
38 #include <boost/archive/binary_iarchive.hpp>
39 #include <boost/shared_array.hpp>
40 #include <boost/algorithm/string.hpp>
41 #include <boost/chrono.hpp>
42 
43 #include <vector>
44 #include <string>
45 
46 #include <vsspdefs.h>
47 
48 namespace vssp
49 {
51 {
52 private:
53  boost::asio::io_service io_service_;
54  boost::asio::ip::tcp::socket socket_;
55  boost::asio::deadline_timer timer_;
56  bool closed_;
58 
59  boost::function<void(
60  const vssp::Header&,
61  const vssp::RangeHeader&,
62  const vssp::RangeIndex&,
65  const boost::posix_time::ptime&)> cb_point_;
66  boost::function<void(
67  const vssp::Header&,
68  const vssp::AuxHeader&,
70  const boost::posix_time::ptime&)> cb_aux_;
71  boost::function<void(
72  const vssp::Header&,
73  const boost::posix_time::ptime&)> cb_ping_;
74  boost::function<void(
75  const vssp::Header&,
76  const std::string&,
77  const boost::posix_time::ptime&)> cb_error_;
78  boost::function<void(bool)> cb_connect_;
80  std::vector<boost::shared_array<const TableSincos>> tbl_v_;
83  std::vector<bool> tbl_vn_loaded_;
84  boost::posix_time::time_duration timeout_;
85 
86  boost::asio::streambuf buf_;
87 
88 public:
90  : socket_(io_service_)
91  , timer_(io_service_)
92  , closed_(false)
93  , aux_factor_(AUX_FACTOR_DEFAULT)
94  , cb_point_(0)
95  , cb_aux_(0)
96  , cb_ping_(0)
97  , tbl_h_loaded_(false)
98  , tbl_v_loaded_(false)
99  , timeout_(boost::posix_time::seconds(1))
100  {
101  }
102  void setTimeout(const double to)
103  {
104  timeout_ = boost::posix_time::milliseconds(static_cast<int64_t>(1000 * to));
105  }
106  void connect(const char* ip, const unsigned int port, decltype(cb_connect_) cb)
107  {
108  cb_connect_ = cb;
109  boost::asio::ip::tcp::endpoint endpoint(boost::asio::ip::address::from_string(ip), port);
110  timer_.expires_from_now(timeout_);
111  timer_.async_wait(boost::bind(&VsspDriver::onTimeoutConnect, this, boost::asio::placeholders::error));
112  socket_.async_connect(endpoint, boost::bind(&vssp::VsspDriver::onConnect, this, boost::asio::placeholders::error));
113  }
114  void registerErrorCallback(decltype(cb_error_) cb)
115  {
116  cb_error_ = cb;
117  }
118  void registerCallback(decltype(cb_point_) cb)
119  {
120  cb_point_ = cb;
121  }
122  void registerAuxCallback(decltype(cb_aux_) cb)
123  {
124  cb_aux_ = cb;
125  }
126  void registerPingCallback(decltype(cb_ping_) cb)
127  {
128  cb_ping_ = cb;
129  }
130  void setAutoReset(const bool enable)
131  {
132  if (enable)
133  send(std::string("SET:_ars=1\n"));
134  else
135  send(std::string("SET:_ars=0\n"));
136  }
137  [[deprecated("use setHorizontalInterlace() instead of setInterlace()")]] void setInterlace(const int itl)
138  {
140  }
141  void setHorizontalInterlace(const int itl)
142  {
143  send((boost::format("SET:_itl=0,%02d\n") % itl).str());
144  }
145  void setVerticalInterlace(const int itl)
146  {
147  send((boost::format("SET:_itv=0,%02d\n") % itl).str());
148  }
149  void requestVerticalTable(const int itl = 1)
150  {
151  tbl_v_.resize(itl);
152  tbl_vn_loaded_.resize(itl);
153  if (itl == 1)
154  {
155  send(std::string("GET:tblv\n"));
156  }
157  else
158  {
159  for (int i = 0; i < itl; ++i)
160  {
161  send((boost::format("GET:tv%02d\n") % i).str());
162  tbl_vn_loaded_[i] = false;
163  }
164  }
165  }
167  {
168  send(std::string("GET:tblh\n"));
169  }
170  void requestPing()
171  {
172  send(std::string("PNG\n"));
173  }
174  void requestAuxData(const bool start = 1)
175  {
176  send((boost::format("DAT:ax=%d\n") % static_cast<int>(start)).str());
177  }
178  void requestData(const bool intensity = 1, const bool start = 1)
179  {
180  if (intensity)
181  {
182  send((boost::format("DAT:ri=%d\n") % static_cast<int>(start)).str());
183  }
184  else
185  {
186  send((boost::format("DAT:ro=%d\n") % static_cast<int>(start)).str());
187  }
188  }
190  {
191  timer_.cancel();
192  timer_.expires_from_now(timeout_);
193  timer_.async_wait(boost::bind(&VsspDriver::onTimeout, this, boost::asio::placeholders::error));
194  // Read at least 4 bytes.
195  // In most case, callback function will be called for each VSSP line.
196  boost::asio::async_read(socket_, buf_, boost::asio::transfer_at_least(4),
197  boost::bind(&VsspDriver::onRead, this, boost::asio::placeholders::error));
198  }
199  bool poll()
200  {
201  boost::system::error_code ec;
202  io_service_.poll(ec);
203  if (!ec)
204  return true;
205  return false;
206  }
207  void spin()
208  {
209  io_service_.run();
210  }
211  void stop()
212  {
213  io_service_.stop();
214  }
215  boost::asio::io_service& getIoService()
216  {
217  return io_service_;
218  }
219 
220 private:
221  void send(const std::string cmd)
222  {
223  boost::shared_ptr<std::string> data(new std::string(cmd));
224  boost::asio::async_write(socket_, boost::asio::buffer(*data),
225  boost::bind(&VsspDriver::onSend, this, boost::asio::placeholders::error, data));
226  }
227  void onTimeoutConnect(const boost::system::error_code& error)
228  {
229  if (!error)
230  {
231  closed_ = true;
232  io_service_.stop();
233  }
234  }
235  void onTimeout(const boost::system::error_code& error)
236  {
237  if (!error)
238  {
239  closed_ = true;
240  io_service_.stop();
241  }
242  }
243  void onConnect(const boost::system::error_code& error)
244  {
245  timer_.cancel();
246  if (error)
247  {
248  closed_ = true;
249  cb_connect_(false);
250  return;
251  }
252  cb_connect_(true);
253  }
254  void onSend(const boost::system::error_code& error, boost::shared_ptr<std::string> data)
255  {
256  if (error)
257  {
258  closed_ = true;
259  return;
260  }
261  }
262  template <class DATA_TYPE>
264  const vssp::RangeHeader& range_header,
265  const vssp::RangeHeaderV2R1& range_header_v2r1,
266  const vssp::RangeIndex& range_index,
268  const boost::shared_array<vssp::XYZI>& points)
269  {
270  if (tbl_vn_loaded_.size() != range_header_v2r1.vertical_interlace)
271  return false;
272 
273  int i = 0;
274  const double h_head = range_header.line_head_h_angle_ratio * 2.0 * M_PI / 65535.0;
275  const double h_tail = range_header.line_tail_h_angle_ratio * 2.0 * M_PI / 65535.0;
276  const DATA_TYPE* data = boost::asio::buffer_cast<const DATA_TYPE*>(buf_.data());
277  const int tv = range_header_v2r1.vertical_field;
278  for (int s = 0; s < range_index.nspots; s++)
279  {
280  const double spot = s + range_header.spot;
281  const double h_rad = h_head + (h_tail - h_head) * tbl_h_[spot];
282  const double h_cos = cos(h_rad);
283  const double h_sin = sin(h_rad);
284  const vssp::XYZI dir(tbl_v_[tv][spot].s, tbl_v_[tv][spot].c, h_sin, h_cos);
285  for (int e = index[s]; e < index[s + 1]; e++)
286  points[i++] = dir * data[e];
287  }
288  return true;
289  }
290  void onRead(const boost::system::error_code& error)
291  {
292  const auto time_read = boost::posix_time::microsec_clock::universal_time();
293  if (error == boost::asio::error::eof)
294  {
295  // Connection closed_
296  closed_ = true;
297  io_service_.stop();
298  return;
299  }
300  else if (error)
301  {
302  // Connection error
303  closed_ = true;
304  io_service_.stop();
305  }
306  while (true)
307  {
308  if (buf_.size() < sizeof(vssp::Header))
309  {
310  break;
311  }
312  // Read packet Header
313  const vssp::Header header = *boost::asio::buffer_cast<const vssp::Header*>(buf_.data());
314  if (header.mark != vssp::VSSP_MARK)
315  {
316  // Invalid packet
317  // find VSSP mark
318  const uint8_t* data = boost::asio::buffer_cast<const uint8_t*>(buf_.data());
319  for (size_t i = 1; i < buf_.size() - sizeof(uint32_t); i++)
320  {
321  const uint32_t* mark = reinterpret_cast<const uint32_t*>(data + i);
322  if (*mark == vssp::VSSP_MARK)
323  {
324  buf_.consume(i);
325  break;
326  }
327  }
328  break;
329  }
330  if (buf_.size() < header.length)
331  break;
332 
333  size_t length = header.length - header.header_length;
334  buf_.consume(header.header_length);
335 
336  for (int i = 0; i < 1; ++i)
337  {
338  switch (header.type)
339  {
340  case TYPE_ERR:
341  case TYPE_ER:
342  // Error message
343  {
344  const std::string data(boost::asio::buffer_cast<const char*>(buf_.data()));
345  std::string message(data, 0, header.length - header.header_length - 1);
346  if (cb_error_)
347  cb_error_(header, message, time_read);
348  }
349  break;
350  default:
351  break;
352  }
353  if (header.status != vssp::STATUS_OK)
354  break;
355 
356  switch (header.type)
357  {
358  case TYPE_GET:
359  // Response to get command
360  {
361  const std::string data(boost::asio::buffer_cast<const char*>(buf_.data()));
362  std::vector<std::string> lines;
363  boost::algorithm::split(lines, data, boost::algorithm::is_any_of("\n\r"));
364  if (lines.size() == 0)
365  break;
366 
367  if (lines[0].compare(0, 7, "GET:tbl") == 0 ||
368  lines[0].compare(0, 6, "GET:tv") == 0)
369  {
370  if (lines.size() < 2)
371  break;
372  std::vector<std::string> cells;
373  boost::algorithm::split(cells, lines[1], boost::algorithm::is_any_of(","));
374 
375  if (lines[0].compare("GET:tblv") == 0 ||
376  lines[0].compare(0, 6, "GET:tv") == 0)
377  {
378  int tv = 0;
379  if (lines[0].compare(0, 6, "GET:tv") == 0)
380  tv = std::stoi(lines[0].substr(6));
381 
382  if (tv >= static_cast<int>(tbl_v_.size()))
383  break;
384 
385  boost::shared_array<TableSincos> tbl_v(new TableSincos[cells.size()]);
386  int i = 0;
387  for (auto& cell : cells)
388  {
389  const double rad(std::strtol(cell.c_str(), nullptr, 16) * 2.0 * M_PI / 65535.0);
390  sincos(rad, &tbl_v[i].s, &tbl_v[i].c);
391  i++;
392  }
393  tbl_v_[tv] = tbl_v;
394  tbl_vn_loaded_[tv] = true;
395 
396  bool load_finished = true;
397  for (auto loaded : tbl_vn_loaded_)
398  {
399  if (!loaded)
400  load_finished = false;
401  }
402  tbl_v_loaded_ = load_finished;
403  }
404  else if (lines[0].compare("GET:tblh") == 0)
405  {
406  boost::shared_array<double> tbl_h(new double[cells.size()]);
407  int i = 0;
408  for (auto& cell : cells)
409  {
410  tbl_h[i] = std::strtol(cell.c_str(), nullptr, 16) / 65535.0;
411  i++;
412  }
413  tbl_h_ = tbl_h;
414  tbl_h_loaded_ = true;
415  }
416  }
417  }
418  break;
419  case TYPE_SET:
420  // Response to set command
421  break;
422  case TYPE_DAT:
423  // Response to data request command
424  break;
425  case TYPE_VER:
426  // Response to version request command
427  break;
428  case TYPE_PNG:
429  // Response to ping command
430  if (cb_ping_)
431  cb_ping_(header, time_read);
432  break;
433  case TYPE_RI:
434  case TYPE_RO:
435  // Range data
436  if (!tbl_h_loaded_ || !tbl_v_loaded_ || !cb_point_)
437  {
438  // Something wrong
439  break;
440  }
441  {
442  // Decode range data Header
443  const vssp::RangeHeader range_header = *boost::asio::buffer_cast<const vssp::RangeHeader*>(buf_.data());
445  if (range_header.header_length >= 24)
446  {
447  range_header_v2r1 = *boost::asio::buffer_cast<const vssp::RangeHeaderV2R1*>(
448  buf_.data() + sizeof(vssp::RangeHeader));
449  }
450  buf_.consume(range_header.header_length);
451  length -= range_header.header_length;
452 
453  // Decode range index Header
454  const vssp::RangeIndex range_index = *boost::asio::buffer_cast<const vssp::RangeIndex*>(buf_.data());
455  size_t index_length = range_index.index_length;
456  buf_.consume(sizeof(vssp::RangeIndex));
457  index_length -= sizeof(vssp::RangeIndex);
458  length -= sizeof(vssp::RangeIndex);
459 
460  // Decode range index
461  boost::shared_array<uint16_t> index(new uint16_t[range_index.nspots + 1]);
462  std::memcpy(index.get(), boost::asio::buffer_cast<const vssp::RangeIndex*>(buf_.data()),
463  sizeof(uint16_t) * (range_index.nspots + 1));
464  buf_.consume(index_length);
465  length -= index_length;
466 
467  // Decode range data
468  boost::shared_array<vssp::XYZI> points(new vssp::XYZI[index[range_index.nspots]]);
469  bool success;
470  switch (header.type)
471  {
472  case TYPE_RI:
473  // Range and Intensity
474  success = rangeToXYZ<vssp::DataRangeIntensity>(
475  range_header, range_header_v2r1, range_index, index, points);
476  break;
477  case TYPE_RO:
478  // Range
479  success = rangeToXYZ<vssp::DataRangeOnly>(
480  range_header, range_header_v2r1, range_index, index, points);
481  break;
482  default:
483  success = false;
484  break;
485  }
486  if (!success)
487  break;
488  cb_point_(header, range_header, range_index, index, points, time_read);
489  }
490  break;
491  case TYPE_AX:
492  // Aux data
493  {
494  // Decode range data Header
495  const vssp::AuxHeader aux_header = *boost::asio::buffer_cast<const vssp::AuxHeader*>(buf_.data());
496  buf_.consume(aux_header.header_length);
497  length -= aux_header.header_length;
498 
499  // Decode Aux data
501  for (int i = 0; i < aux_header.data_count; i++)
502  {
503  const vssp::AuxData* data = boost::asio::buffer_cast<const vssp::AuxData*>(buf_.data());
504  int offset = 0;
505  for (AuxId b = vssp::AX_MASK_LAST; b >= vssp::AX_MASK_FIRST; b = static_cast<AuxId>(b - 1))
506  {
507  if (aux_header.data_bitfield & (1 << static_cast<int>(b)))
508  auxs[i][b] = aux_factor_[b] * data[offset++].val;
509  }
510  buf_.consume(sizeof(int32_t) * offset);
511  length -= sizeof(int32_t) * offset;
512  }
513  if (cb_aux_)
514  cb_aux_(header, aux_header, auxs, time_read);
515  }
516  break;
517  default:
518  break;
519  }
520  }
521  buf_.consume(length);
522  }
523  receivePackets();
524  return;
525  }
526 };
527 
528 } // namespace vssp
529 
530 #endif // VSSP_H
static const uint32_t TYPE_PNG
Definition: vsspdefs.h:51
void setAutoReset(const bool enable)
Definition: vssp.h:130
static const uint32_t TYPE_SET
Definition: vsspdefs.h:48
Definition: vssp.h:48
bool poll()
Definition: vssp.h:199
uint16_t header_length
Definition: vsspdefs.h:90
uint8_t data_count
Definition: vsspdefs.h:128
void onTimeout(const boost::system::error_code &error)
Definition: vssp.h:235
boost::asio::io_service & getIoService()
Definition: vssp.h:215
void onRead(const boost::system::error_code &error)
Definition: vssp.h:290
ROSCPP_DECL void start()
bool rangeToXYZ(const vssp::RangeHeader &range_header, const vssp::RangeHeaderV2R1 &range_header_v2r1, const vssp::RangeIndex &range_index, const boost::shared_array< const uint16_t > &index, const boost::shared_array< vssp::XYZI > &points)
Definition: vssp.h:263
void requestData(const bool intensity=1, const bool start=1)
Definition: vssp.h:178
void registerAuxCallback(decltype(cb_aux_) cb)
Definition: vssp.h:122
uint16_t header_length
Definition: vsspdefs.h:83
boost::asio::io_service io_service_
Definition: vssp.h:53
void requestVerticalTable(const int itl=1)
Definition: vssp.h:149
void setHorizontalInterlace(const int itl)
Definition: vssp.h:141
XmlRpcServer s
void setTimeout(const double to)
Definition: vssp.h:102
void setVerticalInterlace(const int itl)
Definition: vssp.h:145
boost::function< void(bool)> cb_connect_
Definition: vssp.h:78
static const uint32_t TYPE_AX
Definition: vsspdefs.h:55
void stop()
Definition: vssp.h:211
std_msgs::Header * header(M &m)
void registerCallback(decltype(cb_point_) cb)
Definition: vssp.h:118
uint32_t mark
Definition: vsspdefs.h:80
bool tbl_h_loaded_
Definition: vssp.h:81
void registerErrorCallback(decltype(cb_error_) cb)
Definition: vssp.h:114
boost::asio::ip::tcp::socket socket_
Definition: vssp.h:54
static const AuxFactorArray AUX_FACTOR_DEFAULT
Definition: vsspdefs.h:254
void requestAuxData(const bool start=1)
Definition: vssp.h:174
boost::asio::deadline_timer timer_
Definition: vssp.h:55
int16_t line_tail_h_angle_ratio
Definition: vsspdefs.h:94
bool tbl_v_loaded_
Definition: vssp.h:82
AuxFactorArray aux_factor_
Definition: vssp.h:57
uint16_t spot
Definition: vsspdefs.h:98
uint32_t data_bitfield
Definition: vsspdefs.h:127
static const uint32_t TYPE_RI
Definition: vsspdefs.h:53
void registerPingCallback(decltype(cb_ping_) cb)
Definition: vssp.h:126
void receivePackets()
Definition: vssp.h:189
uint16_t nspots
Definition: vsspdefs.h:112
void requestHorizontalTable()
Definition: vssp.h:166
uint8_t vertical_field
Definition: vsspdefs.h:102
boost::asio::streambuf buf_
Definition: vssp.h:86
void onTimeoutConnect(const boost::system::error_code &error)
Definition: vssp.h:227
static const uint32_t TYPE_ERR
Definition: vsspdefs.h:52
uint16_t length
Definition: vsspdefs.h:84
static const uint32_t TYPE_DAT
Definition: vsspdefs.h:49
boost::function< void(const vssp::Header &, const boost::posix_time::ptime &)> cb_ping_
Definition: vssp.h:73
bool closed_
Definition: vssp.h:56
void setInterlace(const int itl)
Definition: vssp.h:137
std::vector< bool > tbl_vn_loaded_
Definition: vssp.h:83
int16_t line_head_h_angle_ratio
Definition: vsspdefs.h:93
void onConnect(const boost::system::error_code &error)
Definition: vssp.h:243
boost::function< void(const vssp::Header &, const std::string &, const boost::posix_time::ptime &)> cb_error_
Definition: vssp.h:77
static const uint32_t TYPE_RO
Definition: vsspdefs.h:54
void onSend(const boost::system::error_code &error, boost::shared_ptr< std::string > data)
Definition: vssp.h:254
static const uint32_t TYPE_ER
Definition: vsspdefs.h:56
const RangeHeaderV2R1 RANGE_HEADER_V2R1_DEFAULT
Definition: vsspdefs.h:105
void spin()
Definition: vssp.h:207
void connect(const char *ip, const unsigned int port, decltype(cb_connect_) cb)
Definition: vssp.h:106
AuxId
Definition: vsspdefs.h:58
int32_t val
Definition: vsspdefs.h:133
static const uint32_t STATUS_OK
Definition: vsspdefs.h:39
static const uint32_t VSSP_MARK
Definition: vsspdefs.h:38
uint8_t vertical_interlace
Definition: vsspdefs.h:103
void requestPing()
Definition: vssp.h:170
static const uint32_t TYPE_VER
Definition: vsspdefs.h:50
uint32_t status
Definition: vsspdefs.h:82
boost::posix_time::time_duration timeout_
Definition: vssp.h:84
uint32_t type
Definition: vsspdefs.h:81
boost::function< void(const vssp::Header &, const vssp::AuxHeader &, const boost::shared_array< vssp::Aux > &, const boost::posix_time::ptime &)> cb_aux_
Definition: vssp.h:70
std::vector< boost::shared_array< const TableSincos > > tbl_v_
Definition: vssp.h:80
uint16_t header_length
Definition: vsspdefs.h:125
boost::shared_array< const double > tbl_h_
Definition: vssp.h:79
uint16_t index_length
Definition: vsspdefs.h:111
boost::function< void(const vssp::Header &, const vssp::RangeHeader &, const vssp::RangeIndex &, const boost::shared_array< uint16_t > &, const boost::shared_array< vssp::XYZI > &, const boost::posix_time::ptime &)> cb_point_
Definition: vssp.h:65
static const uint32_t TYPE_GET
Definition: vsspdefs.h:47
void send(const std::string cmd)
Definition: vssp.h:221


hokuyo3d
Author(s): Atsushi Watanabe
autogenerated on Thu May 13 2021 02:27:44