37 #include <linux/input.h>
38 #include <linux/serial.h>
41 #include <boost/asio.hpp>
52 1200, 2400, 4800, 9600, 19200, 38400, 57600,
53 115200, 230400, 460800, 500000, 576000, 921600, 1000000,
54 1152000, 1500000, 2000000, 2500000, 3000000, 3500000, 4000000};
83 socket_.reset(
new boost::asio::ip::udp::socket(
85 boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(),
port_)));
92 "Listening on UDP port " + std::to_string(
port_));
101 boost::asio::placeholders::error,
102 boost::asio::placeholders::bytes_transferred));
111 if (!error && (bytes_recvd > 0))
113 while ((bytes_recvd - idx) > 2)
115 std::shared_ptr<Telegram> telegram(
new Telegram);
116 telegram->stamp = stamp;
128 telegram->message.assign(&
buffer_[idx],
137 "AsyncManager crc failed for SBF " +
139 telegram->message)) +
149 telegram->message.assign(&
buffer_[idx],
159 telegram->message.assign(&
buffer_[idx],
168 std::string(std::string(
169 telegram->message.begin(),
170 telegram->message.begin() + 2)));
181 "UDP client receive error: " + error.message());
197 std::this_thread::sleep_for(std::chrono::milliseconds(1000));
202 "UDP client connection lost. Trying to reconnect.");
213 size_t idx_end = idx + 2;
215 while (idx_end < bytes_recvd)
231 boost::asio::ip::udp::endpoint
eP_;
232 std::unique_ptr<boost::asio::ip::udp::socket>
socket_;
233 std::array<uint8_t, MAX_UDP_PACKET_SIZE>
buffer_;
241 std::shared_ptr<boost::asio::io_service> ioService) :
256 boost::asio::ip::tcp::resolver::iterator endpointIterator;
260 boost::asio::ip::tcp::resolver resolver(*
ioService_);
261 boost::asio::ip::tcp::resolver::query query(
263 endpointIterator = resolver.resolve(query);
264 }
catch (std::runtime_error& e)
268 " on port " +
port_ +
": " + e.what());
280 stream_->connect(*endpointIterator);
282 stream_->set_option(boost::asio::ip::tcp::no_delay(
true));
285 "Connected to " + endpointIterator->host_name() +
":" +
286 endpointIterator->service_name() +
".");
287 }
catch (std::runtime_error& e)
290 "Could not connect to " + endpointIterator->host_name() +
291 ": " + endpointIterator->service_name() +
": " +
305 std::unique_ptr<boost::asio::ip::tcp::socket>
stream_;
312 std::shared_ptr<boost::asio::io_service> ioService) :
338 "Connecting serially to device " +
340 ", targeted baudrate: " +
344 }
catch (
const boost::system::system_error& err)
348 ". Error: " + err.what() +
349 ". Will retry every second.");
351 using namespace std::chrono_literals;
352 std::this_thread::sleep_for(1
s);
358 stream_->set_option(boost::asio::serial_port_base::parity(
359 boost::asio::serial_port_base::parity::none));
360 stream_->set_option(boost::asio::serial_port_base::character_size(8));
361 stream_->set_option(boost::asio::serial_port_base::stop_bits(
362 boost::asio::serial_port_base::stop_bits::one));
367 stream_->set_option(boost::asio::serial_port_base::flow_control(
368 boost::asio::serial_port_base::flow_control::hardware));
371 stream_->set_option(boost::asio::serial_port_base::flow_control(
372 boost::asio::serial_port_base::flow_control::none));
376 int fd =
stream_->native_handle();
377 struct serial_struct serialInfo;
378 ioctl(fd, TIOCGSERIAL, &serialInfo);
379 serialInfo.flags |= ASYNC_LOW_LATENCY;
380 ioctl(fd, TIOCSSERIAL, &serialInfo);
389 "Gradually increasing the baudrate to the desired value...");
390 boost::asio::serial_port_base::baud_rate current_baudrate;
394 stream_->get_option(current_baudrate);
400 }
catch (boost::system::system_error& e)
404 static_cast<std::string
>(e.what()));
406 static_cast<std::string
>(e.what()));
420 "Current baudrate is " +
421 std::to_string(current_baudrate.value()));
422 for (uint8_t i = 0; i <
baudrates.size(); i++)
424 if (current_baudrate.value() ==
baudrate_)
428 if (current_baudrate.value() >=
baudrates[i] &&
437 boost::asio::serial_port_base::baud_rate(
baudrates[i]));
438 }
catch (boost::system::system_error& e)
442 "set_option failed due to " +
443 static_cast<std::string
>(e.what()));
445 "Additional info about error is " +
446 static_cast<std::string
>(e.what()));
449 using namespace std::chrono_literals;
450 std::this_thread::sleep_for(500ms);
454 stream_->get_option(current_baudrate);
455 }
catch (boost::system::system_error& e)
459 "get_option failed due to " +
460 static_cast<std::string
>(e.what()));
462 "Additional info about error is " +
463 static_cast<std::string
>(e.what()));
474 "Set ASIO baudrate to " +
475 std::to_string(current_baudrate.value()));
478 "Set ASIO baudrate to " +
479 std::to_string(current_baudrate.value()) +
480 ", leaving InitializeSerial() method");
483 ::tcflush(
stream_->native_handle(), TCIOFLUSH);
495 std::unique_ptr<boost::asio::serial_port>
stream_;
502 std::shared_ptr<boost::asio::io_service> ioService) :
527 new boost::asio::posix::stream_descriptor(*
ioService_));
530 }
catch (std::runtime_error& e)
533 static_cast<std::string
>(e.what()));
544 std::unique_ptr<boost::asio::posix::stream_descriptor>
stream_;
551 std::shared_ptr<boost::asio::io_service> ioService) :
577 new boost::asio::posix::stream_descriptor(*
ioService_));
581 stream_->assign(pcap_get_selectable_fd(pcap_));
583 }
catch (std::runtime_error& e)
586 static_cast<std::string
>(e.what()));
599 std::unique_ptr<boost::asio::posix::stream_descriptor>
stream_;