Go to the documentation of this file.00001
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #pragma once
00032
00033 #include <boost/bind.hpp>
00034 #include <boost/signals2.hpp>
00035 #include <boost/smart_ptr.hpp>
00036 #include <boost/make_shared.hpp>
00037 #include <boost/system/system_error.hpp>
00038
00039 #include <set>
00040 #include <mutex>
00041 #include <thread>
00042 #include <memory>
00043 #include <sstream>
00044 #include <mavconn/mavlink_dialect.h>
00045
00046 namespace mavconn {
00047 namespace sig2 = boost::signals2;
00048
00049 class MsgBuffer;
00050
00054 class DeviceError : public std::exception {
00055 private:
00056 std::string e_what_;
00057
00058 public:
00062 explicit DeviceError(const char *module, const char *description) {
00063 std::ostringstream ss;
00064 ss << "DeviceError:" << module << ": " << description;
00065 e_what_ = ss.str();
00066 }
00067
00071 explicit DeviceError(const char *module, int errnum) {
00072 std::ostringstream ss;
00073 ss << "DeviceError:" << module << ":" << errnum << ": " << strerror(errnum);
00074 e_what_ = ss.str();
00075 }
00076
00080 explicit DeviceError(const char *module, boost::system::system_error &err) {
00081 std::ostringstream ss;
00082 ss << "DeviceError:" << module << ":" << err.what();
00083 e_what_ = ss.str();
00084 }
00085
00086 DeviceError(const DeviceError& other) : e_what_(other.e_what_) {}
00087 virtual ~DeviceError() throw() {}
00088 virtual const char *what() const throw() {
00089 return e_what_.c_str();
00090 }
00091 };
00092
00096 class MAVConnInterface {
00097 private:
00098 MAVConnInterface(const MAVConnInterface&) = delete;
00099
00100 public:
00101 typedef sig2::signal<void(const mavlink_message_t *message, uint8_t system_id, uint8_t component_id)> MessageSig;
00102 typedef boost::shared_ptr<MAVConnInterface> Ptr;
00103 typedef boost::shared_ptr<MAVConnInterface const> ConstPtr;
00104 typedef boost::weak_ptr<MAVConnInterface> WeakPtr;
00105
00110 MAVConnInterface(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE);
00111 virtual ~MAVConnInterface() {
00112 delete_channel(channel);
00113 };
00114
00118 virtual void close() = 0;
00119
00123 inline void send_message(const mavlink_message_t *message) {
00124 send_message(message, sys_id, comp_id);
00125 };
00126
00135 virtual void send_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid) = 0;
00136
00140 virtual void send_bytes(const uint8_t *bytes, size_t length) = 0;
00141
00145 MessageSig message_received;
00146 sig2::signal<void()> port_closed;
00147
00148 virtual mavlink_status_t get_status() = 0;
00149 virtual bool is_open() = 0;
00150
00151 inline int get_channel() { return channel; };
00152 inline uint8_t get_system_id() { return sys_id; };
00153 inline void set_system_id(uint8_t sysid) { sys_id = sysid; };
00154 inline uint8_t get_component_id() { return comp_id; };
00155 inline void set_component_id(uint8_t compid) { comp_id = compid; };
00156
00174 static Ptr open_url(std::string url,
00175 uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE);
00176
00177 protected:
00178 int channel;
00179 uint8_t sys_id;
00180 uint8_t comp_id;
00181
00182 #if MAVLINK_CRC_EXTRA
00183 static const uint8_t mavlink_crcs[];
00184 #endif
00185
00186 static int new_channel();
00187 static void delete_channel(int chan);
00188 static int channes_available();
00189
00193 MsgBuffer *new_msgbuffer(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
00194
00195 private:
00196 static std::recursive_mutex channel_mutex;
00197 static std::set<int> allocated_channels;
00198 };
00199
00200 };