.. _program_listing_file__tmp_ws_src_mavros_libmavconn_include_mavconn_serial.hpp: Program Listing for File serial.hpp =================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/mavros/libmavconn/include/mavconn/serial.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // // libmavconn // Copyright 2013,2014,2015,2016,2021 Vladimir Ermakov, All rights reserved. // // This file is part of the mavros package and subject to the license terms // in the top-level LICENSE file of the mavros repository. // https://github.com/mavlink/mavros/tree/master/LICENSE.md // #pragma once #ifndef MAVCONN__SERIAL_HPP_ #define MAVCONN__SERIAL_HPP_ #include #include #include #include #include #include namespace mavconn { class MAVConnSerial : public MAVConnInterface, public std::enable_shared_from_this { public: static constexpr auto DEFAULT_DEVICE = "/dev/ttyACM0"; static constexpr auto DEFAULT_BAUDRATE = 57600; MAVConnSerial( uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE, std::string device = DEFAULT_DEVICE, unsigned baudrate = DEFAULT_BAUDRATE, bool hwflow = false); virtual ~MAVConnSerial(); void connect( const ReceivedCb & cb_handle_message, const ClosedCb & cb_handle_closed_port = ClosedCb()) override; void close() override; void send_message(const mavlink::mavlink_message_t * message) override; void send_message(const mavlink::Message & message, const uint8_t source_compid) override; void send_bytes(const uint8_t * bytes, size_t length) override; inline bool is_open() override { return serial_dev.is_open(); } private: asio::io_service io_service; std::thread io_thread; asio::serial_port serial_dev; std::atomic tx_in_progress; std::deque tx_q; std::array rx_buf; std::recursive_mutex mutex; void do_read(); void do_write(bool check_tx_state); }; } // namespace mavconn #endif // MAVCONN__SERIAL_HPP_