Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Blimp/GCS_MAVLink_Blimp.cpp
9575 views
1
#include "Blimp.h"
2
3
#include "GCS_MAVLink_Blimp.h"
4
#include <AP_RPM/AP_RPM_config.h>
5
#include <AP_OpticalFlow/AP_OpticalFlow_config.h>
6
7
MAV_TYPE GCS_Blimp::frame_type() const
8
{
9
return blimp.get_frame_mav_type();
10
}
11
12
uint8_t GCS_MAVLINK_Blimp::base_mode() const
13
{
14
uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
15
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
16
17
// we are armed if we are not initialising
18
if (blimp.motors != nullptr && blimp.motors->armed()) {
19
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
20
}
21
22
// indicate we have set a custom mode
23
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
24
25
return _base_mode;
26
}
27
28
uint32_t GCS_Blimp::custom_mode() const
29
{
30
return (uint32_t)blimp.control_mode;
31
}
32
33
MAV_STATE GCS_MAVLINK_Blimp::vehicle_system_status() const
34
{
35
// set system as critical if any failsafe have triggered
36
if (blimp.any_failsafe_triggered()) {
37
return MAV_STATE_CRITICAL;
38
}
39
40
if (blimp.ap.land_complete) {
41
return MAV_STATE_STANDBY;
42
}
43
if (!blimp.ap.initialised) {
44
return MAV_STATE_BOOT;
45
}
46
47
return MAV_STATE_ACTIVE;
48
}
49
50
51
void GCS_MAVLINK_Blimp::send_position_target_global_int()
52
{
53
Location target;
54
if (!blimp.flightmode->get_wp(target)) {
55
return;
56
}
57
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;
58
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
59
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
60
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
61
62
mavlink_msg_position_target_global_int_send(
63
chan,
64
AP_HAL::millis(), // time_boot_ms
65
MAV_FRAME_GLOBAL, // targets are always global altitude
66
TYPE_MASK, // ignore everything except the x/y/z components
67
target.lat, // latitude as 1e7
68
target.lng, // longitude as 1e7
69
target.alt * 0.01f, // altitude is sent as a float
70
0.0f, // vx
71
0.0f, // vy
72
0.0f, // vz
73
0.0f, // afx
74
0.0f, // afy
75
0.0f, // afz
76
0.0f, // yaw
77
0.0f); // yaw_rate
78
}
79
80
void GCS_MAVLINK_Blimp::send_nav_controller_output() const
81
{
82
83
}
84
85
float GCS_MAVLINK_Blimp::vfr_hud_airspeed() const
86
{
87
Vector3f airspeed_vec_bf;
88
if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
89
// we are running the EKF3 wind estimation code which can give
90
// us an airspeed estimate
91
return airspeed_vec_bf.length();
92
}
93
return AP::gps().ground_speed();
94
}
95
96
int16_t GCS_MAVLINK_Blimp::vfr_hud_throttle() const
97
{
98
if (blimp.motors == nullptr) {
99
return 0;
100
}
101
return (int16_t)(blimp.motors->get_throttle() * 100);
102
}
103
104
/*
105
send PID tuning message
106
*/
107
void GCS_MAVLINK_Blimp::send_pid_tuning()
108
{
109
if (blimp.control_mode == Mode::Number::MANUAL || blimp.control_mode == Mode::Number::LAND) {
110
//No PIDs are used in Manual or Land mode.
111
return;
112
}
113
114
static const int8_t axes[] = {
115
PID_SEND::VELX,
116
PID_SEND::VELY,
117
PID_SEND::VELZ,
118
PID_SEND::VELYAW,
119
PID_SEND::POSX,
120
PID_SEND::POSY,
121
PID_SEND::POSZ,
122
PID_SEND::POSYAW
123
};
124
for (uint8_t i=0; i<ARRAY_SIZE(axes); i++) {
125
if (!(blimp.g.gcs_pid_mask & (1<<(axes[i]-1)))) {
126
continue;
127
}
128
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
129
return;
130
}
131
const AP_PIDInfo *pid_info = nullptr;
132
switch (axes[i]) {
133
case PID_SEND::VELX:
134
pid_info = &blimp.pid_vel_xy.get_pid_info_x();
135
break;
136
case PID_SEND::VELY:
137
pid_info = &blimp.pid_vel_xy.get_pid_info_y();
138
break;
139
case PID_SEND::VELZ:
140
pid_info = &blimp.pid_vel_z.get_pid_info();
141
break;
142
case PID_SEND::VELYAW:
143
pid_info = &blimp.pid_vel_yaw.get_pid_info();
144
break;
145
case PID_SEND::POSX:
146
pid_info = &blimp.pid_pos_xy.get_pid_info_x();
147
break;
148
case PID_SEND::POSY:
149
pid_info = &blimp.pid_pos_xy.get_pid_info_y();
150
break;
151
case PID_SEND::POSZ:
152
pid_info = &blimp.pid_pos_z.get_pid_info();
153
break;
154
case PID_SEND::POSYAW:
155
pid_info = &blimp.pid_pos_yaw.get_pid_info();
156
break;
157
default:
158
continue;
159
}
160
if (pid_info != nullptr) {
161
mavlink_msg_pid_tuning_send(chan,
162
axes[i],
163
pid_info->target,
164
pid_info->actual,
165
pid_info->FF,
166
pid_info->P,
167
pid_info->I,
168
pid_info->D,
169
pid_info->slew_rate,
170
pid_info->Dmod);
171
}
172
}
173
}
174
175
bool GCS_Blimp::vehicle_initialised() const
176
{
177
return blimp.ap.initialised;
178
}
179
180
// try to send a message, return false if it wasn't sent
181
bool GCS_MAVLINK_Blimp::try_send_message(enum ap_message id)
182
{
183
switch (id) {
184
185
case MSG_WIND:
186
CHECK_PAYLOAD_SIZE(WIND);
187
send_wind();
188
break;
189
190
case MSG_ADSB_VEHICLE:
191
// unused
192
break;
193
194
default:
195
return GCS_MAVLINK::try_send_message(id);
196
}
197
return true;
198
}
199
200
void GCS_MAVLINK_Blimp::packetReceived(const mavlink_status_t &status,
201
const mavlink_message_t &msg)
202
{
203
GCS_MAVLINK::packetReceived(status, msg);
204
}
205
206
bool GCS_MAVLINK_Blimp::params_ready() const
207
{
208
if (AP_BoardConfig::in_config_error()) {
209
// we may never have parameters "initialised" in this case
210
return true;
211
}
212
// if we have not yet initialised (including allocating the motors
213
// object) we drop this request. That prevents the GCS from getting
214
// a confusing parameter count during bootup
215
return blimp.ap.initialised_params;
216
}
217
218
void GCS_MAVLINK_Blimp::send_banner()
219
{
220
GCS_MAVLINK::send_banner();
221
send_text(MAV_SEVERITY_INFO, "Frame: %s", blimp.get_frame_string());
222
}
223
224
MAV_RESULT GCS_MAVLINK_Blimp::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
225
{
226
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
227
}
228
229
230
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_do_set_roi(const Location &roi_loc)
231
{
232
if (!roi_loc.check_latlng()) {
233
return MAV_RESULT_FAILED;
234
}
235
// blimp.flightmode->auto_yaw.set_roi(roi_loc);
236
return MAV_RESULT_ACCEPTED;
237
}
238
239
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
240
{
241
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
242
if (!blimp.flightmode->in_guided_mode() && !change_modes) {
243
return MAV_RESULT_DENIED;
244
}
245
246
// sanity check location
247
if (!check_latlng(packet.x, packet.y)) {
248
return MAV_RESULT_DENIED;
249
}
250
251
Location request_location {};
252
if (!location_from_command_t(packet, request_location)) {
253
return MAV_RESULT_DENIED;
254
}
255
256
if (request_location.sanitize(blimp.current_loc)) {
257
// if the location wasn't already sane don't load it
258
return MAV_RESULT_DENIED; // failed as the location is not valid
259
}
260
261
return MAV_RESULT_ACCEPTED;
262
}
263
264
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
265
{
266
switch (packet.command) {
267
case MAV_CMD_DO_REPOSITION:
268
return handle_command_int_do_reposition(packet);
269
case MAV_CMD_NAV_TAKEOFF:
270
return MAV_RESULT_ACCEPTED;
271
default:
272
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
273
}
274
}
275
276
#if AP_MAVLINK_COMMAND_LONG_ENABLED
277
bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const
278
{
279
if (packet_command == MAV_CMD_NAV_TAKEOFF) {
280
frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
281
return true;
282
}
283
return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);
284
}
285
#endif
286
287
void GCS_MAVLINK_Blimp::handle_message(const mavlink_message_t &msg)
288
{
289
switch (msg.msgid) {
290
default:
291
GCS_MAVLINK::handle_message(msg);
292
break;
293
} // end switch
294
} // end handle mavlink
295
296
297
MAV_RESULT GCS_MAVLINK_Blimp::handle_flight_termination(const mavlink_command_int_t &packet)
298
{
299
MAV_RESULT result = MAV_RESULT_FAILED;
300
if (packet.param1 > 0.5f) {
301
blimp.arming.disarm(AP_Arming::Method::TERMINATION);
302
result = MAV_RESULT_ACCEPTED;
303
}
304
return result;
305
}
306
307
float GCS_MAVLINK_Blimp::vfr_hud_alt() const
308
{
309
if (blimp.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {
310
// compatibility option for older mavlink-aware devices that
311
// assume Blimp returns a relative altitude in VFR_HUD.alt
312
return blimp.current_loc.alt * 0.01f;
313
}
314
return GCS_MAVLINK::vfr_hud_alt();
315
}
316
317
uint64_t GCS_MAVLINK_Blimp::capabilities() const
318
{
319
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
320
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
321
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
322
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
323
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
324
MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
325
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
326
GCS_MAVLINK::capabilities());
327
}
328
329
MAV_LANDED_STATE GCS_MAVLINK_Blimp::landed_state() const
330
{
331
if (blimp.ap.land_complete) {
332
return MAV_LANDED_STATE_ON_GROUND;
333
}
334
if (blimp.flightmode->is_landing()) {
335
return MAV_LANDED_STATE_LANDING;
336
}
337
// if (blimp.flightmode->is_taking_off()) {
338
// return MAV_LANDED_STATE_TAKEOFF;
339
// }
340
return MAV_LANDED_STATE_IN_AIR;
341
}
342
343
void GCS_MAVLINK_Blimp::send_wind() const
344
{
345
Vector3f airspeed_vec_bf;
346
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
347
// if we don't have an airspeed estimate then we don't have a
348
// valid wind estimate on blimps
349
return;
350
}
351
const Vector3f wind = AP::ahrs().wind_estimate();
352
mavlink_msg_wind_send(
353
chan,
354
degrees(atan2f(-wind.y, -wind.x)),
355
wind.length(),
356
wind.z);
357
}
358
359
#if HAL_HIGH_LATENCY2_ENABLED
360
uint8_t GCS_MAVLINK_Blimp::high_latency_wind_speed() const
361
{
362
Vector3f airspeed_vec_bf;
363
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
364
// if we don't have an airspeed estimate then we don't have a
365
// valid wind estimate on blimps
366
return 0;
367
}
368
// return units are m/s*5
369
const Vector3f wind = AP::ahrs().wind_estimate();
370
return wind.length() * 5;
371
}
372
373
uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
374
{
375
Vector3f airspeed_vec_bf;
376
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
377
// if we don't have an airspeed estimate then we don't have a
378
// valid wind estimate on blimps
379
return 0;
380
}
381
const Vector3f wind = AP::ahrs().wind_estimate();
382
// need to convert -180->180 to 0->360/2
383
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
384
}
385
#endif // HAL_HIGH_LATENCY2_ENABLED
386
387
// Send the mode with the given index (not mode number!) return the total number of modes
388
// Index starts at 1
389
uint8_t GCS_MAVLINK_Blimp::send_available_mode(uint8_t index) const
390
{
391
const Mode* modes[] {
392
&blimp.mode_land,
393
&blimp.mode_manual,
394
&blimp.mode_velocity,
395
&blimp.mode_loiter,
396
&blimp.mode_rtl,
397
};
398
399
const uint8_t mode_count = ARRAY_SIZE(modes);
400
401
// Convert to zero indexed
402
const uint8_t index_zero = index - 1;
403
if (index_zero >= mode_count) {
404
// Mode does not exist!?
405
return mode_count;
406
}
407
408
// Ask the mode for its name and number
409
const char* name = modes[index_zero]->name();
410
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
411
412
mavlink_msg_available_modes_send(
413
chan,
414
mode_count,
415
index,
416
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
417
mode_number,
418
0, // MAV_MODE_PROPERTY bitmask
419
name
420
);
421
422
return mode_count;
423
}
424
425