-
Notifications
You must be signed in to change notification settings - Fork 0
/
mavlink_channels.h
52 lines (40 loc) · 1.38 KB
/
mavlink_channels.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
#pragma once
#include <cstdint>
#include <mutex>
namespace mavsdk {
class MAVLinkChannels {
public:
static MAVLinkChannels& Instance()
{
// This should be thread-safe in C++11.
static MAVLinkChannels instance;
return instance;
}
// delete copy and move constructors and assign operators
MAVLinkChannels(MAVLinkChannels const&) = delete; // Copy construct
MAVLinkChannels(MAVLinkChannels&&) = delete; // Move construct
MAVLinkChannels& operator=(MAVLinkChannels const&) = delete; // Copy assign
MAVLinkChannels& operator=(MAVLinkChannels&&) = delete; // Move assign
MAVLinkChannels();
~MAVLinkChannels();
/**
* Check out a free channel and mark it as used.
*
* @param new_channel: the channel assigned to use
* @return true if a free channel was available.
*/
bool checkout_free_channel(uint8_t& new_channel);
/**
* Check a used channel back in and mark it as free again.
*
* @param used_channel: the channel that is returned
*/
void checkin_used_channel(uint8_t used_channel);
uint8_t get_max_channels() { return MAX_CHANNELS; }
private:
// It is not clear what the limit of the number of channels is, except UINT8_MAX.
static constexpr uint8_t MAX_CHANNELS = 32;
bool _channels_used[MAX_CHANNELS];
std::mutex _channels_used_mutex;
};
} // namespace mavsdk