00001
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <cassert>
00028 #include <console_bridge/console.h>
00029
00030 #include <mavconn/thread_utils.h>
00031 #include <mavconn/serial.h>
00032
00033 namespace mavconn {
00034 using boost::system::error_code;
00035 using boost::asio::io_service;
00036 using boost::asio::serial_port_base;
00037 using boost::asio::buffer;
00038 typedef std::lock_guard<std::recursive_mutex> lock_guard;
00039
00040
00041 MAVConnSerial::MAVConnSerial(uint8_t system_id, uint8_t component_id,
00042 std::string device, unsigned baudrate) :
00043 MAVConnInterface(system_id, component_id),
00044 tx_in_progress(false),
00045 io_service(),
00046 serial_dev(io_service)
00047 {
00048 logInform("serial%d: device: %s @ %d bps", channel, device.c_str(), baudrate);
00049
00050 try {
00051 serial_dev.open(device);
00052
00053
00054 serial_dev.set_option(serial_port_base::baud_rate(baudrate));
00055 serial_dev.set_option(serial_port_base::character_size(8));
00056 serial_dev.set_option(serial_port_base::parity(serial_port_base::parity::none));
00057 serial_dev.set_option(serial_port_base::stop_bits(serial_port_base::stop_bits::one));
00058 serial_dev.set_option(serial_port_base::flow_control(serial_port_base::flow_control::none));
00059 }
00060 catch (boost::system::system_error &err) {
00061 throw DeviceError("serial", err);
00062 }
00063
00064
00065 io_service.post(boost::bind(&MAVConnSerial::do_read, this));
00066
00067
00068 std::thread t(boost::bind(&io_service::run, &this->io_service));
00069 mavutils::set_thread_name(t, "MAVConnSerial%d", channel);
00070 io_thread.swap(t);
00071 }
00072
00073 MAVConnSerial::~MAVConnSerial() {
00074 close();
00075 }
00076
00077 void MAVConnSerial::close() {
00078 lock_guard lock(mutex);
00079 if (!is_open())
00080 return;
00081
00082 serial_dev.close();
00083 io_service.stop();
00084
00085
00086 std::for_each(tx_q.begin(), tx_q.end(),
00087 [](MsgBuffer *p) { delete p; });
00088 tx_q.clear();
00089
00090 if (io_thread.joinable())
00091 io_thread.join();
00092
00093 port_closed();
00094 }
00095
00096 void MAVConnSerial::send_bytes(const uint8_t *bytes, size_t length)
00097 {
00098 if (!is_open()) {
00099 logError("serial%d:send: channel closed!", channel);
00100 return;
00101 }
00102
00103 MsgBuffer *buf = new MsgBuffer(bytes, length);
00104 {
00105 lock_guard lock(mutex);
00106 tx_q.push_back(buf);
00107 }
00108 io_service.post(boost::bind(&MAVConnSerial::do_write, this, true));
00109 }
00110
00111 void MAVConnSerial::send_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid)
00112 {
00113 assert(message != nullptr);
00114
00115 if (!is_open()) {
00116 logError("serial%d:send: channel closed!", channel);
00117 return;
00118 }
00119
00120 logDebug("serial%d:send: Message-Id: %d [%d bytes]", channel, message->msgid, message->len);
00121
00122 MsgBuffer *buf = new_msgbuffer(message, sysid, compid);
00123 {
00124 lock_guard lock(mutex);
00125 tx_q.push_back(buf);
00126 }
00127 io_service.post(boost::bind(&MAVConnSerial::do_write, this, true));
00128 }
00129
00130 void MAVConnSerial::do_read(void)
00131 {
00132 serial_dev.async_read_some(
00133 buffer(rx_buf, sizeof(rx_buf)),
00134 boost::bind(&MAVConnSerial::async_read_end,
00135 this,
00136 boost::asio::placeholders::error,
00137 boost::asio::placeholders::bytes_transferred));
00138 }
00139
00140 void MAVConnSerial::async_read_end(error_code error, size_t bytes_transferred)
00141 {
00142 mavlink_message_t message;
00143 mavlink_status_t status;
00144
00145 if (error) {
00146 logError("serial%d:receive: %s", channel, error.message().c_str());
00147 close();
00148 return;
00149 }
00150
00151 for (ssize_t i = 0; i < bytes_transferred; i++) {
00152 if (mavlink_parse_char(channel, rx_buf[i], &message, &status)) {
00153 logDebug("serial%d:recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d",
00154 channel, message.msgid, message.len, message.sysid, message.compid);
00155
00156 message_received(&message, message.sysid, message.compid);
00157 }
00158 }
00159
00160 do_read();
00161 }
00162
00163 void MAVConnSerial::do_write(bool check_tx_state)
00164 {
00165 if (check_tx_state && tx_in_progress)
00166 return;
00167
00168 lock_guard lock(mutex);
00169 if (tx_q.empty())
00170 return;
00171
00172 tx_in_progress = true;
00173 MsgBuffer *buf = tx_q.front();
00174 serial_dev.async_write_some(
00175 buffer(buf->dpos(), buf->nbytes()),
00176 boost::bind(&MAVConnSerial::async_write_end,
00177 this,
00178 boost::asio::placeholders::error,
00179 boost::asio::placeholders::bytes_transferred));
00180 }
00181
00182 void MAVConnSerial::async_write_end(error_code error, size_t bytes_transferred)
00183 {
00184 if (error) {
00185 logError("serial%d:write: %s", channel, error.message().c_str());
00186 close();
00187 return;
00188 }
00189
00190 lock_guard lock(mutex);
00191 if (tx_q.empty()) {
00192 tx_in_progress = false;
00193 return;
00194 }
00195
00196 MsgBuffer *buf = tx_q.front();
00197 buf->pos += bytes_transferred;
00198 if (buf->nbytes() == 0) {
00199 tx_q.pop_front();
00200 delete buf;
00201 }
00202
00203 if (!tx_q.empty())
00204 do_write(false);
00205 else
00206 tx_in_progress = false;
00207 }
00208
00209 };