Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/GCS_MAVLink_Copter.cpp
9451 views
1
#include "Copter.h"
2
3
#include "GCS_MAVLink_Copter.h"
4
#include <AP_RPM/AP_RPM_config.h>
5
#include <AP_EFI/AP_EFI_config.h>
6
7
MAV_TYPE GCS_Copter::frame_type() const
8
{
9
/*
10
for GCS don't give MAV_TYPE_GENERIC as the GCS would have no
11
information and won't display UIs such as flight mode
12
selection
13
*/
14
#if FRAME_CONFIG == HELI_FRAME
15
const MAV_TYPE mav_type_default = MAV_TYPE_HELICOPTER;
16
#else
17
const MAV_TYPE mav_type_default = MAV_TYPE_QUADROTOR;
18
#endif
19
if (copter.motors == nullptr) {
20
return mav_type_default;
21
}
22
MAV_TYPE mav_type = copter.motors->get_frame_mav_type();
23
if (mav_type == MAV_TYPE_GENERIC) {
24
mav_type = mav_type_default;
25
}
26
return mav_type;
27
}
28
29
uint8_t GCS_MAVLINK_Copter::base_mode() const
30
{
31
uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
32
// work out the base_mode. This value is not very useful
33
// for APM, but we calculate it as best we can so a generic
34
// MAVLink enabled ground station can work out something about
35
// what the MAV is up to. The actual bit values are highly
36
// ambiguous for most of the APM flight modes. In practice, you
37
// only get useful information from the custom_mode, which maps to
38
// the APM flight mode and has a well defined meaning in the
39
// ArduPlane documentation
40
if ((copter.pos_control != nullptr) && copter.pos_control->NE_is_active()) {
41
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
42
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
43
// APM does in any mode, as that is defined as "system finds its own goal
44
// positions", which APM does not currently do
45
}
46
47
// all modes except INITIALISING have some form of manual
48
// override if stick mixing is enabled
49
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
50
51
// we are armed if we are not initialising
52
if (copter.motors != nullptr && copter.motors->armed()) {
53
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
54
}
55
56
// indicate we have set a custom mode
57
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
58
59
return _base_mode;
60
}
61
62
uint32_t GCS_Copter::custom_mode() const
63
{
64
return (uint32_t)copter.flightmode->mode_number();
65
}
66
67
MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const
68
{
69
// set system as critical if any failsafe have triggered
70
if (copter.any_failsafe_triggered()) {
71
return MAV_STATE_CRITICAL;
72
}
73
74
if (copter.ap.land_complete) {
75
return MAV_STATE_STANDBY;
76
}
77
78
if (!copter.ap.initialised) {
79
return MAV_STATE_BOOT;
80
}
81
82
return MAV_STATE_ACTIVE;
83
}
84
85
86
void GCS_MAVLINK_Copter::send_attitude_target()
87
{
88
const Quaternion quat = copter.attitude_control->get_attitude_target_quat();
89
const Vector3f ang_vel = copter.attitude_control->get_attitude_target_ang_vel();
90
const float thrust = copter.attitude_control->get_throttle_in();
91
92
const float quat_out[4] {quat.q1, quat.q2, quat.q3, quat.q4};
93
94
// Note: When sending out the attitude_target info. we send out all of info. no matter the mavlink typemask
95
// This way we send out the maximum information that can be used by the sending control systems to adapt their generated trajectories
96
const uint16_t typemask = 0; // Ignore nothing
97
98
mavlink_msg_attitude_target_send(
99
chan,
100
AP_HAL::millis(), // time since boot (ms)
101
typemask, // Bitmask that tells the system what control dimensions should be ignored by the vehicle
102
quat_out, // Attitude quaternion [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], unit-length
103
ang_vel.x, // roll rate (rad/s)
104
ang_vel.y, // pitch rate (rad/s)
105
ang_vel.z, // yaw rate (rad/s)
106
thrust); // Collective thrust, normalized to 0 .. 1
107
}
108
109
void GCS_MAVLINK_Copter::send_position_target_global_int()
110
{
111
Location target;
112
if (!copter.flightmode->get_wp(target)) {
113
return;
114
}
115
116
// convert altitude frame to AMSL (this may use the terrain database)
117
if (!target.change_alt_frame(Location::AltFrame::ABSOLUTE)) {
118
return;
119
}
120
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;
121
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
122
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
123
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
124
mavlink_msg_position_target_global_int_send(
125
chan,
126
AP_HAL::millis(), // time_boot_ms
127
MAV_FRAME_GLOBAL, // targets are always global altitude
128
TYPE_MASK, // ignore everything except the x/y/z components
129
target.lat, // latitude as 1e7
130
target.lng, // longitude as 1e7
131
target.alt * 0.01f, // altitude is sent as a float
132
0.0f, // vx
133
0.0f, // vy
134
0.0f, // vz
135
0.0f, // afx
136
0.0f, // afy
137
0.0f, // afz
138
0.0f, // yaw
139
0.0f); // yaw_rate
140
}
141
142
void GCS_MAVLINK_Copter::send_position_target_local_ned()
143
{
144
#if MODE_GUIDED_ENABLED
145
if (!copter.flightmode->in_guided_mode()) {
146
return;
147
}
148
149
const ModeGuided::SubMode guided_mode = copter.mode_guided.submode();
150
Vector3f target_pos_ned_m;
151
Vector3f target_vel_ned_ms;
152
Vector3f target_accel_ned_mss;
153
uint16_t type_mask = 0;
154
155
switch (guided_mode) {
156
case ModeGuided::SubMode::Angle:
157
// we don't have a local target when in angle mode
158
return;
159
case ModeGuided::SubMode::TakeOff:
160
case ModeGuided::SubMode::WP:
161
case ModeGuided::SubMode::Pos:
162
type_mask = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
163
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
164
POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position
165
target_pos_ned_m = copter.mode_guided.get_target_pos_NED_m().tofloat();
166
break;
167
case ModeGuided::SubMode::PosVelAccel:
168
type_mask = POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position, velocity & acceleration
169
target_pos_ned_m = copter.mode_guided.get_target_pos_NED_m().tofloat();
170
target_vel_ned_ms = copter.mode_guided.get_target_vel_NED_ms();
171
target_accel_ned_mss = copter.mode_guided.get_target_accel_NED_mss();
172
break;
173
case ModeGuided::SubMode::VelAccel:
174
type_mask = POSITION_TARGET_TYPEMASK_X_IGNORE | POSITION_TARGET_TYPEMASK_Y_IGNORE | POSITION_TARGET_TYPEMASK_Z_IGNORE |
175
POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration
176
target_vel_ned_ms = copter.mode_guided.get_target_vel_NED_ms();
177
target_accel_ned_mss = copter.mode_guided.get_target_accel_NED_mss();
178
break;
179
case ModeGuided::SubMode::Accel:
180
type_mask = POSITION_TARGET_TYPEMASK_X_IGNORE | POSITION_TARGET_TYPEMASK_Y_IGNORE | POSITION_TARGET_TYPEMASK_Z_IGNORE |
181
POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
182
POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration
183
target_accel_ned_mss = copter.mode_guided.get_target_accel_NED_mss();
184
break;
185
}
186
187
mavlink_msg_position_target_local_ned_send(
188
chan,
189
AP_HAL::millis(), // time boot ms
190
MAV_FRAME_LOCAL_NED,
191
type_mask,
192
target_pos_ned_m.x, // x in metres
193
target_pos_ned_m.y, // y in metres
194
target_pos_ned_m.z, // z in metres NED frame
195
target_vel_ned_ms.x, // vx in m/s
196
target_vel_ned_ms.y, // vy in m/s
197
target_vel_ned_ms.z, // vz in m/s NED frame
198
target_accel_ned_mss.x, // afx in m/s/s
199
target_accel_ned_mss.y, // afy in m/s/s
200
target_accel_ned_mss.z, // afz in m/s/s NED frame
201
0.0f, // yaw
202
0.0f); // yaw_rate
203
#endif
204
}
205
206
void GCS_MAVLINK_Copter::send_nav_controller_output() const
207
{
208
if (!copter.ap.initialised) {
209
return;
210
}
211
const Vector3f &targets_rad = copter.attitude_control->get_att_target_euler_rad();
212
const Mode *flightmode = copter.flightmode;
213
mavlink_msg_nav_controller_output_send(
214
chan,
215
degrees(targets_rad.x),
216
degrees(targets_rad.y),
217
degrees(targets_rad.z),
218
flightmode->wp_bearing_deg(),
219
MIN(flightmode->wp_distance_m(), UINT16_MAX),
220
copter.pos_control->get_pos_error_D_m(),
221
0,
222
flightmode->crosstrack_error_m());
223
}
224
225
float GCS_MAVLINK_Copter::vfr_hud_airspeed() const
226
{
227
#if AP_AIRSPEED_ENABLED
228
// airspeed sensors are best. While the AHRS airspeed_estimate
229
// will use an airspeed sensor, that value is constrained by the
230
// ground speed. When reporting we should send the true airspeed
231
// value if possible:
232
if (copter.airspeed.enabled() && copter.airspeed.healthy()) {
233
return copter.airspeed.get_airspeed();
234
}
235
#endif
236
237
Vector3f airspeed_vec_bf;
238
if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
239
// we are running the EKF3 wind estimation code which can give
240
// us an airspeed estimate
241
return airspeed_vec_bf.length();
242
}
243
return AP::gps().ground_speed();
244
}
245
246
int16_t GCS_MAVLINK_Copter::vfr_hud_throttle() const
247
{
248
if (copter.motors == nullptr) {
249
return 0;
250
}
251
return (int16_t)(copter.motors->get_throttle() * 100);
252
}
253
254
/*
255
send PID tuning message
256
*/
257
void GCS_MAVLINK_Copter::send_pid_tuning()
258
{
259
static const PID_TUNING_AXIS axes[] = {
260
PID_TUNING_ROLL,
261
PID_TUNING_PITCH,
262
PID_TUNING_YAW,
263
PID_TUNING_ACCZ
264
};
265
for (uint8_t i=0; i<ARRAY_SIZE(axes); i++) {
266
if (!(copter.g.gcs_pid_mask & (1<<(axes[i]-1)))) {
267
continue;
268
}
269
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
270
return;
271
}
272
const AP_PIDInfo *pid_info = nullptr;
273
switch (axes[i]) {
274
case PID_TUNING_ROLL:
275
pid_info = &copter.attitude_control->get_rate_roll_pid().get_pid_info();
276
break;
277
case PID_TUNING_PITCH:
278
pid_info = &copter.attitude_control->get_rate_pitch_pid().get_pid_info();
279
break;
280
case PID_TUNING_YAW:
281
pid_info = &copter.attitude_control->get_rate_yaw_pid().get_pid_info();
282
break;
283
case PID_TUNING_ACCZ:
284
pid_info = &copter.pos_control->D_get_accel_pid().get_pid_info();
285
break;
286
default:
287
continue;
288
}
289
if (pid_info != nullptr) {
290
mavlink_msg_pid_tuning_send(chan,
291
axes[i],
292
pid_info->target,
293
pid_info->actual,
294
pid_info->FF,
295
pid_info->P,
296
pid_info->I,
297
pid_info->D,
298
pid_info->slew_rate,
299
pid_info->Dmod);
300
}
301
}
302
}
303
304
#if AP_WINCH_ENABLED
305
// send winch status message
306
void GCS_MAVLINK_Copter::send_winch_status() const
307
{
308
AP_Winch *winch = AP::winch();
309
if (winch == nullptr) {
310
return;
311
}
312
winch->send_status(*this);
313
}
314
#endif
315
316
bool GCS_Copter::vehicle_initialised() const {
317
return copter.ap.initialised;
318
}
319
320
// try to send a message, return false if it wasn't sent
321
bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
322
{
323
switch(id) {
324
325
case MSG_WIND:
326
CHECK_PAYLOAD_SIZE(WIND);
327
send_wind();
328
break;
329
330
case MSG_ADSB_VEHICLE: {
331
#if HAL_ADSB_ENABLED
332
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
333
copter.adsb.send_adsb_vehicle(chan);
334
#endif
335
#if AP_OAPATHPLANNER_ENABLED
336
AP_OADatabase *oadb = AP_OADatabase::get_singleton();
337
if (oadb != nullptr) {
338
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
339
uint16_t interval_ms = 0;
340
if (get_ap_message_interval(id, interval_ms)) {
341
oadb->send_adsb_vehicle(chan, interval_ms);
342
}
343
}
344
#endif
345
break;
346
}
347
348
default:
349
return GCS_MAVLINK::try_send_message(id);
350
}
351
return true;
352
}
353
354
355
MISSION_STATE GCS_MAVLINK_Copter::mission_state(const class AP_Mission &mission) const
356
{
357
if (copter.mode_auto.paused()) {
358
return MISSION_STATE_PAUSED;
359
}
360
return GCS_MAVLINK::mission_state(mission);
361
}
362
363
bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)
364
{
365
#if MODE_AUTO_ENABLED
366
return copter.mode_auto.do_guided(cmd);
367
#else
368
return false;
369
#endif
370
}
371
372
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
373
const mavlink_message_t &msg)
374
{
375
// we handle these messages here to avoid them being blocked by mavlink routing code
376
#if AP_ADSB_AVOIDANCE_ENABLED
377
if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) {
378
// optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source
379
copter.avoidance_adsb.handle_msg(msg);
380
}
381
#endif
382
GCS_MAVLINK::packetReceived(status, msg);
383
}
384
385
bool GCS_MAVLINK_Copter::params_ready() const
386
{
387
if (AP_BoardConfig::in_config_error()) {
388
// we may never have parameters "initialised" in this case
389
return true;
390
}
391
// if we have not yet initialised (including allocating the motors
392
// object) we drop this request. That prevents the GCS from getting
393
// a confusing parameter count during bootup
394
return copter.ap.initialised_params;
395
}
396
397
void GCS_MAVLINK_Copter::send_banner()
398
{
399
GCS_MAVLINK::send_banner();
400
if (copter.motors == nullptr) {
401
send_text(MAV_SEVERITY_INFO, "motors not allocated");
402
return;
403
}
404
char frame_and_type_string[30];
405
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
406
send_text(MAV_SEVERITY_INFO, "%s", frame_and_type_string);
407
}
408
409
void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)
410
{
411
copter.command_ack_counter++;
412
GCS_MAVLINK::handle_command_ack(msg);
413
}
414
415
/*
416
handle a LANDING_TARGET command. The timestamp has been jitter corrected
417
*/
418
void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
419
{
420
#if AC_PRECLAND_ENABLED
421
copter.precland.handle_msg(packet, timestamp_ms);
422
#endif
423
}
424
425
MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
426
{
427
if (packet.y == 1) {
428
// compassmot calibration
429
return copter.mavlink_compassmot(*this);
430
}
431
432
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
433
}
434
435
436
MAV_RESULT GCS_MAVLINK_Copter::handle_command_do_set_roi(const Location &roi_loc)
437
{
438
if (!roi_loc.check_latlng()) {
439
return MAV_RESULT_FAILED;
440
}
441
copter.flightmode->auto_yaw.set_roi(roi_loc);
442
return MAV_RESULT_ACCEPTED;
443
}
444
445
MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
446
{
447
// reject reboot if user has also specified they want the "Auto" ESC calibration on next reboot
448
if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) {
449
send_text(MAV_SEVERITY_CRITICAL, "Reboot rejected, ESC cal on reboot");
450
return MAV_RESULT_FAILED;
451
}
452
453
// call parent
454
return GCS_MAVLINK::handle_preflight_reboot(packet, msg);
455
}
456
457
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
458
{
459
#if MODE_GUIDED_ENABLED
460
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
461
if (!copter.flightmode->in_guided_mode() && !change_modes) {
462
return MAV_RESULT_DENIED;
463
}
464
465
// sanity check location
466
if (!check_latlng(packet.x, packet.y)) {
467
return MAV_RESULT_DENIED;
468
}
469
470
Location request_location;
471
if (!location_from_command_t(packet, request_location)) {
472
return MAV_RESULT_DENIED;
473
}
474
475
if (request_location.sanitize(copter.current_loc)) {
476
// if the location wasn't already sane don't load it
477
return MAV_RESULT_DENIED; // failed as the location is not valid
478
}
479
480
// we need to do this first, as we don't want to change the flight mode unless we can also set the target
481
if (!copter.mode_guided.set_destination(request_location, false, 0, false, 0)) {
482
return MAV_RESULT_FAILED;
483
}
484
485
if (!copter.flightmode->in_guided_mode()) {
486
if (!copter.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {
487
return MAV_RESULT_FAILED;
488
}
489
// the position won't have been loaded if we had to change the flight mode, so load it again
490
if (!copter.mode_guided.set_destination(request_location, false, 0, false, 0)) {
491
return MAV_RESULT_FAILED;
492
}
493
}
494
495
return MAV_RESULT_ACCEPTED;
496
#else
497
return MAV_RESULT_UNSUPPORTED;
498
#endif
499
}
500
501
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
502
{
503
switch(packet.command) {
504
505
case MAV_CMD_CONDITION_YAW:
506
return handle_MAV_CMD_CONDITION_YAW(packet);
507
508
case MAV_CMD_DO_CHANGE_SPEED:
509
return handle_MAV_CMD_DO_CHANGE_SPEED(packet);
510
511
case MAV_CMD_DO_REPOSITION:
512
return handle_command_int_do_reposition(packet);
513
514
// pause or resume an auto mission
515
case MAV_CMD_DO_PAUSE_CONTINUE:
516
return handle_command_pause_continue(packet);
517
518
case MAV_CMD_DO_MOTOR_TEST:
519
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
520
521
case MAV_CMD_NAV_TAKEOFF:
522
case MAV_CMD_NAV_VTOL_TAKEOFF:
523
return handle_MAV_CMD_NAV_TAKEOFF(packet);
524
525
#if HAL_PARACHUTE_ENABLED
526
case MAV_CMD_DO_PARACHUTE:
527
return handle_MAV_CMD_DO_PARACHUTE(packet);
528
#endif
529
530
#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
531
// Solo user presses pause button
532
case MAV_CMD_SOLO_BTN_PAUSE_CLICK:
533
return handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(packet);
534
// Solo user presses Fly button:
535
case MAV_CMD_SOLO_BTN_FLY_HOLD:
536
return handle_MAV_CMD_SOLO_BTN_FLY_HOLD(packet);
537
// Solo user holds down Fly button for a couple of seconds
538
case MAV_CMD_SOLO_BTN_FLY_CLICK:
539
return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet);
540
#endif
541
542
#if MODE_AUTO_ENABLED
543
case MAV_CMD_MISSION_START:
544
return handle_MAV_CMD_MISSION_START(packet);
545
#endif
546
547
#if AP_WINCH_ENABLED
548
case MAV_CMD_DO_WINCH:
549
return handle_MAV_CMD_DO_WINCH(packet);
550
#endif
551
552
case MAV_CMD_NAV_LOITER_UNLIM:
553
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
554
return MAV_RESULT_FAILED;
555
}
556
return MAV_RESULT_ACCEPTED;
557
558
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
559
if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) {
560
return MAV_RESULT_FAILED;
561
}
562
return MAV_RESULT_ACCEPTED;
563
564
case MAV_CMD_NAV_VTOL_LAND:
565
case MAV_CMD_NAV_LAND:
566
if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {
567
return MAV_RESULT_FAILED;
568
}
569
return MAV_RESULT_ACCEPTED;
570
571
#if MODE_AUTO_ENABLED
572
case MAV_CMD_DO_RETURN_PATH_START:
573
if (copter.mode_auto.return_path_start_auto_RTL(ModeReason::GCS_COMMAND)) {
574
return MAV_RESULT_ACCEPTED;
575
}
576
return MAV_RESULT_FAILED;
577
578
case MAV_CMD_DO_LAND_START:
579
if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {
580
return MAV_RESULT_ACCEPTED;
581
}
582
return MAV_RESULT_FAILED;
583
#endif
584
585
default:
586
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
587
}
588
}
589
590
#if HAL_MOUNT_ENABLED
591
MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
592
{
593
switch (packet.command) {
594
case MAV_CMD_DO_MOUNT_CONTROL:
595
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
596
if (((MAV_MOUNT_MODE)packet.z == MAV_MOUNT_MODE_MAVLINK_TARGETING) &&
597
(copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&
598
!copter.camera_mount.has_pan_control()) {
599
// Per the handler in AP_Mount, DO_MOUNT_CONTROL yaw angle is in body frame, which is
600
// equivalent to an offset to the current yaw demand.
601
copter.flightmode->auto_yaw.set_yaw_angle_offset_deg(packet.param3);
602
}
603
break;
604
default:
605
break;
606
}
607
return GCS_MAVLINK::handle_command_mount(packet, msg);
608
}
609
#endif
610
611
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet)
612
{
613
if (packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) {
614
return MAV_RESULT_DENIED; // meaning some parameters are bad
615
}
616
617
// param3 : horizontal navigation by pilot acceptable
618
// param4 : yaw angle (not supported)
619
// param5 : latitude (not supported)
620
// param6 : longitude (not supported)
621
// param7 : altitude [metres]
622
623
float takeoff_alt_m = packet.z;
624
625
if (!copter.flightmode->do_user_takeoff_U_m(takeoff_alt_m, is_zero(packet.param3))) {
626
return MAV_RESULT_FAILED;
627
}
628
return MAV_RESULT_ACCEPTED;
629
}
630
631
#if AP_MAVLINK_COMMAND_LONG_ENABLED
632
bool GCS_MAVLINK_Copter::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const
633
{
634
if (packet_command == MAV_CMD_NAV_TAKEOFF ||
635
packet_command == MAV_CMD_NAV_VTOL_TAKEOFF) {
636
frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
637
return true;
638
}
639
return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);
640
}
641
#endif
642
643
644
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)
645
{
646
// param1 : target angle [0-360]
647
// param2 : speed during change [deg per second]
648
// param3 : direction (-1:ccw, +1:cw)
649
// param4 : relative offset (1) or absolute angle (0)
650
if ((packet.param1 >= 0.0f) &&
651
(packet.param1 <= 360.0f) &&
652
(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {
653
copter.flightmode->auto_yaw.set_fixed_yaw_rad(
654
radians(packet.param1),
655
radians(packet.param2),
656
(int8_t)packet.param3,
657
is_positive(packet.param4));
658
return MAV_RESULT_ACCEPTED;
659
}
660
return MAV_RESULT_FAILED;
661
}
662
663
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
664
{
665
if (!is_positive(packet.param2)) {
666
// Target speed must be larger than zero
667
return MAV_RESULT_DENIED;
668
}
669
670
const float speed_ms = packet.param2;
671
672
bool success = false;
673
switch (SPEED_TYPE(packet.param1)) {
674
case SPEED_TYPE_ENUM_END:
675
return MAV_RESULT_DENIED;
676
677
case SPEED_TYPE_AIRSPEED: // Airspeed is treated as ground speed for GCS compatibility
678
case SPEED_TYPE_GROUNDSPEED:
679
success = copter.flightmode->set_speed_NE_ms(speed_ms);
680
break;
681
682
case SPEED_TYPE_CLIMB_SPEED:
683
success = copter.flightmode->set_speed_up_ms(speed_ms);
684
break;
685
686
case SPEED_TYPE_DESCENT_SPEED:
687
success = copter.flightmode->set_speed_down_ms(speed_ms);
688
break;
689
}
690
691
return success ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
692
}
693
694
#if MODE_AUTO_ENABLED
695
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
696
{
697
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
698
// first-item/last item not supported
699
return MAV_RESULT_DENIED;
700
}
701
if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
702
copter.set_auto_armed(true);
703
if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {
704
copter.mode_auto.mission.start_or_resume();
705
}
706
return MAV_RESULT_ACCEPTED;
707
}
708
return MAV_RESULT_FAILED;
709
}
710
#endif
711
712
713
714
#if HAL_PARACHUTE_ENABLED
715
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
716
{
717
// configure or release parachute
718
switch ((uint16_t)packet.param1) {
719
case PARACHUTE_DISABLE:
720
copter.parachute.enabled(false);
721
return MAV_RESULT_ACCEPTED;
722
case PARACHUTE_ENABLE:
723
copter.parachute.enabled(true);
724
return MAV_RESULT_ACCEPTED;
725
case PARACHUTE_RELEASE:
726
// treat as a manual release which performs some additional check of altitude
727
copter.parachute_manual_release();
728
return MAV_RESULT_ACCEPTED;
729
}
730
return MAV_RESULT_FAILED;
731
}
732
#endif
733
734
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
735
{
736
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
737
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
738
// param3 : throttle (range depends upon param2)
739
// param4 : timeout (in seconds)
740
// param5 : num_motors (in sequence)
741
// param6 : motor test order
742
return copter.mavlink_motor_test_start(*this,
743
(uint8_t)packet.param1,
744
(uint8_t)packet.param2,
745
packet.param3,
746
packet.param4,
747
(uint8_t)packet.x);
748
}
749
750
#if AP_WINCH_ENABLED
751
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet)
752
{
753
// param1 : winch number (ignored)
754
// param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum.
755
if (!copter.g2.winch.enabled()) {
756
return MAV_RESULT_FAILED;
757
}
758
switch ((uint8_t)packet.param2) {
759
case WINCH_RELAXED:
760
copter.g2.winch.relax();
761
return MAV_RESULT_ACCEPTED;
762
case WINCH_RELATIVE_LENGTH_CONTROL: {
763
copter.g2.winch.release_length(packet.param3);
764
return MAV_RESULT_ACCEPTED;
765
}
766
case WINCH_RATE_CONTROL:
767
copter.g2.winch.set_desired_rate(packet.param4);
768
return MAV_RESULT_ACCEPTED;
769
default:
770
break;
771
}
772
return MAV_RESULT_FAILED;
773
}
774
#endif // AP_WINCH_ENABLED
775
776
#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
777
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet)
778
{
779
if (copter.failsafe.radio) {
780
return MAV_RESULT_ACCEPTED;
781
}
782
783
// set mode to Loiter or fall back to AltHold
784
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
785
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);
786
}
787
return MAV_RESULT_ACCEPTED;
788
}
789
790
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet)
791
{
792
if (copter.failsafe.radio) {
793
return MAV_RESULT_ACCEPTED;
794
}
795
796
if (!copter.motors->armed()) {
797
// if disarmed, arm motors
798
copter.arming.arm(AP_Arming::Method::MAVLINK);
799
} else if (copter.ap.land_complete) {
800
// if armed and landed, takeoff
801
if (copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
802
copter.flightmode->do_user_takeoff_U_m(packet.param1, true);
803
}
804
} else {
805
// if flying, land
806
copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND);
807
}
808
return MAV_RESULT_ACCEPTED;
809
}
810
811
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet)
812
{
813
if (copter.failsafe.radio) {
814
return MAV_RESULT_ACCEPTED;
815
}
816
817
if (copter.motors->armed()) {
818
if (copter.ap.land_complete) {
819
// if landed, disarm motors
820
copter.arming.disarm(AP_Arming::Method::SOLOPAUSEWHENLANDED);
821
} else {
822
// assume that shots modes are all done in guided.
823
// NOTE: this may need to change if we add a non-guided shot mode
824
bool shot_mode = (!is_zero(packet.param1) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS));
825
826
if (!shot_mode) {
827
#if MODE_BRAKE_ENABLED
828
if (copter.set_mode(Mode::Number::BRAKE, ModeReason::GCS_COMMAND)) {
829
copter.mode_brake.timeout_to_loiter_ms(2500);
830
} else {
831
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);
832
}
833
#else
834
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);
835
#endif
836
} else {
837
// SoloLink is expected to handle pause in shots
838
}
839
}
840
}
841
return MAV_RESULT_ACCEPTED;
842
}
843
#endif // AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
844
845
MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet)
846
{
847
// requested pause
848
if ((uint8_t) packet.param1 == 0) {
849
if (copter.flightmode->pause()) {
850
return MAV_RESULT_ACCEPTED;
851
}
852
send_text(MAV_SEVERITY_INFO, "Failed to pause");
853
return MAV_RESULT_FAILED;
854
}
855
856
// requested resume
857
if ((uint8_t) packet.param1 == 1) {
858
if (copter.flightmode->resume()) {
859
return MAV_RESULT_ACCEPTED;
860
}
861
send_text(MAV_SEVERITY_INFO, "Failed to resume");
862
return MAV_RESULT_FAILED;
863
}
864
return MAV_RESULT_DENIED;
865
}
866
867
// this is called on receipt of a MANUAL_CONTROL packet and is
868
// expected to call manual_override to override RC input on desired
869
// axes.
870
void GCS_MAVLINK_Copter::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
871
{
872
if (packet.z < 0) { // Copter doesn't do negative thrust
873
return;
874
}
875
876
manual_override(copter.channel_roll, packet.y, 1000, 2000, tnow);
877
manual_override(copter.channel_pitch, packet.x, 1000, 2000, tnow, true);
878
manual_override(copter.channel_throttle, packet.z, 0, 1000, tnow);
879
manual_override(copter.channel_yaw, packet.r, 1000, 2000, tnow);
880
}
881
882
// sanity check velocity or acceleration vector components are numbers
883
// (e.g. not NaN) and below 1000. vec argument units are in meters/second or
884
// metres/second/second
885
bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const
886
{
887
for (uint8_t i=0; i<3; i++) {
888
// consider velocity invalid if any component nan or >1000(m/s or m/s/s)
889
if (isnan(vec[i]) || fabsf(vec[i]) > 1000) {
890
return false;
891
}
892
}
893
return true;
894
}
895
896
#if MODE_GUIDED_ENABLED
897
// for mavlink SET_POSITION_TARGET messages
898
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE =
899
POSITION_TARGET_TYPEMASK_X_IGNORE |
900
POSITION_TARGET_TYPEMASK_Y_IGNORE |
901
POSITION_TARGET_TYPEMASK_Z_IGNORE;
902
903
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE =
904
POSITION_TARGET_TYPEMASK_VX_IGNORE |
905
POSITION_TARGET_TYPEMASK_VY_IGNORE |
906
POSITION_TARGET_TYPEMASK_VZ_IGNORE;
907
908
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE =
909
POSITION_TARGET_TYPEMASK_AX_IGNORE |
910
POSITION_TARGET_TYPEMASK_AY_IGNORE |
911
POSITION_TARGET_TYPEMASK_AZ_IGNORE;
912
913
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE =
914
POSITION_TARGET_TYPEMASK_YAW_IGNORE;
915
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE =
916
POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;
917
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_FORCE_SET =
918
POSITION_TARGET_TYPEMASK_FORCE_SET;
919
#endif
920
921
#if MODE_GUIDED_ENABLED
922
void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_message_t &msg)
923
{
924
// decode packet
925
mavlink_set_attitude_target_t packet;
926
mavlink_msg_set_attitude_target_decode(&msg, &packet);
927
928
// exit if vehicle is not in Guided mode or Auto-Guided mode
929
if (!copter.flightmode->in_guided_mode()) {
930
return;
931
}
932
933
const bool roll_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
934
const bool pitch_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE;
935
const bool yaw_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE;
936
const bool throttle_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE;
937
const bool attitude_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE;
938
939
// ensure thrust field is not ignored
940
if (throttle_ignore) {
941
// The throttle input is not defined
942
copter.mode_guided.hold_position();
943
return;
944
}
945
946
Quaternion attitude_quat;
947
if (attitude_ignore) {
948
attitude_quat.zero();
949
} else {
950
attitude_quat = Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]);
951
952
// Do not accept the attitude_quaternion
953
// if its magnitude is not close to unit length +/- 1E-3
954
// this limit is somewhat greater than sqrt(FLT_EPSL)
955
if (!attitude_quat.is_unit_length()) {
956
// The attitude quaternion is ill-defined
957
copter.mode_guided.hold_position();
958
return;
959
}
960
}
961
962
Vector3f ang_vel_body;
963
if (!roll_rate_ignore && !pitch_rate_ignore && !yaw_rate_ignore) {
964
ang_vel_body.x = packet.body_roll_rate;
965
ang_vel_body.y = packet.body_pitch_rate;
966
ang_vel_body.z = packet.body_yaw_rate;
967
} else if (!(roll_rate_ignore && pitch_rate_ignore && yaw_rate_ignore)) {
968
// The body rates are ill-defined
969
copter.mode_guided.hold_position();
970
return;
971
}
972
973
// check if the message's thrust field should be interpreted as a climb rate or as thrust
974
const bool use_thrust = copter.mode_guided.set_attitude_target_provides_thrust();
975
976
float climb_rate_ms_or_thrust;
977
if (use_thrust) {
978
// interpret thrust as thrust
979
climb_rate_ms_or_thrust = constrain_float(packet.thrust, -1.0f, 1.0f);
980
} else {
981
// convert thrust to climb rate
982
packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);
983
if (is_equal(packet.thrust, 0.5f)) {
984
climb_rate_ms_or_thrust = 0.0f;
985
} else if (packet.thrust > 0.5f) {
986
// climb at up to WPNAV_SPEED_UP
987
climb_rate_ms_or_thrust = (packet.thrust - 0.5f) * 2.0f * copter.wp_nav->get_default_speed_up_ms();
988
} else {
989
// descend at up to WPNAV_SPEED_DN
990
climb_rate_ms_or_thrust = (0.5f - packet.thrust) * 2.0f * -copter.wp_nav->get_default_speed_down_ms();
991
}
992
}
993
994
copter.mode_guided.set_angle(attitude_quat, ang_vel_body,
995
climb_rate_ms_or_thrust, use_thrust);
996
}
997
998
void GCS_MAVLINK_Copter::handle_message_set_position_target_local_ned(const mavlink_message_t &msg)
999
{
1000
// decode packet
1001
mavlink_set_position_target_local_ned_t packet;
1002
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
1003
1004
// exit if vehicle is not in Guided mode or Auto-Guided mode
1005
if (!copter.flightmode->in_guided_mode()) {
1006
return;
1007
}
1008
1009
// check for supported coordinate frames
1010
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
1011
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
1012
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
1013
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
1014
// unsupported coordinate frame
1015
copter.mode_guided.hold_position();
1016
return;
1017
}
1018
1019
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
1020
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
1021
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
1022
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
1023
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
1024
bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;
1025
1026
// Force inputs are not supported
1027
// Do not accept command if force_set is true and acc_ignore is false
1028
if (force_set && !acc_ignore) {
1029
copter.mode_guided.hold_position();
1030
return;
1031
}
1032
1033
// prepare position
1034
Vector3p pos_ned_m;
1035
if (!pos_ignore) {
1036
// convert to m
1037
pos_ned_m = Vector3p{packet.x, packet.y, packet.z};
1038
// rotate to body-frame if necessary
1039
if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||
1040
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
1041
pos_ned_m.xy() = copter.ahrs.body_to_earth2D_p(pos_ned_m.xy());
1042
}
1043
// add body offset if necessary
1044
if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||
1045
packet.coordinate_frame == MAV_FRAME_BODY_NED ||
1046
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
1047
Vector3p rel_pos_ned_m;
1048
if (!AP::ahrs().get_relative_position_NED_origin(rel_pos_ned_m)) {
1049
// need position estimate to calculate target position
1050
copter.mode_guided.hold_position();
1051
return;
1052
}
1053
pos_ned_m += rel_pos_ned_m;
1054
}
1055
}
1056
1057
// prepare velocity
1058
Vector3f vel_ned_ms;
1059
if (!vel_ignore) {
1060
vel_ned_ms = Vector3f{packet.vx, packet.vy, packet.vz};
1061
if (!sane_vel_or_acc_vector(vel_ned_ms)) {
1062
// velocity vector contains NaN or Inf
1063
copter.mode_guided.hold_position();
1064
return;
1065
}
1066
// rotate to body-frame if necessary
1067
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
1068
vel_ned_ms.xy() = copter.ahrs.body_to_earth2D(vel_ned_ms.xy());
1069
}
1070
}
1071
1072
// prepare acceleration
1073
Vector3f accel_ned_mss;
1074
if (!acc_ignore) {
1075
accel_ned_mss = Vector3f{packet.afx, packet.afy, packet.afz};
1076
// rotate to body-frame if necessary
1077
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
1078
accel_ned_mss.xy() = copter.ahrs.body_to_earth2D(accel_ned_mss.xy());
1079
}
1080
}
1081
1082
// prepare yaw
1083
float yaw_rad = 0.0f;
1084
bool yaw_relative = false;
1085
float yaw_rate_rads = 0.0f;
1086
if (!yaw_ignore) {
1087
yaw_rad = packet.yaw;
1088
yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED;
1089
}
1090
if (!yaw_rate_ignore) {
1091
yaw_rate_rads = packet.yaw_rate;
1092
}
1093
1094
// send request
1095
if (!pos_ignore && !vel_ignore) {
1096
copter.mode_guided.set_pos_vel_accel_NED_m(pos_ned_m, vel_ned_ms, accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative);
1097
} else if (pos_ignore && !vel_ignore) {
1098
copter.mode_guided.set_vel_accel_NED_m(vel_ned_ms, accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative);
1099
} else if (pos_ignore && vel_ignore && !acc_ignore) {
1100
copter.mode_guided.set_accel_NED_mss(accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative);
1101
} else if (!pos_ignore && vel_ignore && acc_ignore) {
1102
copter.mode_guided.set_pos_NED_m(pos_ned_m, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative, false);
1103
} else {
1104
// unsupported combination of position/velocity/acceleration flags
1105
copter.mode_guided.hold_position();
1106
}
1107
}
1108
1109
void GCS_MAVLINK_Copter::handle_message_set_position_target_global_int(const mavlink_message_t &msg)
1110
{
1111
// decode packet
1112
mavlink_set_position_target_global_int_t packet;
1113
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
1114
1115
// exit if vehicle is not in Guided mode or Auto-Guided mode
1116
if (!copter.flightmode->in_guided_mode()) {
1117
return;
1118
}
1119
1120
// todo: do we need to check for supported coordinate frames
1121
1122
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
1123
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
1124
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
1125
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
1126
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
1127
bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;
1128
1129
// Force inputs are not supported
1130
// Do not accept command if force_set is true and acc_ignore is false
1131
if (force_set && !acc_ignore) {
1132
copter.mode_guided.hold_position();
1133
return;
1134
}
1135
1136
// extract location from message
1137
Location loc;
1138
if (!pos_ignore) {
1139
// sanity check location
1140
if (!check_latlng(packet.lat_int, packet.lon_int)) {
1141
// invalid latitude or longitude
1142
copter.mode_guided.hold_position();
1143
return;
1144
}
1145
Location::AltFrame frame;
1146
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {
1147
// unknown coordinate frame
1148
copter.mode_guided.hold_position();
1149
return;
1150
}
1151
loc = {packet.lat_int, packet.lon_int, int32_t(packet.alt*100), frame};
1152
}
1153
1154
// prepare velocity
1155
Vector3f vel_ned_ms;
1156
if (!vel_ignore) {
1157
vel_ned_ms = Vector3f{packet.vx, packet.vy, packet.vz};
1158
if (!sane_vel_or_acc_vector(vel_ned_ms)) {
1159
// velocity vector contains NaN or Inf
1160
copter.mode_guided.hold_position();
1161
return;
1162
}
1163
}
1164
1165
// prepare acceleration
1166
Vector3f accel_ned_mss;
1167
if (!acc_ignore) {
1168
accel_ned_mss = Vector3f{packet.afx, packet.afy, packet.afz};
1169
}
1170
1171
// prepare yaw
1172
float yaw_rad = 0.0f;
1173
float yaw_rate_rads = 0.0f;
1174
if (!yaw_ignore) {
1175
yaw_rad = packet.yaw;
1176
}
1177
if (!yaw_rate_ignore) {
1178
yaw_rate_rads = packet.yaw_rate;
1179
}
1180
1181
// send targets to the appropriate guided mode controller
1182
if (!pos_ignore && !vel_ignore) {
1183
// convert Location to vector from ekf origin for posvel controller
1184
if (loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {
1185
// posvel controller does not support alt-above-terrain
1186
copter.mode_guided.hold_position();
1187
return;
1188
}
1189
Vector3p pos_ned_m;
1190
if (!loc.get_vector_from_origin_NED_m(pos_ned_m)) {
1191
// could not convert location to NED position
1192
copter.mode_guided.hold_position();
1193
return;
1194
}
1195
copter.mode_guided.set_pos_vel_NED_m(pos_ned_m, vel_ned_ms, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);
1196
} else if (pos_ignore && !vel_ignore) {
1197
copter.mode_guided.set_vel_accel_NED_m(vel_ned_ms, accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);
1198
} else if (pos_ignore && vel_ignore && !acc_ignore) {
1199
copter.mode_guided.set_accel_NED_mss(accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);
1200
} else if (!pos_ignore && vel_ignore && acc_ignore) {
1201
copter.mode_guided.set_destination(loc, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);
1202
} else {
1203
// unsupported combination of position/velocity/acceleration flags
1204
copter.mode_guided.hold_position();
1205
}
1206
}
1207
#endif // MODE_GUIDED_ENABLED
1208
1209
void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
1210
{
1211
1212
switch (msg.msgid) {
1213
#if MODE_GUIDED_ENABLED
1214
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
1215
handle_message_set_attitude_target(msg);
1216
break;
1217
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
1218
handle_message_set_position_target_local_ned(msg);
1219
break;
1220
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
1221
handle_message_set_position_target_global_int(msg);
1222
break;
1223
#endif
1224
1225
#if TOY_MODE_ENABLED
1226
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
1227
copter.g2.toy_mode.handle_message(msg);
1228
break;
1229
#endif
1230
default:
1231
GCS_MAVLINK::handle_message(msg);
1232
break;
1233
}
1234
}
1235
1236
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {
1237
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
1238
if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {
1239
return MAV_RESULT_ACCEPTED;
1240
}
1241
#endif
1242
if (packet.param1 > 0.5f) {
1243
copter.arming.disarm(AP_Arming::Method::TERMINATION);
1244
return MAV_RESULT_ACCEPTED;
1245
}
1246
1247
return MAV_RESULT_FAILED;
1248
}
1249
1250
float GCS_MAVLINK_Copter::vfr_hud_alt() const
1251
{
1252
if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {
1253
// compatibility option for older mavlink-aware devices that
1254
// assume Copter returns a relative altitude in VFR_HUD.alt
1255
return copter.current_loc.alt * 0.01f;
1256
}
1257
return GCS_MAVLINK::vfr_hud_alt();
1258
}
1259
1260
uint64_t GCS_MAVLINK_Copter::capabilities() const
1261
{
1262
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
1263
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
1264
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
1265
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
1266
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
1267
MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
1268
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
1269
#if AP_TERRAIN_AVAILABLE
1270
(copter.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
1271
#endif
1272
GCS_MAVLINK::capabilities());
1273
}
1274
1275
MAV_LANDED_STATE GCS_MAVLINK_Copter::landed_state() const
1276
{
1277
if (copter.ap.land_complete) {
1278
return MAV_LANDED_STATE_ON_GROUND;
1279
}
1280
if (copter.flightmode->is_landing()) {
1281
return MAV_LANDED_STATE_LANDING;
1282
}
1283
if (copter.flightmode->is_taking_off()) {
1284
return MAV_LANDED_STATE_TAKEOFF;
1285
}
1286
return MAV_LANDED_STATE_IN_AIR;
1287
}
1288
1289
void GCS_MAVLINK_Copter::send_wind() const
1290
{
1291
Vector3f airspeed_vec_bf;
1292
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
1293
// if we don't have an airspeed estimate then we don't have a
1294
// valid wind estimate on copters
1295
return;
1296
}
1297
const Vector3f wind = AP::ahrs().wind_estimate();
1298
mavlink_msg_wind_send(
1299
chan,
1300
degrees(atan2f(-wind.y, -wind.x)),
1301
wind.length(),
1302
wind.z);
1303
}
1304
1305
#if HAL_HIGH_LATENCY2_ENABLED
1306
int16_t GCS_MAVLINK_Copter::high_latency_target_altitude() const
1307
{
1308
AP_AHRS &ahrs = AP::ahrs();
1309
Location global_position_current;
1310
UNUSED_RESULT(ahrs.get_location(global_position_current));
1311
1312
//return units are m
1313
if (copter.ap.initialised) {
1314
return global_position_current.alt * 0.01 - copter.pos_control->get_pos_error_D_m();
1315
}
1316
return 0;
1317
1318
}
1319
1320
uint8_t GCS_MAVLINK_Copter::high_latency_tgt_heading() const
1321
{
1322
if (copter.ap.initialised) {
1323
// return units are deg/2
1324
const Mode *flightmode = copter.flightmode;
1325
// need to convert -180->180 to 0->360/2
1326
return wrap_360(flightmode->wp_bearing_deg()) * 0.5;
1327
}
1328
return 0;
1329
}
1330
1331
uint16_t GCS_MAVLINK_Copter::high_latency_tgt_dist() const
1332
{
1333
if (copter.ap.initialised) {
1334
// return units are dm
1335
const Mode *flightmode = copter.flightmode;
1336
return MIN(flightmode->wp_distance_m(), UINT16_MAX) / 10;
1337
}
1338
return 0;
1339
}
1340
1341
uint8_t GCS_MAVLINK_Copter::high_latency_tgt_airspeed() const
1342
{
1343
if (copter.ap.initialised) {
1344
// return units are m/s*5
1345
return MIN(copter.pos_control->get_vel_target_NED_ms().length() * 5.0, UINT8_MAX);
1346
}
1347
return 0;
1348
}
1349
1350
uint8_t GCS_MAVLINK_Copter::high_latency_wind_speed() const
1351
{
1352
Vector3f airspeed_vec_bf;
1353
Vector3f wind;
1354
// return units are m/s*5
1355
if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
1356
wind = AP::ahrs().wind_estimate();
1357
return wind.length() * 5;
1358
}
1359
return 0;
1360
}
1361
1362
uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const
1363
{
1364
Vector3f airspeed_vec_bf;
1365
Vector3f wind;
1366
// return units are deg/2
1367
if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
1368
wind = AP::ahrs().wind_estimate();
1369
// need to convert -180->180 to 0->360/2
1370
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
1371
}
1372
return 0;
1373
}
1374
#endif // HAL_HIGH_LATENCY2_ENABLED
1375
1376
// Send the mode with the given index (not mode number!) return the total number of modes
1377
// Index starts at 1
1378
uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const
1379
{
1380
const Mode* modes[] {
1381
#if MODE_AUTO_ENABLED
1382
&copter.mode_auto, // This auto is actually auto RTL!
1383
&copter.mode_auto, // This one is really is auto!
1384
#endif
1385
#if MODE_ACRO_ENABLED
1386
&copter.mode_acro,
1387
#endif
1388
&copter.mode_stabilize,
1389
&copter.mode_althold,
1390
#if MODE_CIRCLE_ENABLED
1391
&copter.mode_circle,
1392
#endif
1393
#if MODE_LOITER_ENABLED
1394
&copter.mode_loiter,
1395
#endif
1396
#if MODE_GUIDED_ENABLED
1397
&copter.mode_guided,
1398
#endif
1399
&copter.mode_land,
1400
#if MODE_RTL_ENABLED
1401
&copter.mode_rtl,
1402
#endif
1403
#if MODE_DRIFT_ENABLED
1404
&copter.mode_drift,
1405
#endif
1406
#if MODE_SPORT_ENABLED
1407
&copter.mode_sport,
1408
#endif
1409
#if MODE_FLIP_ENABLED
1410
&copter.mode_flip,
1411
#endif
1412
#if AUTOTUNE_ENABLED
1413
&copter.mode_autotune,
1414
#endif
1415
#if MODE_POSHOLD_ENABLED
1416
&copter.mode_poshold,
1417
#endif
1418
#if MODE_BRAKE_ENABLED
1419
&copter.mode_brake,
1420
#endif
1421
#if MODE_THROW_ENABLED
1422
&copter.mode_throw,
1423
#endif
1424
#if AP_ADSB_AVOIDANCE_ENABLED
1425
&copter.mode_avoid_adsb,
1426
#endif
1427
#if MODE_GUIDED_NOGPS_ENABLED
1428
&copter.mode_guided_nogps,
1429
#endif
1430
#if MODE_SMARTRTL_ENABLED
1431
&copter.mode_smartrtl,
1432
#endif
1433
#if MODE_FLOWHOLD_ENABLED
1434
(Mode*)copter.g2.mode_flowhold_ptr,
1435
#endif
1436
#if MODE_FOLLOW_ENABLED
1437
&copter.mode_follow,
1438
#endif
1439
#if MODE_ZIGZAG_ENABLED
1440
&copter.mode_zigzag,
1441
#endif
1442
#if MODE_SYSTEMID_ENABLED
1443
(Mode *)copter.g2.mode_systemid_ptr,
1444
#endif
1445
#if MODE_AUTOROTATE_ENABLED
1446
&copter.mode_autorotate,
1447
#endif
1448
#if MODE_TURTLE_ENABLED
1449
&copter.mode_turtle,
1450
#endif
1451
};
1452
1453
const uint8_t base_mode_count = ARRAY_SIZE(modes);
1454
uint8_t mode_count = base_mode_count;
1455
1456
#if AP_SCRIPTING_ENABLED
1457
for (uint8_t i = 0; i < ARRAY_SIZE(copter.mode_guided_custom); i++) {
1458
if (copter.mode_guided_custom[i] != nullptr) {
1459
mode_count += 1;
1460
}
1461
}
1462
#endif
1463
1464
// Convert to zero indexed
1465
const uint8_t index_zero = index - 1;
1466
if (index_zero >= mode_count) {
1467
// Mode does not exist!?
1468
return mode_count;
1469
}
1470
1471
// Ask the mode for its name and number
1472
const char* name;
1473
uint8_t mode_number;
1474
1475
if (index_zero < base_mode_count) {
1476
name = modes[index_zero]->name();
1477
mode_number = (uint8_t)modes[index_zero]->mode_number();
1478
1479
} else {
1480
#if AP_SCRIPTING_ENABLED
1481
const uint8_t custom_index = index_zero - base_mode_count;
1482
if (copter.mode_guided_custom[custom_index] == nullptr) {
1483
// Invalid index, should not happen
1484
return mode_count;
1485
}
1486
name = copter.mode_guided_custom[custom_index]->name();
1487
mode_number = (uint8_t)copter.mode_guided_custom[custom_index]->mode_number();
1488
#else
1489
// Should not endup here
1490
return mode_count;
1491
#endif
1492
}
1493
1494
#if MODE_AUTO_ENABLED
1495
// Auto RTL is odd
1496
// Have to deal with is separately because its number and name can change depending on if were in it or not
1497
if (index_zero == 0) {
1498
mode_number = (uint8_t)Mode::Number::AUTO_RTL;
1499
name = "Auto RTL";
1500
1501
} else if (index_zero == 1) {
1502
mode_number = (uint8_t)Mode::Number::AUTO;
1503
name = "Auto";
1504
1505
}
1506
#endif
1507
1508
mavlink_msg_available_modes_send(
1509
chan,
1510
mode_count,
1511
index,
1512
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
1513
mode_number,
1514
0, // MAV_MODE_PROPERTY bitmask
1515
name
1516
);
1517
1518
return mode_count;
1519
}
1520
1521