00001 00009 /* 00010 * Copyright 2014 Vladimir Ermakov. 00011 * 00012 * This file is part of the mavros package and subject to the license terms 00013 * in the top-level LICENSE file of the mavros repository. 00014 * https://github.com/mavlink/mavros/tree/master/LICENSE.md 00015 */ 00016 00017 #pragma once 00018 00019 #include <diagnostic_updater/diagnostic_updater.h> 00020 #include <mavconn/interface.h> 00021 00022 namespace mavros { 00023 class MavlinkDiag : public diagnostic_updater::DiagnosticTask 00024 { 00025 public: 00026 explicit MavlinkDiag(std::string name); 00027 00028 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00029 00030 void set_mavconn(const mavconn::MAVConnInterface::Ptr &link) { 00031 weak_link = link; 00032 } 00033 00034 void set_connection_status(bool connected) { 00035 is_connected = connected; 00036 } 00037 00038 private: 00039 mavconn::MAVConnInterface::WeakPtr weak_link; 00040 unsigned int last_drop_count; 00041 std::atomic<bool> is_connected; 00042 }; 00043 }; // namespace mavros 00044