-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmavlink_inspection_transfer.h
134 lines (114 loc) · 3.47 KB
/
mavlink_inspection_transfer.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
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
#pragma once
#include <chrono>
#include <cstdint>
#include <functional>
#include <memory>
#include <mutex>
#include <vector>
#include "mavlink_sender.h"
#include "timeout_handler.h"
#include "locked_queue.h"
#include "log.h"
namespace mavsdk {
class MAVLinkInspectionTransfer {
public:
enum class Result {
Success,
ConnectionError,
Timeout,
Cancelled,
InvalidSequence,
CurrentInvalid,
ProtocolError
};
enum class Ack {
Accepted,
Error,
Unsupported,
NoSpace,
Invalid,
InvalidParam1,
InvalidParam2,
InvalidParam3,
InvalidParam4,
InvalidParam5,
InvalidParam6,
InvalidParam7,
InvalidSequence,
Cancelled,
Unknown
};
struct WaypointItem {
uint16_t seq;
std::string task_uuid;
std::string task_type_uuid;
uint16_t command;
uint8_t autocontinue;
float param1;
float param2;
float param3;
float param4;
float x;
float y;
float z;
bool operator==(const WaypointItem& other) const
{
return (
seq == other.seq && task_uuid == other.task_uuid && task_type_uuid == other.task_type_uuid &&
command == other.command && autocontinue == other.autocontinue && param1 == other.param1 &&
param2 == other.param2 && param3 == other.param3 && param4 == other.param4 &&
x == other.x && y == other.y && z == other.z);
}
};
struct WaypointList {
std::string plan_uuid;
uint32_t sync_id;
std::vector<WaypointItem> items{};
bool operator==(const WaypointList& other) const
{
return plan_uuid == other.plan_uuid && sync_id == other.sync_id && items == other.items;
}
};
using ResultCallback = std::function<void(Result result)>;
using ResultAndAckCallback = std::function<void(Result result, Ack ack)>;
using ResultAndListCallback = std::function<void(Result result, WaypointList list)>;
class WorkItem {
public:
WorkItem(
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler);
virtual ~WorkItem();
virtual void start() = 0;
virtual void cancel() = 0;
bool has_started();
bool is_done();
WorkItem(const WorkItem&) = delete;
WorkItem(WorkItem&&) = delete;
WorkItem& operator=(const WorkItem&) = delete;
WorkItem& operator=(WorkItem&&) = delete;
protected:
Sender& _sender;
MAVLinkMessageHandler& _message_handler;
TimeoutHandler& _timeout_handler;
bool _started{false};
bool _done{false};
std::mutex _mutex{};
};
static constexpr double timeout_s = 0.5;
static constexpr unsigned retries = 4;
MAVLinkInspectionTransfer(
Sender& sender, MAVLinkMessageHandler& message_handler, TimeoutHandler& timeout_handler);
virtual ~MAVLinkInspectionTransfer();
void do_work();
bool is_idle();
// Non-copyable
MAVLinkInspectionTransfer(const MAVLinkInspectionTransfer&) = delete;
const MAVLinkInspectionTransfer& operator=(const MAVLinkInspectionTransfer&) = delete;
protected:
Sender& _sender;
MAVLinkMessageHandler& _message_handler;
TimeoutHandler& _timeout_handler;
LockedQueue<WorkItem> _work_queue{};
};
} // namespace mavsdk