-
-
Notifications
You must be signed in to change notification settings - Fork 487
/
offboard_velocity.cpp
245 lines (202 loc) · 8.02 KB
/
offboard_velocity.cpp
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
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
/**
* @file offboard_velocity.cpp
* @brief Example that demonstrates offboard velocity control in local NED and body coordinates
*
* @authors Author: Julian Oes <julian@oes.ch>,
* Shakthi Prashanth <shakthi.prashanth.m@intel.com>
* @date 2017-10-17
*/
#include <chrono>
#include <cmath>
#include <dronecode_sdk/action.h>
#include <dronecode_sdk/dronecode_sdk.h>
#include <dronecode_sdk/offboard.h>
#include <dronecode_sdk/telemetry.h>
#include <iostream>
#include <thread>
using namespace dronecode_sdk;
using std::this_thread::sleep_for;
using std::chrono::milliseconds;
using std::chrono::seconds;
#define ERROR_CONSOLE_TEXT "\033[31m" // Turn text on console red
#define TELEMETRY_CONSOLE_TEXT "\033[34m" // Turn text on console blue
#define NORMAL_CONSOLE_TEXT "\033[0m" // Restore normal console colour
// Handles Action's result
inline void action_error_exit(Action::Result result, const std::string &message)
{
if (result != Action::Result::SUCCESS) {
std::cerr << ERROR_CONSOLE_TEXT << message << Action::result_str(result)
<< NORMAL_CONSOLE_TEXT << std::endl;
exit(EXIT_FAILURE);
}
}
// Handles Offboard's result
inline void offboard_error_exit(Offboard::Result result, const std::string &message)
{
if (result != Offboard::Result::SUCCESS) {
std::cerr << ERROR_CONSOLE_TEXT << message << Offboard::result_str(result)
<< NORMAL_CONSOLE_TEXT << std::endl;
exit(EXIT_FAILURE);
}
}
// Handles connection result
inline void connection_error_exit(ConnectionResult result, const std::string &message)
{
if (result != ConnectionResult::SUCCESS) {
std::cerr << ERROR_CONSOLE_TEXT << message << connection_result_str(result)
<< NORMAL_CONSOLE_TEXT << std::endl;
exit(EXIT_FAILURE);
}
}
// Logs during Offboard control
inline void offboard_log(const std::string &offb_mode, const std::string msg)
{
std::cout << "[" << offb_mode << "] " << msg << std::endl;
}
/**
* Does Offboard control using NED co-ordinates.
*
* returns true if everything went well in Offboard control, exits with a log otherwise.
*/
bool offb_ctrl_ned(std::shared_ptr<dronecode_sdk::Offboard> offboard)
{
const std::string offb_mode = "NED";
// Send it once before starting offboard, otherwise it will be rejected.
offboard->set_velocity_ned({0.0f, 0.0f, 0.0f, 0.0f});
Offboard::Result offboard_result = offboard->start();
offboard_error_exit(offboard_result, "Offboard start failed");
offboard_log(offb_mode, "Offboard started");
offboard_log(offb_mode, "Turn to face East");
offboard->set_velocity_ned({0.0f, 0.0f, 0.0f, 90.0f});
sleep_for(seconds(1)); // Let yaw settle.
{
const float step_size = 0.01f;
const float one_cycle = 2.0f * (float)M_PI;
const unsigned steps = 2 * unsigned(one_cycle / step_size);
offboard_log(offb_mode, "Go North and back South");
for (unsigned i = 0; i < steps; ++i) {
float vx = 5.0f * sinf(i * step_size);
offboard->set_velocity_ned({vx, 0.0f, 0.0f, 90.0f});
sleep_for(milliseconds(10));
}
}
offboard_log(offb_mode, "Turn to face West");
offboard->set_velocity_ned({0.0f, 0.0f, 0.0f, 270.0f});
sleep_for(seconds(2));
offboard_log(offb_mode, "Go up 2 m/s, turn to face South");
offboard->set_velocity_ned({0.0f, 0.0f, -2.0f, 180.0f});
sleep_for(seconds(4));
offboard_log(offb_mode, "Go down 1 m/s, turn to face North");
offboard->set_velocity_ned({0.0f, 0.0f, 1.0f, 0.0f});
sleep_for(seconds(4));
// Now, stop offboard mode.
offboard_result = offboard->stop();
offboard_error_exit(offboard_result, "Offboard stop failed: ");
offboard_log(offb_mode, "Offboard stopped");
return true;
}
/**
* Does Offboard control using body co-ordinates.
*
* returns true if everything went well in Offboard control, exits with a log otherwise.
*/
bool offb_ctrl_body(std::shared_ptr<dronecode_sdk::Offboard> offboard)
{
const std::string offb_mode = "BODY";
// Send it once before starting offboard, otherwise it will be rejected.
offboard->set_velocity_body({0.0f, 0.0f, 0.0f, 0.0f});
Offboard::Result offboard_result = offboard->start();
offboard_error_exit(offboard_result, "Offboard start failed: ");
offboard_log(offb_mode, "Offboard started");
offboard_log(offb_mode, "Turn clock-wise and climb");
offboard->set_velocity_body({0.0f, 0.0f, -1.0f, 60.0f});
sleep_for(seconds(5));
offboard_log(offb_mode, "Turn back anti-clockwise");
offboard->set_velocity_body({0.0f, 0.0f, 0.0f, -60.0f});
sleep_for(seconds(5));
offboard_log(offb_mode, "Wait for a bit");
offboard->set_velocity_body({0.0f, 0.0f, 0.0f, 0.0f});
sleep_for(seconds(2));
offboard_log(offb_mode, "Fly a circle");
offboard->set_velocity_body({5.0f, 0.0f, 0.0f, 30.0f});
sleep_for(seconds(15));
offboard_log(offb_mode, "Wait for a bit");
offboard->set_velocity_body({0.0f, 0.0f, 0.0f, 0.0f});
sleep_for(seconds(5));
offboard_log(offb_mode, "Fly a circle sideways");
offboard->set_velocity_body({0.0f, -5.0f, 0.0f, 30.0f});
sleep_for(seconds(15));
offboard_log(offb_mode, "Wait for a bit");
offboard->set_velocity_body({0.0f, 0.0f, 0.0f, 0.0f});
sleep_for(seconds(8));
offboard_result = offboard->stop();
offboard_error_exit(offboard_result, "Offboard stop failed: ");
offboard_log(offb_mode, "Offboard stopped");
return true;
}
void usage(std::string bin_name)
{
std::cout << NORMAL_CONSOLE_TEXT << "Usage : " << bin_name << " <connection_url>" << std::endl
<< "Connection URL format should be :" << std::endl
<< " For TCP : tcp://[server_host][:server_port]" << std::endl
<< " For UDP : udp://[bind_host][:bind_port]" << std::endl
<< " For Serial : serial:///path/to/serial/dev[:baudrate]" << std::endl
<< "For example, to connect to the simulator use URL: udp://:14540" << std::endl;
}
int main(int argc, char **argv)
{
DronecodeSDK dc;
std::string connection_url;
ConnectionResult connection_result;
if (argc == 2) {
connection_url = argv[1];
connection_result = dc.add_any_connection(connection_url);
} else {
usage(argv[0]);
return 1;
}
if (connection_result != ConnectionResult::SUCCESS) {
std::cout << ERROR_CONSOLE_TEXT
<< "Connection failed: " << connection_result_str(connection_result)
<< NORMAL_CONSOLE_TEXT << std::endl;
return 1;
}
// Wait for the system to connect via heartbeat
while (!dc.is_connected()) {
std::cout << "Wait for system to connect via heartbeat" << std::endl;
sleep_for(seconds(1));
}
// System got discovered.
System &system = dc.system();
auto action = std::make_shared<Action>(system);
auto offboard = std::make_shared<Offboard>(system);
auto telemetry = std::make_shared<Telemetry>(system);
while (!telemetry->health_all_ok()) {
std::cout << "Waiting for system to be ready" << std::endl;
sleep_for(seconds(1));
}
std::cout << "System is ready" << std::endl;
Action::Result arm_result = action->arm();
action_error_exit(arm_result, "Arming failed");
std::cout << "Armed" << std::endl;
Action::Result takeoff_result = action->takeoff();
action_error_exit(takeoff_result, "Takeoff failed");
std::cout << "In Air..." << std::endl;
sleep_for(seconds(5));
// using local NED co-ordinates
bool ret = offb_ctrl_ned(offboard);
if (ret == false) {
return EXIT_FAILURE;
}
// using body co-ordinates
ret = offb_ctrl_body(offboard);
if (ret == false) {
return EXIT_FAILURE;
}
const Action::Result land_result = action->land();
action_error_exit(land_result, "Landing failed");
// We are relying on auto-disarming but let's keep watching the telemetry for a bit longer.
sleep_for(seconds(10));
std::cout << "Landed" << std::endl;
return EXIT_SUCCESS;
}