• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

37.5
/src/mavsdk/core/mavsdk_impl.h
1
#pragma once
2

3
#include <cstdint>
4
#include <mutex>
5
#include <sys/types.h>
6
#include <utility>
7
#include <vector>
8
#include <atomic>
9
#include <thread>
10

11
#include "autopilot.h"
12
#include "call_every_handler.h"
13
#include "component_type.h"
14
#include "connection.h"
15
#include "cli_arg.h"
16
#include "handle_factory.h"
17
#include "handle.h"
18
#include "mavsdk.h"
19
#include "mavlink_include.h"
20
#include "mavlink_address.h"
21
#include "mavlink_message_handler.h"
22
#include "mavlink_command_receiver.h"
23
#include "safe_queue.h"
24
#include "server_component.h"
25
#include "system.h"
26
#include "sender.h"
27
#include "timeout_handler.h"
28
#include "callback_list.h"
29

30
namespace mavsdk {
31

32
class MavsdkImpl {
33
public:
34
    MavsdkImpl(const Mavsdk::Configuration& configuration);
35
    ~MavsdkImpl();
36
    MavsdkImpl(const MavsdkImpl&) = delete;
37
    void operator=(const MavsdkImpl&) = delete;
38

39
    static std::string version();
40

41
    void forward_message(mavlink_message_t& message, Connection* connection);
42
    void receive_message(mavlink_message_t& message, Connection* connection);
43

44
    std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
45
    add_any_connection(const std::string& connection_url, ForwardingOption forwarding_option);
46
    void remove_connection(Mavsdk::ConnectionHandle handle);
47

48
    std::vector<std::shared_ptr<System>> systems() const;
49

50
    std::optional<std::shared_ptr<System>> first_autopilot(double timeout_s);
51

52
    void set_configuration(Mavsdk::Configuration new_configuration);
53
    Mavsdk::Configuration get_configuration() const;
54

55
    bool send_message(mavlink_message_t& message);
56
    uint8_t get_own_system_id() const;
57
    uint8_t get_own_component_id() const;
58
    uint8_t channel() const;
59
    Autopilot autopilot() const;
60

61
    Sender& sender();
62

63
    uint8_t get_mav_type() const;
64

65
    Mavsdk::NewSystemHandle subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback);
66
    void unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle);
67

68
    void notify_on_discover();
69
    void notify_on_timeout();
70

71
    void start_sending_heartbeats();
72
    void stop_sending_heartbeats();
73

74
    void intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback);
75
    void intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback);
76

77
    std::shared_ptr<ServerComponent> server_component(unsigned instance = 0);
78

79
    std::shared_ptr<ServerComponent>
80
    server_component_by_type(ComponentType server_component_type, unsigned instance = 0);
81
    std::shared_ptr<ServerComponent> server_component_by_id(uint8_t component_id);
82

83
    Time time{};
84
    TimeoutHandler timeout_handler;
85
    CallEveryHandler call_every_handler;
86

87
    void call_user_callback_located(
88
        const std::string& filename, int linenumber, const std::function<void()>& func);
89

90
    void set_timeout_s(double timeout_s) { _timeout_s = timeout_s; }
60✔
91

92
    double timeout_s() const { return _timeout_s; };
866✔
93

94
    MavlinkMessageHandler mavlink_message_handler{};
95

96
    ServerComponentImpl& default_server_component_impl();
97

98
private:
99
    static constexpr float DEFAULT_TIMEOUT_S = 0.5f;
100

101
    std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
102
    add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option);
103

104
    std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
105
    add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option);
106
    std::pair<ConnectionResult, Mavsdk::ConnectionHandle> add_serial_connection(
107
        const std::string& dev_path,
108
        int baudrate,
109
        bool flow_control,
110
        ForwardingOption forwarding_option);
111

112
    Mavsdk::ConnectionHandle add_connection(const std::shared_ptr<Connection>&);
113
    void make_system_with_component(uint8_t system_id, uint8_t component_id);
114

115
    void work_thread();
116
    void process_user_callbacks_thread();
117

118
    void send_heartbeat();
119
    bool is_any_system_connected() const;
120

121
    static uint8_t get_target_system_id(const mavlink_message_t& message);
122
    static uint8_t get_target_component_id(const mavlink_message_t& message);
123

124
    std::mutex _connections_mutex{};
125
    HandleFactory<> _connections_handle_factory;
126
    struct ConnectionEntry {
127
        std::shared_ptr<Connection> connection;
128
        Handle<> handle;
129
    };
130
    std::vector<ConnectionEntry> _connections{};
131

132
    mutable std::recursive_mutex _systems_mutex{};
133
    std::vector<std::pair<uint8_t, std::shared_ptr<System>>> _systems{};
134

135
    mutable std::mutex _server_components_mutex{};
136
    std::vector<std::pair<uint8_t, std::shared_ptr<ServerComponent>>> _server_components{};
137
    std::shared_ptr<ServerComponent> _default_server_component{nullptr};
138

139
    CallbackList<> _new_system_callbacks{};
140

141
    Mavsdk::Configuration _configuration{ComponentType::GroundStation};
142

143
    struct UserCallback {
144
        UserCallback() = default;
145
        explicit UserCallback(std::function<void()> func_) : func(std::move(func_)) {}
808✔
146
        UserCallback(std::function<void()> func_, std::string filename_, const int linenumber_) :
×
147
            func(std::move(func_)),
×
148
            filename(std::move(filename_)),
×
149
            linenumber(linenumber_)
×
150
        {}
×
151

152
        std::function<void()> func{};
153
        std::string filename{};
154
        int linenumber{};
155
    };
156

157
    std::thread* _work_thread{nullptr};
158
    std::thread* _process_user_callbacks_thread{nullptr};
159
    SafeQueue<UserCallback> _user_callback_queue{};
160

161
    bool _message_logging_on{false};
162
    bool _callback_debugging{false};
163
    bool _system_debugging{false};
164

165
    mutable std::mutex _intercept_callback_mutex{};
166
    std::function<bool(mavlink_message_t&)> _intercept_incoming_messages_callback{nullptr};
167
    std::function<bool(mavlink_message_t&)> _intercept_outgoing_messages_callback{nullptr};
168

169
    std::atomic<double> _timeout_s{DEFAULT_TIMEOUT_S};
170

171
    static constexpr double HEARTBEAT_SEND_INTERVAL_S = 1.0;
172
    CallEveryHandler::Cookie _heartbeat_send_cookie{};
173

174
    std::atomic<bool> _should_exit = {false};
175
};
176

177
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc