5 typedef unsigned int uint;
21 if(ver == 1 || ver == 2) {
46 port.set_option(asio::serial_port::baud_rate(
uint(baudrate)));
48 asio::serial_port::parity(asio::serial_port::parity::none));
49 port.set_option(asio::serial_port::character_size(
50 asio::serial_port::character_size(8)));
52 asio::serial_port::stop_bits(asio::serial_port::stop_bits::one));
54 catch(
const std::system_error& e) {
55 const int ecode = e.code().value();
56 throw std::runtime_error(
"Error when opening '" + device +
57 "': " + e.code().category().message(ecode) +
58 " (error code: " + std::to_string(ecode) +
77 if(
running_.test_and_set())
return false;
79 thread = std::thread([
this] {
80 asio::async_read_until(
port,
84 std::placeholders::_1,
85 std::placeholders::_2),
88 std::placeholders::_1,
89 std::placeholders::_2));
110 rc &= sub.second->start();
118 rc &= sub.second->stop();
125 std::cout <<
"sending message - ID " << size_t(message.
id())
129 std::cerr <<
"message failed to send" << std::endl;
134 const auto predicate = [&] {
149 std::chrono::milliseconds(
size_t(timeout * 1e3)),
152 std::cout <<
"timed out waiting for response to message ID " 153 << size_t(message.
id()) << std::endl;
169 const bool decode_success = data.size() == 0 ?
true : message.
decode(data);
170 return recv_success && decode_success;
175 std::cout <<
"async sending message - ID " << size_t(message.
id())
179 std::cerr <<
"async sendData failed" << std::endl;
186 if(
buffer.sgetc() == EOF) {
188 std::cerr <<
"buffer returned EOF; reading char directly from port" 190 asio::read(
port,
buffer, asio::transfer_exactly(1));
192 return uint8_t(
buffer.sbumpc());
197 std::cout <<
"sending: " << size_t(
id) <<
" | " << data;
207 std::size_t bytes_written;
211 asio::write(
port, asio::buffer(msg.data(), msg.size()), ec);
215 std::cerr <<
"------------------> WRITE FAILED <--------------------" 220 std::cout <<
"write complete: " << bytes_written <<
" vs " << msg.size()
222 return (bytes_written == msg.size());
231 msg.push_back(uint8_t(data.size()));
232 msg.push_back(uint8_t(
id));
233 msg.insert(msg.end(), data.begin(), data.end());
234 msg.push_back(
crcV1(uint8_t(
id), data));
239 uint8_t crc = uint8_t(data.size()) ^
id;
240 for(
const uint8_t d : data) {
253 msg.push_back(uint8_t(uint16_t(
id) & 0xFF));
254 msg.push_back(uint8_t(uint16_t(
id) >> 8));
256 const uint16_t size = uint16_t(data.size());
257 msg.push_back(uint8_t(size & 0xFF));
258 msg.push_back(uint8_t(size >> 8));
260 msg.insert(msg.end(), data.begin(), data.end());
267 for(
const uint8_t& p : data) {
275 for(
int ii = 0; ii < 8; ++ii) {
277 crc = uint8_t(crc << 1) ^ 0xD5;
280 crc = uint8_t(crc << 1);
287 const std::size_t& bytes_transferred) {
289 std::cout <<
"processOneMessage on " << bytes_transferred <<
" bytes" 292 if(ec == asio::error::operation_aborted) {
301 if(msg_marker !=
'$')
302 std::cerr <<
"Message marker " << size_t(msg_marker)
303 <<
" is not recognised!" << std::endl;
308 if(ver_marker ==
'M') ver = 1;
309 if(ver_marker ==
'X') ver = 2;
311 std::cerr <<
"Version marker " << size_t(ver_marker)
312 <<
" is not recognised!" << std::endl;
340 asio::async_read_until(
port,
344 std::placeholders::_1,
345 std::placeholders::_2),
348 std::placeholders::_1,
349 std::placeholders::_2));
352 std::cout <<
"processOneMessage finished" << std::endl;
358 const size_t available = size_t(std::distance(begin, end));
360 if(available < 2)
return std::make_pair(begin,
false);
362 if(*i ==
'$' && *(i + 1) ==
'M') {
364 if(available < 6)
return std::make_pair(begin,
false);
366 const uint8_t payload_size = uint8_t(*(i + 3));
368 if(available <
size_t(5 + payload_size + 1))
369 return std::make_pair(begin,
false);
371 std::advance(i, 5 + payload_size + 1);
373 else if(*i ==
'$' && *(i + 1) ==
'X') {
375 if(available < 9)
return std::make_pair(begin,
false);
377 const uint16_t payload_size =
378 uint8_t(*(i + 6)) | uint8_t(*(i + 7) << 8);
381 if(available <
size_t(8 + payload_size + 1))
382 return std::make_pair(begin,
false);
384 std::advance(i, 8 + payload_size + 1);
387 for(; i != end; ++i) {
393 return std::make_pair(i,
true);
403 const bool ok_id = (dir !=
'!');
413 std::cerr <<
"Message v1 with ID " << size_t(ret.
id)
414 <<
" is not recognised!" << std::endl;
418 for(
size_t i(0); i < len; i++) {
425 const bool ok_crc = (rcv_crc == exp_crc);
428 std::cerr <<
"Message v1 with ID " << size_t(ret.
id)
429 <<
" has wrong CRC! (expected: " << size_t(exp_crc)
430 <<
", received: " << size_t(rcv_crc) <<
")" << std::endl;
452 if(
log_level_ >=
DEBUG) std::cout <<
"dir: " << size_t(dir) << std::endl;
453 const bool ok_id = (dir !=
'!');
457 if(
log_level_ >=
DEBUG) std::cout <<
"flag: " << size_t(flag) << std::endl;
458 exp_crc =
crcV2(exp_crc, flag);
463 uint16_t
id = uint16_t(id_low) | uint16_t(id_high << 8);
465 if(
log_level_ >=
DEBUG) std::cout <<
"id: " << size_t(
id) << std::endl;
466 exp_crc =
crcV2(exp_crc, id_low);
467 exp_crc =
crcV2(exp_crc, id_high);
472 uint32_t len = uint32_t(len_low) | (uint32_t(len_high) << 8);
473 exp_crc =
crcV2(exp_crc, len_low);
474 exp_crc =
crcV2(exp_crc, len_high);
478 std::cerr <<
"Message v2 with ID " << size_t(ret.
id)
479 <<
" is not recognised!" << std::endl;
484 for(
size_t i(0); i < len; i++) {
493 const bool ok_crc = (rcv_crc == exp_crc);
496 std::cerr <<
"Message v2 with ID " << size_t(ret.
id)
497 <<
" has wrong CRC! (expected: " << size_t(exp_crc)
498 <<
", received: " << size_t(rcv_crc) <<
")" << std::endl;
void processOneMessage(const asio::error_code &ec, const std::size_t &bytes_transferred)
Main entry point for processing received data. It is called directly by the ASIO library, and as such it much match the function signatures expected by ASIO.
bool start(const std::string &device, const size_t baudrate=115200)
Start communications with a flight controller.
bool stopReadThread()
Stops the receiver thread.
uint8_t extractChar()
Read a single byte from either the buffer or the serial device.
std::condition_variable cv_response
bool sendMessageNoWait(const msp::Message &message)
Send a message, but do not wait for any response.
bool sendData(const msp::ID id, const ByteVector &data=ByteVector(0))
Send an ID and payload to the flight controller.
bool setVersion(const int &ver)
Change the device path on the next connect.
std::mutex mutex_response
ByteVector packMessageV1(const msp::ID id, const ByteVector &data=ByteVector(0)) const
packMessageV1 Packs data ID and data payload into a MSPv1 formatted buffer ready for sending to the s...
std::mutex mutex_subscriptions
void setLoggingLevel(const LoggingLevel &level)
Set the verbosity of the output.
virtual ByteVectorUptr encode() const
Encode all data into a ByteVector.
asio::io_service io
! io service
~Client()
~Client Destructor
bool stop()
Stop communications with a flight controller.
std::unique_ptr< ReceivedMessage > request_received
bool stopSubscriptions()
Stops the receiver thread.
uint8_t crcV2(uint8_t crc, const ByteVector &data) const
crcV2 Computes a checksum for MSPv2 messages
FirmwareVariant
Enum of firmware variants.
std::atomic_flag running_
std::map< msp::ID, std::shared_ptr< SubscriptionBase > > subscriptions
asio::buffers_iterator< asio::streambuf::const_buffers_type > iterator
void setVariant(const FirmwareVariant &v)
Change the device path on the next connect.
std::mutex cv_response_mtx
ReceivedMessage processOneMessageV2()
processOneMessageV2 Iterates over characters in the ASIO buffer to identify and unpack a MSPv2 encode...
asio::serial_port port
! port for serial device
Client()
Client Constructor.
virtual bool decode(const ByteVector &)
Decode message contents from a ByteVector.
FirmwareVariant fw_variant
bool sendMessage(msp::Message &message, const double &timeout=0)
Send a message to the connected flight controller. If the message sends data to the flight controller...
int getVersion() const
Query the cached device path.
uint8_t crcV1(const uint8_t id, const ByteVector &data) const
crcV1 Computes a checksum for MSPv1 messages
bool startReadThread()
Starts the receiver thread that handles incomming messages.
virtual ID id() const =0
get the ID of the message
bool isConnected() const
Query the system to see if a connection is active.
bool connectPort(const std::string &device, const size_t baudrate=115200)
Establish connection to serial device and start read thread.
FirmwareVariant getVariant() const
Query the cached device path.
ReceivedMessage processOneMessageV1()
processOneMessageV1 Iterates over characters in the ASIO buffer to identify and unpack a MSPv1 encode...
ByteVector packMessageV2(const msp::ID id, const ByteVector &data=ByteVector(0)) const
packMessageV2 Packs data ID and data payload into a MSPv2 formatted buffer ready for sending to the s...
bool disconnectPort()
Break connection to serial device and stop read thread.
std::pair< iterator, bool > messageReady(iterator begin, iterator end) const
messageReady Method used by ASIO library to determine if a full message is present in receiving buffe...
bool startSubscriptions()
Starts the receiver thread that handles incomming messages.