Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/GCS_MAVLink_Plane.cpp
9659 views
1
#include "GCS_MAVLink_Plane.h"
2
3
#include "Plane.h"
4
#include <AP_RPM/AP_RPM_config.h>
5
#include <AP_Airspeed/AP_Airspeed_config.h>
6
#include <AP_EFI/AP_EFI_config.h>
7
8
MAV_TYPE GCS_Plane::frame_type() const
9
{
10
#if HAL_QUADPLANE_ENABLED
11
return plane.quadplane.get_mav_type();
12
#else
13
return MAV_TYPE_FIXED_WING;
14
#endif
15
}
16
17
uint8_t GCS_MAVLINK_Plane::base_mode() const
18
{
19
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
20
21
// work out the base_mode. This value is not very useful
22
// for APM, but we calculate it as best we can so a generic
23
// MAVLink enabled ground station can work out something about
24
// what the MAV is up to. The actual bit values are highly
25
// ambiguous for most of the APM flight modes. In practice, you
26
// only get useful information from the custom_mode, which maps to
27
// the APM flight mode and has a well defined meaning in the
28
// ArduPlane documentation
29
switch (plane.control_mode->mode_number()) {
30
case Mode::Number::MANUAL:
31
case Mode::Number::TRAINING:
32
case Mode::Number::ACRO:
33
#if HAL_QUADPLANE_ENABLED
34
case Mode::Number::QACRO:
35
_base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
36
break;
37
#endif
38
case Mode::Number::STABILIZE:
39
case Mode::Number::FLY_BY_WIRE_A:
40
case Mode::Number::AUTOTUNE:
41
case Mode::Number::FLY_BY_WIRE_B:
42
#if HAL_QUADPLANE_ENABLED
43
case Mode::Number::QSTABILIZE:
44
case Mode::Number::QHOVER:
45
case Mode::Number::QLOITER:
46
case Mode::Number::QLAND:
47
#if QAUTOTUNE_ENABLED
48
case Mode::Number::QAUTOTUNE:
49
#endif
50
#endif // HAL_QUADPLANE_ENABLED
51
case Mode::Number::CRUISE:
52
_base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
53
break;
54
case Mode::Number::AUTO:
55
case Mode::Number::RTL:
56
case Mode::Number::LOITER:
57
case Mode::Number::THERMAL:
58
case Mode::Number::AVOID_ADSB:
59
case Mode::Number::GUIDED:
60
case Mode::Number::CIRCLE:
61
case Mode::Number::TAKEOFF:
62
#if MODE_AUTOLAND_ENABLED
63
case Mode::Number::AUTOLAND:
64
#endif
65
#if HAL_QUADPLANE_ENABLED
66
case Mode::Number::QRTL:
67
case Mode::Number::LOITER_ALT_QLAND:
68
#endif
69
_base_mode = MAV_MODE_FLAG_GUIDED_ENABLED |
70
MAV_MODE_FLAG_STABILIZE_ENABLED;
71
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
72
// APM does in any mode, as that is defined as "system finds its own goal
73
// positions", which APM does not currently do
74
break;
75
case Mode::Number::INITIALISING:
76
break;
77
}
78
79
if (!plane.training_manual_pitch || !plane.training_manual_roll) {
80
_base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
81
}
82
83
if (plane.control_mode != &plane.mode_manual && plane.control_mode != &plane.mode_initializing) {
84
// stabiliser of some form is enabled
85
_base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
86
}
87
88
if (plane.g.stick_mixing != StickMixing::NONE && plane.control_mode != &plane.mode_initializing) {
89
if ((plane.g.stick_mixing != StickMixing::VTOL_YAW) || (plane.control_mode == &plane.mode_auto)) {
90
// all modes except INITIALISING have some form of manual
91
// override if stick mixing is enabled
92
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
93
}
94
}
95
96
// we are armed if we are not initialising
97
if (plane.control_mode != &plane.mode_initializing && plane.arming.is_armed()) {
98
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
99
}
100
101
// indicate we have set a custom mode
102
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
103
104
return _base_mode;
105
}
106
107
uint32_t GCS_Plane::custom_mode() const
108
{
109
return plane.control_mode->mode_number();
110
}
111
112
MAV_STATE GCS_MAVLINK_Plane::vehicle_system_status() const
113
{
114
if (plane.control_mode == &plane.mode_initializing) {
115
return MAV_STATE_CALIBRATING;
116
}
117
if (plane.any_failsafe_triggered()) {
118
return MAV_STATE_CRITICAL;
119
}
120
if (plane.crash_state.is_crashed) {
121
return MAV_STATE_EMERGENCY;
122
}
123
if (plane.is_flying()) {
124
return MAV_STATE_ACTIVE;
125
}
126
127
return MAV_STATE_STANDBY;
128
}
129
130
131
void GCS_MAVLINK_Plane::send_attitude() const
132
{
133
const AP_AHRS &ahrs = AP::ahrs();
134
135
float r = ahrs.get_roll_rad();
136
float p = ahrs.get_pitch_rad();
137
float y = ahrs.get_yaw_rad();
138
139
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH))) {
140
p -= radians(plane.g.pitch_trim);
141
}
142
143
#if HAL_QUADPLANE_ENABLED
144
if (plane.quadplane.show_vtol_view()) {
145
r = plane.quadplane.ahrs_view->roll;
146
p = plane.quadplane.ahrs_view->pitch;
147
y = plane.quadplane.ahrs_view->yaw;
148
}
149
#endif
150
151
const Vector3f &omega = ahrs.get_gyro();
152
mavlink_msg_attitude_send(
153
chan,
154
millis(),
155
r,
156
p,
157
y,
158
omega.x,
159
omega.y,
160
omega.z);
161
}
162
163
void GCS_MAVLINK_Plane::send_attitude_target()
164
{
165
#if HAL_QUADPLANE_ENABLED
166
// Check if the attitude target is valid for reporting
167
const uint32_t now = AP_HAL::millis();
168
if (now - plane.quadplane.last_att_control_ms > 100) {
169
return;
170
}
171
172
const Quaternion quat = plane.quadplane.attitude_control->get_attitude_target_quat();
173
const Vector3f& ang_vel = plane.quadplane.attitude_control->get_attitude_target_ang_vel();
174
const float throttle = plane.quadplane.attitude_control->get_throttle_in();
175
176
const float quat_out[4] {quat.q1, quat.q2, quat.q3, quat.q4};
177
178
const uint16_t typemask = 0;
179
180
mavlink_msg_attitude_target_send(
181
chan,
182
now, // time since boot (ms)
183
typemask, // Bitmask that tells the system what control dimensions should be ignored by the vehicle
184
quat_out, // Target attitude quaternion [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], unit-length
185
ang_vel.x, // bodyframe target roll rate (rad/s)
186
ang_vel.y, // bodyframe target pitch rate (rad/s)
187
ang_vel.z, // bodyframe yaw rate (rad/s)
188
throttle); // Collective thrust, normalized to 0 .. 1
189
190
#endif // HAL_QUADPLANE_ENABLED
191
}
192
193
void GCS_MAVLINK_Plane::send_aoa_ssa()
194
{
195
AP_AHRS &ahrs = AP::ahrs();
196
197
mavlink_msg_aoa_ssa_send(
198
chan,
199
micros(),
200
ahrs.getAOA(),
201
ahrs.getSSA());
202
}
203
204
void GCS_MAVLINK_Plane::send_nav_controller_output() const
205
{
206
if (plane.control_mode == &plane.mode_manual) {
207
return;
208
}
209
#if HAL_QUADPLANE_ENABLED
210
const QuadPlane &quadplane = plane.quadplane;
211
if (quadplane.show_vtol_view() && quadplane.using_wp_nav()) {
212
const Vector3f &targets = quadplane.attitude_control->get_att_target_euler_cd();
213
214
const Vector2f& curr_pos_m = quadplane.inertial_nav.get_position_xy_cm() * 0.01;
215
const Vector2f& target_pos_m = quadplane.pos_control->get_pos_target_NED_m().xy().tofloat();
216
const Vector2f error_m = (target_pos_m - curr_pos_m);
217
218
mavlink_msg_nav_controller_output_send(
219
chan,
220
targets.x * 0.01,
221
targets.y * 0.01,
222
targets.z * 0.01,
223
degrees(error_m.angle()),
224
MIN(error_m.length(), UINT16_MAX),
225
(plane.control_mode != &plane.mode_qstabilize) ? -quadplane.pos_control->get_pos_error_D_m() : 0,
226
plane.airspeed_error * 100, // incorrect units; see PR#7933
227
quadplane.wp_nav->crosstrack_error_m());
228
return;
229
}
230
#endif
231
{
232
const AP_Navigation *nav_controller = plane.nav_controller;
233
mavlink_msg_nav_controller_output_send(
234
chan,
235
plane.nav_roll_cd * 0.01,
236
plane.nav_pitch_cd * 0.01,
237
nav_controller->nav_bearing_cd() * 0.01,
238
nav_controller->target_bearing_cd() * 0.01,
239
MIN(plane.auto_state.wp_distance, UINT16_MAX),
240
plane.calc_altitude_error_cm() * 0.01,
241
plane.airspeed_error * 100, // incorrect units; see PR#7933
242
nav_controller->crosstrack_error());
243
}
244
}
245
246
void GCS_MAVLINK_Plane::send_position_target_global_int()
247
{
248
if (plane.control_mode == &plane.mode_manual) {
249
return;
250
}
251
Location &next_WP_loc = plane.next_WP_loc;
252
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;
253
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
254
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
255
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
256
int32_t alt = 0;
257
if (!next_WP_loc.is_zero()) {
258
UNUSED_RESULT(next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt));
259
}
260
261
mavlink_msg_position_target_global_int_send(
262
chan,
263
AP_HAL::millis(), // time_boot_ms
264
MAV_FRAME_GLOBAL, // targets are always global altitude
265
TYPE_MASK, // ignore everything except the x/y/z components
266
next_WP_loc.lat, // latitude as 1e7
267
next_WP_loc.lng, // longitude as 1e7
268
alt * 0.01, // altitude is sent as a float
269
0.0f, // vx
270
0.0f, // vy
271
0.0f, // vz
272
0.0f, // afx
273
0.0f, // afy
274
0.0f, // afz
275
0.0f, // yaw
276
0.0f); // yaw_rate
277
}
278
279
280
float GCS_MAVLINK_Plane::vfr_hud_airspeed() const
281
{
282
// airspeed sensors are best. While the AHRS airspeed_estimate
283
// will use an airspeed sensor, that value is constrained by the
284
// ground speed. When reporting we should send the true airspeed
285
// value if possible:
286
#if AP_AIRSPEED_ENABLED
287
if (plane.airspeed.enabled() && plane.airspeed.healthy()) {
288
return plane.airspeed.get_airspeed();
289
}
290
#endif
291
292
// airspeed estimates are OK:
293
float aspeed;
294
if (AP::ahrs().airspeed_EAS(aspeed)) {
295
return aspeed;
296
}
297
298
// lying is worst:
299
return 0;
300
}
301
302
int16_t GCS_MAVLINK_Plane::vfr_hud_throttle() const
303
{
304
return plane.throttle_percentage();
305
}
306
307
float GCS_MAVLINK_Plane::vfr_hud_climbrate() const
308
{
309
#if HAL_SOARING_ENABLED
310
if (plane.g2.soaring_controller.is_active()) {
311
return plane.g2.soaring_controller.get_vario_reading();
312
}
313
#endif
314
return GCS_MAVLINK::vfr_hud_climbrate();
315
}
316
317
void GCS_MAVLINK_Plane::send_wind() const
318
{
319
const Vector3f wind = AP::ahrs().wind_estimate();
320
mavlink_msg_wind_send(
321
chan,
322
degrees(atan2f(-wind.y, -wind.x)), // use negative, to give
323
// direction wind is coming from
324
wind.length(),
325
wind.z);
326
}
327
328
// sends a single pid info over the provided channel
329
void GCS_MAVLINK_Plane::send_pid_info(const AP_PIDInfo *pid_info,
330
const uint8_t axis, const float achieved)
331
{
332
if (pid_info == nullptr) {
333
return;
334
}
335
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
336
return;
337
}
338
mavlink_msg_pid_tuning_send(chan, axis,
339
pid_info->target,
340
achieved,
341
pid_info->FF,
342
pid_info->P,
343
pid_info->I,
344
pid_info->D,
345
pid_info->slew_rate,
346
pid_info->Dmod);
347
}
348
349
/*
350
send PID tuning message
351
*/
352
void GCS_MAVLINK_Plane::send_pid_tuning()
353
{
354
if (plane.control_mode == &plane.mode_manual) {
355
// no PIDs should be used in manual
356
return;
357
}
358
359
const Parameters &g = plane.g;
360
361
const AP_PIDInfo *pid_info;
362
if (g.gcs_pid_mask & TUNING_BITS_ROLL) {
363
pid_info = &plane.rollController.get_pid_info();
364
#if HAL_QUADPLANE_ENABLED
365
if (plane.quadplane.in_vtol_mode()) {
366
pid_info = &plane.quadplane.attitude_control->get_rate_roll_pid().get_pid_info();
367
}
368
#endif
369
send_pid_info(pid_info, PID_TUNING_ROLL, pid_info->actual);
370
}
371
if (g.gcs_pid_mask & TUNING_BITS_PITCH) {
372
pid_info = &plane.pitchController.get_pid_info();
373
#if HAL_QUADPLANE_ENABLED
374
if (plane.quadplane.in_vtol_mode()) {
375
pid_info = &plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info();
376
}
377
#endif
378
send_pid_info(pid_info, PID_TUNING_PITCH, pid_info->actual);
379
}
380
if (g.gcs_pid_mask & TUNING_BITS_YAW) {
381
pid_info = &plane.yawController.get_pid_info();
382
#if HAL_QUADPLANE_ENABLED
383
if (plane.quadplane.in_vtol_mode()) {
384
pid_info = &plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info();
385
}
386
#endif
387
send_pid_info(pid_info, PID_TUNING_YAW, pid_info->actual);
388
}
389
if (g.gcs_pid_mask & TUNING_BITS_STEER) {
390
pid_info = &plane.steerController.get_pid_info();
391
send_pid_info(pid_info, PID_TUNING_STEER, pid_info->actual);
392
}
393
if ((g.gcs_pid_mask & TUNING_BITS_LAND) && (plane.flight_stage == AP_FixedWing::FlightStage::LAND)) {
394
AP_AHRS &ahrs = AP::ahrs();
395
const Vector3f &gyro = ahrs.get_gyro();
396
send_pid_info(plane.landing.get_pid_info(), PID_TUNING_LANDING, degrees(gyro.z));
397
}
398
#if HAL_QUADPLANE_ENABLED
399
if (g.gcs_pid_mask & TUNING_BITS_ACCZ && plane.quadplane.in_vtol_mode()) {
400
pid_info = &plane.quadplane.pos_control->D_get_accel_pid().get_pid_info();
401
send_pid_info(pid_info, PID_TUNING_ACCZ, pid_info->actual);
402
}
403
#endif
404
}
405
406
// try to send a message, return false if it won't fit in the serial tx buffer
407
bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
408
{
409
switch (id) {
410
411
case MSG_WIND:
412
CHECK_PAYLOAD_SIZE(WIND);
413
send_wind();
414
break;
415
416
case MSG_ADSB_VEHICLE:
417
#if HAL_ADSB_ENABLED
418
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
419
plane.adsb.send_adsb_vehicle(chan);
420
#endif
421
break;
422
423
case MSG_AOA_SSA:
424
CHECK_PAYLOAD_SIZE(AOA_SSA);
425
send_aoa_ssa();
426
break;
427
428
#if HAL_LANDING_DEEPSTALL_ENABLED
429
case MSG_LANDING:
430
plane.landing.send_landing_message(chan);
431
break;
432
#endif // HAL_LANDING_DEEPSTALL_ENABLED
433
434
case MSG_HYGROMETER:
435
#if AP_AIRSPEED_HYGROMETER_ENABLE
436
CHECK_PAYLOAD_SIZE(HYGROMETER_SENSOR);
437
send_hygrometer();
438
#endif
439
break;
440
441
default:
442
return GCS_MAVLINK::try_send_message(id);
443
}
444
return true;
445
}
446
447
#if AP_AIRSPEED_HYGROMETER_ENABLE
448
void GCS_MAVLINK_Plane::send_hygrometer()
449
{
450
if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) {
451
return;
452
}
453
454
const auto *airspeed = AP::airspeed();
455
if (airspeed == nullptr) {
456
return;
457
}
458
const uint32_t now = AP_HAL::millis();
459
460
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
461
uint8_t idx = (i+last_hygrometer_send_idx+1) % AIRSPEED_MAX_SENSORS;
462
float temperature, humidity;
463
uint32_t last_sample_ms;
464
if (!airspeed->get_hygrometer(idx, last_sample_ms, temperature, humidity)) {
465
continue;
466
}
467
if (now - last_sample_ms > 2000) {
468
// not updating, stop sending
469
continue;
470
}
471
if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) {
472
return;
473
}
474
475
mavlink_msg_hygrometer_sensor_send(
476
chan,
477
idx,
478
int16_t(temperature*100),
479
uint16_t(humidity*100));
480
last_hygrometer_send_idx = idx;
481
}
482
}
483
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
484
485
/*
486
handle a request to switch to guided mode. This happens via a
487
callback from handle_mission_item()
488
*/
489
bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)
490
{
491
return plane.control_mode->handle_guided_request(cmd.content.location);
492
}
493
494
/*
495
handle a request to change current WP altitude. This happens via a
496
callback from handle_mission_item()
497
*/
498
void GCS_MAVLINK_Plane::handle_change_alt_request(Location &location)
499
{
500
plane.fix_terrain_WP(location, __LINE__);
501
502
if (location.terrain_alt) {
503
plane.next_WP_loc.copy_alt_from(location);
504
} else {
505
// convert to absolute alt
506
float abs_alt_m;
507
if (location.get_alt_m(Location::AltFrame::ABSOLUTE, abs_alt_m)) {
508
plane.next_WP_loc.set_alt_m(abs_alt_m, Location::AltFrame::ABSOLUTE);
509
}
510
}
511
plane.reset_offset_altitude();
512
}
513
514
515
/*
516
handle a LANDING_TARGET command. The timestamp has been jitter corrected
517
*/
518
void GCS_MAVLINK_Plane::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
519
{
520
#if AC_PRECLAND_ENABLED
521
plane.g2.precland.handle_msg(packet, timestamp_ms);
522
#endif
523
}
524
525
MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
526
{
527
plane.in_calibration = true;
528
MAV_RESULT ret = GCS_MAVLINK::handle_command_preflight_calibration(packet, msg);
529
plane.in_calibration = false;
530
531
return ret;
532
}
533
534
void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
535
const mavlink_message_t &msg)
536
{
537
#if AP_ADSB_AVOIDANCE_ENABLED
538
plane.avoidance_adsb.handle_msg(msg);
539
#endif
540
GCS_MAVLINK::packetReceived(status, msg);
541
}
542
543
544
bool Plane::set_home_to_current_location(bool _lock)
545
{
546
if (!set_home_persistently(AP::gps().location())) {
547
return false;
548
}
549
if (_lock) {
550
AP::ahrs().lock_home();
551
}
552
if ((control_mode == &mode_rtl)
553
#if HAL_QUADPLANE_ENABLED
554
|| (control_mode == &mode_qrtl)
555
#endif
556
) {
557
// if in RTL head to the updated home location
558
control_mode->enter();
559
}
560
return true;
561
}
562
bool Plane::set_home(const Location& loc, bool _lock)
563
{
564
if (!AP::ahrs().set_home(loc)) {
565
return false;
566
}
567
if (_lock) {
568
AP::ahrs().lock_home();
569
}
570
if ((control_mode == &mode_rtl)
571
#if HAL_QUADPLANE_ENABLED
572
|| (control_mode == &mode_qrtl)
573
#endif
574
) {
575
// if in RTL head to the updated home location
576
control_mode->enter();
577
}
578
return true;
579
}
580
581
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
582
{
583
// sanity check location
584
if (!check_latlng(packet.x, packet.y)) {
585
return MAV_RESULT_DENIED;
586
}
587
588
Location requested_position;
589
if (!location_from_command_t(packet, requested_position)) {
590
return MAV_RESULT_DENIED;
591
}
592
plane.fix_terrain_WP(requested_position, __LINE__);
593
594
if (isnan(packet.param4) || is_zero(packet.param4)) {
595
requested_position.loiter_ccw = 0;
596
} else {
597
requested_position.loiter_ccw = 1;
598
}
599
600
if (requested_position.sanitize(plane.current_loc)) {
601
// if the location wasn't already sane don't load it
602
return MAV_RESULT_DENIED;
603
}
604
605
#if AP_FENCE_ENABLED
606
// reject destination if outside the fence
607
if (!plane.fence.check_destination_within_fence(requested_position)) {
608
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
609
return MAV_RESULT_DENIED;
610
}
611
#endif
612
613
// location is valid load and set
614
if (((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) ||
615
(plane.control_mode == &plane.mode_guided)) {
616
plane.set_mode(plane.mode_guided, ModeReason::GCS_COMMAND);
617
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
618
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
619
#endif
620
621
// convert to absolute alt
622
if (!requested_position.terrain_alt) {
623
requested_position.change_alt_frame(Location::AltFrame::ABSOLUTE);
624
}
625
626
plane.set_guided_WP(requested_position);
627
628
// Loiter radius for planes. Positive radius in meters, direction is controlled by Yaw (param4) value, parsed above
629
if (!isnan(packet.param3) && packet.param3 > 0) {
630
plane.mode_guided.set_radius_and_direction(packet.param3, requested_position.loiter_ccw);
631
}
632
633
return MAV_RESULT_ACCEPTED;
634
}
635
return MAV_RESULT_FAILED;
636
}
637
638
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_DO_CHANGE_ALTITUDE(const mavlink_command_int_t &packet)
639
{
640
const float alt = packet.param1;
641
MAV_FRAME mav_frame = (MAV_FRAME)packet.param2;
642
Location::AltFrame alt_frame;
643
if (!mavlink_coordinate_frame_to_location_alt_frame(mav_frame, alt_frame)) {
644
return MAV_RESULT_DENIED;
645
}
646
Location loc {
647
0,
648
0,
649
int32_t(alt * 100), // m -> cm
650
alt_frame,
651
};
652
handle_change_alt_request(loc);
653
return MAV_RESULT_ACCEPTED;
654
}
655
656
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
657
// these are GUIDED mode commands that are RATE or slew enabled, so you can have more powerful control than default controls.
658
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet)
659
{
660
switch(packet.command) {
661
case MAV_CMD_GUIDED_CHANGE_SPEED: {
662
// command is only valid in guided mode
663
if (plane.control_mode != &plane.mode_guided) {
664
return MAV_RESULT_FAILED;
665
}
666
667
// only airspeed commands are supported right now...
668
if (int(packet.param1) != SPEED_TYPE_AIRSPEED) { // since SPEED_TYPE is int in range 0-1 and packet.param1 is a *float* this works.
669
return MAV_RESULT_DENIED;
670
}
671
672
if (!plane.mode_guided.handle_change_airspeed(packet.param2, packet.param3)) {
673
return MAV_RESULT_FAILED;
674
}
675
return MAV_RESULT_ACCEPTED;
676
}
677
678
case MAV_CMD_GUIDED_CHANGE_ALTITUDE: {
679
// command is only valid in guided
680
if (plane.control_mode != &plane.mode_guided) {
681
return MAV_RESULT_FAILED;
682
}
683
684
// disallow default value of -1 and dangerous value of zero
685
if (is_equal(packet.z, -1.0f) || is_equal(packet.z, 0.0f)){
686
return MAV_RESULT_DENIED;
687
}
688
689
Location::AltFrame new_target_alt_frame;
690
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.frame, new_target_alt_frame)) {
691
return MAV_RESULT_DENIED;
692
}
693
// keep a copy of what came in via MAVLink - this is needed for logging, but not for anything else
694
plane.guided_state.target_mav_frame = packet.frame;
695
696
const int32_t new_target_alt_cm = packet.z * 100;
697
plane.guided_state.target_location.set_alt_cm(new_target_alt_cm, new_target_alt_frame);
698
plane.guided_state.target_alt_time_ms = AP_HAL::millis();
699
700
// param3 contains the desired vertical velocity (not acceleration)
701
if (is_zero(packet.param3)) {
702
// the user wanted /maximum altitude change rate, pick a large value as close enough
703
plane.guided_state.target_alt_rate = 1000.0;
704
} else {
705
plane.guided_state.target_alt_rate = fabsf(packet.param3);
706
}
707
708
return MAV_RESULT_ACCEPTED;
709
}
710
711
case MAV_CMD_GUIDED_CHANGE_HEADING: {
712
713
// command is only valid in guided mode
714
if (plane.control_mode != &plane.mode_guided) {
715
return MAV_RESULT_FAILED;
716
}
717
718
// don't accept packets outside of [0-360] degree range
719
if (packet.param2 < 0.0f || packet.param2 >= 360.0f) {
720
return MAV_RESULT_DENIED;
721
}
722
723
float new_target_heading = radians(wrap_180(packet.param2));
724
725
switch(HEADING_TYPE(packet.param1)) {
726
case HEADING_TYPE_COURSE_OVER_GROUND:
727
// course over ground
728
plane.guided_state.target_heading_type = GUIDED_HEADING_COG;
729
plane.prev_WP_loc = plane.current_loc;
730
break;
731
case HEADING_TYPE_HEADING:
732
// normal vehicle heading
733
plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING;
734
break;
735
case HEADING_TYPE_DEFAULT:
736
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
737
return MAV_RESULT_ACCEPTED;
738
default:
739
// MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters).
740
return MAV_RESULT_DENIED;
741
}
742
743
plane.g2.guidedHeading.reset_I();
744
745
plane.guided_state.target_heading = new_target_heading;
746
plane.guided_state.target_heading_accel_limit = MAX(packet.param3, 0.05f);
747
plane.guided_state.target_heading_time_ms = AP_HAL::millis();
748
return MAV_RESULT_ACCEPTED;
749
}
750
}
751
// anything else ...
752
return MAV_RESULT_UNSUPPORTED;
753
}
754
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
755
756
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
757
{
758
switch(packet.command) {
759
760
case MAV_CMD_DO_AUTOTUNE_ENABLE:
761
return handle_MAV_CMD_DO_AUTOTUNE_ENABLE(packet);
762
763
case MAV_CMD_DO_REPOSITION:
764
return handle_command_int_do_reposition(packet);
765
766
case MAV_CMD_DO_CHANGE_ALTITUDE:
767
return handle_command_int_DO_CHANGE_ALTITUDE(packet);
768
769
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
770
// special 'slew-enabled' guided commands here... for speed,alt, and direction commands
771
case MAV_CMD_GUIDED_CHANGE_SPEED:
772
case MAV_CMD_GUIDED_CHANGE_ALTITUDE:
773
case MAV_CMD_GUIDED_CHANGE_HEADING:
774
return handle_command_int_guided_slew_commands(packet);
775
#endif
776
777
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
778
case MAV_CMD_DO_FOLLOW:
779
// param1: sysid of target to follow
780
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
781
plane.g2.follow.set_target_sysid((uint8_t)packet.param1);
782
return MAV_RESULT_ACCEPTED;
783
}
784
return MAV_RESULT_DENIED;
785
#endif
786
787
#if AP_ICENGINE_ENABLED
788
case MAV_CMD_DO_ENGINE_CONTROL:
789
if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3, (uint32_t)packet.param4)) {
790
return MAV_RESULT_FAILED;
791
}
792
return MAV_RESULT_ACCEPTED;
793
#endif
794
795
case MAV_CMD_DO_CHANGE_SPEED:
796
return handle_command_DO_CHANGE_SPEED(packet);
797
798
#if HAL_PARACHUTE_ENABLED
799
case MAV_CMD_DO_PARACHUTE:
800
return handle_MAV_CMD_DO_PARACHUTE(packet);
801
#endif
802
803
#if HAL_QUADPLANE_ENABLED
804
case MAV_CMD_DO_MOTOR_TEST:
805
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
806
807
case MAV_CMD_DO_VTOL_TRANSITION:
808
return handle_command_DO_VTOL_TRANSITION(packet);
809
810
case MAV_CMD_NAV_TAKEOFF:
811
return handle_command_MAV_CMD_NAV_TAKEOFF(packet);
812
#endif
813
814
case MAV_CMD_DO_GO_AROUND:
815
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
816
817
case MAV_CMD_DO_RETURN_PATH_START:
818
// attempt to rejoin after the next DO_RETURN_PATH_START command in the mission
819
if (plane.have_position && plane.mission.jump_to_closest_mission_leg(plane.current_loc)) {
820
plane.mission.set_force_resume(true);
821
if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {
822
return MAV_RESULT_ACCEPTED;
823
}
824
// mode change failed, revert force resume flag
825
plane.mission.set_force_resume(false);
826
}
827
return MAV_RESULT_FAILED;
828
829
case MAV_CMD_DO_LAND_START:
830
// attempt to switch to next DO_LAND_START command in the mission
831
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
832
plane.mission.set_force_resume(true);
833
if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {
834
return MAV_RESULT_ACCEPTED;
835
}
836
// mode change failed, revert force resume flag
837
plane.mission.set_force_resume(false);
838
}
839
return MAV_RESULT_FAILED;
840
841
case MAV_CMD_MISSION_START:
842
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
843
// first-item/last item not supported
844
return MAV_RESULT_DENIED;
845
}
846
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
847
return MAV_RESULT_ACCEPTED;
848
849
case MAV_CMD_NAV_LOITER_UNLIM:
850
plane.set_mode(plane.mode_loiter, ModeReason::GCS_COMMAND);
851
return MAV_RESULT_ACCEPTED;
852
853
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
854
plane.set_mode(plane.mode_rtl, ModeReason::GCS_COMMAND);
855
return MAV_RESULT_ACCEPTED;
856
857
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
858
case MAV_CMD_SET_HAGL:
859
plane.handle_external_hagl(packet);
860
return MAV_RESULT_ACCEPTED;
861
#endif
862
863
default:
864
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
865
}
866
}
867
868
MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
869
{
870
// if we're in failsafe modes (e.g., RTL, LOITER) or in pilot
871
// controlled modes (e.g., MANUAL, TRAINING)
872
// this command should be ignored since it comes in from GCS
873
// or a companion computer:
874
if ((!plane.control_mode->is_guided_mode()) &&
875
(plane.control_mode != &plane.mode_auto)) {
876
// failed
877
return MAV_RESULT_FAILED;
878
}
879
880
if (plane.do_change_speed((SPEED_TYPE)packet.param1, packet.param2, packet.param3)) {
881
return MAV_RESULT_ACCEPTED;
882
}
883
return MAV_RESULT_FAILED;
884
}
885
886
#if HAL_QUADPLANE_ENABLED
887
#if AP_MAVLINK_COMMAND_LONG_ENABLED
888
void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out)
889
{
890
// convert to MAV_FRAME_LOCAL_OFFSET_NED, "NED local tangent frame
891
// with origin that travels with the vehicle"
892
out = {};
893
out.target_system = in.target_system;
894
out.target_component = in.target_component;
895
out.frame = MAV_FRAME_LOCAL_OFFSET_NED;
896
out.command = in.command;
897
// out.current = 0;
898
// out.autocontinue = 0;
899
// out.param1 = in.param1; // we only use the "z" parameter in this command:
900
// out.param2 = in.param2;
901
// out.param3 = in.param3;
902
// out.param4 = in.param4;
903
// out.x = 0; // we don't handle positioning when doing takeoffs
904
// out.y = 0;
905
out.z = -in.param7; // up -> down
906
}
907
908
void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame)
909
{
910
switch (in.command) {
911
case MAV_CMD_NAV_TAKEOFF:
912
convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(in, out);
913
return;
914
}
915
return GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(in, out, frame);
916
}
917
#endif // AP_MAVLINK_COMMAND_LONG_ENABLED
918
919
MAV_RESULT GCS_MAVLINK_Plane::handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet)
920
{
921
float takeoff_alt = packet.z;
922
switch (packet.frame) {
923
case MAV_FRAME_LOCAL_OFFSET_NED: // "NED local tangent frame with origin that travels with the vehicle"
924
takeoff_alt = -takeoff_alt; // down -> up
925
break;
926
default:
927
return MAV_RESULT_DENIED; // "is supported but has invalid parameters"
928
}
929
if (!plane.quadplane.available()) {
930
return MAV_RESULT_FAILED;
931
}
932
if (!plane.quadplane.do_user_takeoff(takeoff_alt)) {
933
return MAV_RESULT_FAILED;
934
}
935
return MAV_RESULT_ACCEPTED;
936
}
937
#endif
938
939
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet)
940
{
941
// param1 : enable/disable
942
plane.autotune_enable(!is_zero(packet.param1));
943
return MAV_RESULT_ACCEPTED;
944
}
945
946
#if HAL_PARACHUTE_ENABLED
947
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
948
{
949
// configure or release parachute
950
switch ((uint16_t)packet.param1) {
951
case PARACHUTE_DISABLE:
952
plane.parachute.enabled(false);
953
return MAV_RESULT_ACCEPTED;
954
case PARACHUTE_ENABLE:
955
plane.parachute.enabled(true);
956
return MAV_RESULT_ACCEPTED;
957
case PARACHUTE_RELEASE:
958
// treat as a manual release which performs some additional check of altitude
959
if (plane.parachute.released()) {
960
gcs().send_text(MAV_SEVERITY_NOTICE, "Parachute already released");
961
return MAV_RESULT_FAILED;
962
}
963
if (!plane.parachute.enabled()) {
964
gcs().send_text(MAV_SEVERITY_NOTICE, "Parachute not enabled");
965
return MAV_RESULT_FAILED;
966
}
967
if (!plane.parachute_manual_release()) {
968
return MAV_RESULT_FAILED;
969
}
970
return MAV_RESULT_ACCEPTED;
971
default:
972
break;
973
}
974
return MAV_RESULT_FAILED;
975
}
976
#endif
977
978
979
#if HAL_QUADPLANE_ENABLED
980
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
981
{
982
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
983
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
984
// param3 : throttle (range depends upon param2)
985
// param4 : timeout (in seconds)
986
// param5 : motor count (number of motors to test in sequence)
987
return plane.quadplane.mavlink_motor_test_start(chan,
988
(uint8_t)packet.param1,
989
(uint8_t)packet.param2,
990
(uint16_t)packet.param3,
991
packet.param4,
992
(uint8_t)packet.x);
993
}
994
995
MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet)
996
{
997
if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) {
998
return MAV_RESULT_FAILED;
999
}
1000
return MAV_RESULT_ACCEPTED;
1001
}
1002
#endif
1003
1004
// this is called on receipt of a MANUAL_CONTROL packet and is
1005
// expected to call manual_override to override RC input on desired
1006
// axes.
1007
void GCS_MAVLINK_Plane::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
1008
{
1009
manual_override(plane.channel_roll, packet.y, 1000, 2000, tnow);
1010
manual_override(plane.channel_pitch, packet.x, 1000, 2000, tnow, true);
1011
manual_override(plane.channel_throttle, packet.z, 0, 1000, tnow);
1012
manual_override(plane.channel_rudder, packet.r, 1000, 2000, tnow);
1013
}
1014
1015
void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)
1016
{
1017
switch (msg.msgid) {
1018
1019
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
1020
handle_set_attitude_target(msg);
1021
break;
1022
1023
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
1024
handle_set_position_target_local_ned(msg);
1025
break;
1026
1027
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
1028
handle_set_position_target_global_int(msg);
1029
break;
1030
1031
default:
1032
GCS_MAVLINK::handle_message(msg);
1033
break;
1034
} // end switch
1035
} // end handle mavlink
1036
1037
void GCS_MAVLINK_Plane::handle_set_attitude_target(const mavlink_message_t &msg)
1038
{
1039
// Only allow companion computer (or other external controller) to
1040
// control attitude in GUIDED mode. We DON'T want external control
1041
// in e.g., RTL, CICLE. Specifying a single mode for companion
1042
// computer control is more safe (even more so when using
1043
// FENCE_ACTION = 4 for geofence failures).
1044
if (plane.control_mode != &plane.mode_guided) { // don't screw up failsafes
1045
return;
1046
}
1047
1048
mavlink_set_attitude_target_t att_target;
1049
mavlink_msg_set_attitude_target_decode(&msg, &att_target);
1050
1051
// Mappings: If any of these bits are set, the corresponding input should be ignored.
1052
// NOTE, when parsing the bits we invert them for easier interpretation but transport has them inverted
1053
// bit 1: body roll rate
1054
// bit 2: body pitch rate
1055
// bit 3: body yaw rate
1056
// bit 4: unknown
1057
// bit 5: unknown
1058
// bit 6: reserved
1059
// bit 7: throttle
1060
// bit 8: attitude
1061
1062
// if not setting all Quaternion values, use _rate flags to indicate which fields.
1063
1064
// Extract the Euler roll angle from the Quaternion.
1065
Quaternion q(att_target.q[0], att_target.q[1],
1066
att_target.q[2], att_target.q[3]);
1067
1068
// NOTE: att_target.type_mask is inverted for easier interpretation
1069
att_target.type_mask = att_target.type_mask ^ 0xFF;
1070
1071
uint8_t attitude_mask = att_target.type_mask & 0b10000111; // q plus rpy
1072
1073
uint32_t now = AP_HAL::millis();
1074
if ((attitude_mask & 0b10000001) || // partial, including roll
1075
(attitude_mask == 0b10000000)) { // all angles
1076
plane.guided_state.forced_rpy_cd.x = degrees(q.get_euler_roll()) * 100.0f;
1077
1078
// Update timer for external roll to the nav control
1079
plane.guided_state.last_forced_rpy_ms.x = now;
1080
}
1081
1082
if ((attitude_mask & 0b10000010) || // partial, including pitch
1083
(attitude_mask == 0b10000000)) { // all angles
1084
plane.guided_state.forced_rpy_cd.y = degrees(q.get_euler_pitch()) * 100.0f;
1085
1086
// Update timer for external pitch to the nav control
1087
plane.guided_state.last_forced_rpy_ms.y = now;
1088
}
1089
1090
if ((attitude_mask & 0b10000100) || // partial, including yaw
1091
(attitude_mask == 0b10000000)) { // all angles
1092
plane.guided_state.forced_rpy_cd.z = degrees(q.get_euler_yaw()) * 100.0f;
1093
1094
// Update timer for external yaw to the nav control
1095
plane.guided_state.last_forced_rpy_ms.z = now;
1096
}
1097
if (att_target.type_mask & 0b01000000) { // throttle
1098
plane.guided_state.forced_throttle = att_target.thrust * 100.0f;
1099
1100
// Update timer for external throttle
1101
plane.guided_state.last_forced_throttle_ms = now;
1102
}
1103
}
1104
1105
void GCS_MAVLINK_Plane::handle_set_position_target_local_ned(const mavlink_message_t &msg)
1106
{
1107
// decode packet
1108
mavlink_set_position_target_local_ned_t packet;
1109
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
1110
1111
// exit if vehicle is not in Guided mode
1112
if (plane.control_mode != &plane.mode_guided) {
1113
return;
1114
}
1115
1116
// only local moves for now
1117
if (packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
1118
return;
1119
}
1120
1121
// just do altitude for now
1122
plane.next_WP_loc.alt += -packet.z*100.0;
1123
gcs().send_text(MAV_SEVERITY_INFO, "Change alt to %.1f",
1124
(double)((plane.next_WP_loc.alt - plane.home.alt)*0.01));
1125
}
1126
1127
void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_message_t &msg)
1128
{
1129
// Only want to allow companion computer position control when
1130
// in a certain mode to avoid inadvertently sending these
1131
// kinds of commands when the autopilot is responding to problems
1132
// in modes such as RTL, CIRCLE, etc. Specifying ONLY one mode
1133
// for companion computer control is more safe (provided
1134
// one uses the FENCE_ACTION = 4 (RTL) for geofence failures).
1135
if (plane.control_mode != &plane.mode_guided) {
1136
//don't screw up failsafes
1137
return;
1138
}
1139
1140
mavlink_set_position_target_global_int_t pos_target;
1141
mavlink_msg_set_position_target_global_int_decode(&msg, &pos_target);
1142
1143
Location::AltFrame frame;
1144
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)pos_target.coordinate_frame, frame)) {
1145
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSITION_TARGET_GLOBAL_INT");
1146
// Even though other parts of the command may be valid, reject the whole thing.
1147
return;
1148
}
1149
1150
// Unexpectedly, the mask is expecting "ones" for dimensions that should
1151
// be IGNORED rather than INCLUDED. See mavlink documentation of the
1152
// SET_POSITION_TARGET_GLOBAL_INT message, type_mask field.
1153
const bool alt_ignore = (pos_target.type_mask & POSITION_TARGET_TYPEMASK_Z_IGNORE);
1154
if (!alt_ignore) {
1155
Location loc {
1156
0, // lat
1157
0, // lng
1158
int32_t(pos_target.alt * 100), // m -> cm
1159
frame,
1160
};
1161
handle_change_alt_request(loc);
1162
}
1163
}
1164
1165
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
1166
{
1167
const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet);
1168
if (result != MAV_RESULT_ACCEPTED) {
1169
return result;
1170
}
1171
1172
// if you change this you must change handle_mission_set_current
1173
plane.auto_state.next_wp_crosstrack = false;
1174
if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) {
1175
plane.mission.resume();
1176
}
1177
1178
return result;
1179
}
1180
1181
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
1182
void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg)
1183
{
1184
// if you change this you must change handle_command_do_set_mission_current
1185
plane.auto_state.next_wp_crosstrack = false;
1186
GCS_MAVLINK::handle_mission_set_current(mission, msg);
1187
if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) {
1188
plane.mission.resume();
1189
}
1190
}
1191
#endif
1192
1193
uint64_t GCS_MAVLINK_Plane::capabilities() const
1194
{
1195
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
1196
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
1197
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
1198
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
1199
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
1200
#if AP_TERRAIN_AVAILABLE
1201
(plane.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
1202
#endif
1203
GCS_MAVLINK::capabilities());
1204
}
1205
1206
#if HAL_HIGH_LATENCY2_ENABLED
1207
int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const
1208
{
1209
AP_AHRS &ahrs = AP::ahrs();
1210
Location global_position_current;
1211
UNUSED_RESULT(ahrs.get_location(global_position_current));
1212
1213
#if HAL_QUADPLANE_ENABLED
1214
const QuadPlane &quadplane = plane.quadplane;
1215
//return units are m
1216
if (quadplane.show_vtol_view()) {
1217
return (plane.control_mode != &plane.mode_qstabilize) ? (global_position_current.alt * 0.01 - quadplane.pos_control->get_pos_error_D_m()) : 0;
1218
}
1219
#endif
1220
return 0.01 * (global_position_current.alt + plane.calc_altitude_error_cm());
1221
}
1222
1223
uint8_t GCS_MAVLINK_Plane::high_latency_tgt_heading() const
1224
{
1225
// return units are deg/2
1226
#if HAL_QUADPLANE_ENABLED
1227
const QuadPlane &quadplane = plane.quadplane;
1228
if (quadplane.show_vtol_view()) {
1229
const Vector3f &targets = quadplane.attitude_control->get_att_target_euler_cd();
1230
return ((uint16_t)(targets.z * 0.01)) / 2;
1231
}
1232
#endif
1233
const AP_Navigation *nav_controller = plane.nav_controller;
1234
// need to convert -18000->18000 to 0->360/2
1235
return wrap_360_cd(nav_controller->target_bearing_cd() ) / 200;
1236
}
1237
1238
// return units are dm
1239
uint16_t GCS_MAVLINK_Plane::high_latency_tgt_dist() const
1240
{
1241
#if HAL_QUADPLANE_ENABLED
1242
const QuadPlane &quadplane = plane.quadplane;
1243
if (quadplane.show_vtol_view()) {
1244
bool wp_nav_valid = quadplane.using_wp_nav();
1245
return (wp_nav_valid ? MIN(quadplane.wp_nav->get_wp_distance_to_destination_cm(), UINT16_MAX) : 0) / 10;
1246
}
1247
#endif
1248
1249
return MIN(plane.auto_state.wp_distance, UINT16_MAX) / 10;
1250
}
1251
1252
uint8_t GCS_MAVLINK_Plane::high_latency_tgt_airspeed() const
1253
{
1254
// return units are m/s*5
1255
return plane.target_airspeed_cm * 0.05;
1256
}
1257
1258
uint8_t GCS_MAVLINK_Plane::high_latency_wind_speed() const
1259
{
1260
Vector3f wind;
1261
wind = AP::ahrs().wind_estimate();
1262
1263
// return units are m/s*5
1264
return MIN(wind.length() * 5, UINT8_MAX);
1265
}
1266
1267
uint8_t GCS_MAVLINK_Plane::high_latency_wind_direction() const
1268
{
1269
const Vector3f wind = AP::ahrs().wind_estimate();
1270
1271
// return units are deg/2
1272
// need to convert -180->180 to 0->360/2
1273
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
1274
}
1275
#endif // HAL_HIGH_LATENCY2_ENABLED
1276
1277
MAV_VTOL_STATE GCS_MAVLINK_Plane::vtol_state() const
1278
{
1279
#if !HAL_QUADPLANE_ENABLED
1280
return MAV_VTOL_STATE_UNDEFINED;
1281
#else
1282
if (!plane.quadplane.available()) {
1283
return MAV_VTOL_STATE_UNDEFINED;
1284
}
1285
1286
return plane.quadplane.transition->get_mav_vtol_state();
1287
#endif
1288
};
1289
1290
MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const
1291
{
1292
if (plane.is_flying()) {
1293
if (plane.is_taking_off()) {
1294
return MAV_LANDED_STATE_TAKEOFF;
1295
}
1296
if (plane.is_landing()) {
1297
return MAV_LANDED_STATE_LANDING;
1298
}
1299
1300
// note that Q-modes almost always consider themselves as flying
1301
return MAV_LANDED_STATE_IN_AIR;
1302
}
1303
1304
return MAV_LANDED_STATE_ON_GROUND;
1305
}
1306
1307
// Send the mode with the given index (not mode number!) return the total number of modes
1308
// Index starts at 1
1309
uint8_t GCS_MAVLINK_Plane::send_available_mode(uint8_t index) const
1310
{
1311
// Fixed wing modes
1312
const Mode* fw_modes[] {
1313
&plane.mode_manual,
1314
&plane.mode_circle,
1315
&plane.mode_stabilize,
1316
&plane.mode_training,
1317
&plane.mode_acro,
1318
&plane.mode_fbwa,
1319
&plane.mode_fbwb,
1320
&plane.mode_cruise,
1321
&plane.mode_autotune,
1322
&plane.mode_auto,
1323
&plane.mode_rtl,
1324
&plane.mode_loiter,
1325
#if HAL_ADSB_ENABLED
1326
&plane.mode_avoidADSB,
1327
#endif
1328
&plane.mode_guided,
1329
&plane.mode_initializing,
1330
&plane.mode_takeoff,
1331
#if HAL_SOARING_ENABLED
1332
&plane.mode_thermal,
1333
#endif
1334
#if MODE_AUTOLAND_ENABLED
1335
&plane.mode_autoland,
1336
#endif
1337
};
1338
1339
const uint8_t fw_mode_count = ARRAY_SIZE(fw_modes);
1340
1341
// Fixedwing modes are always present
1342
uint8_t mode_count = fw_mode_count;
1343
1344
#if HAL_QUADPLANE_ENABLED
1345
// Quadplane modes
1346
const Mode* q_modes[] {
1347
&plane.mode_qstabilize,
1348
&plane.mode_qhover,
1349
&plane.mode_qloiter,
1350
&plane.mode_qland,
1351
&plane.mode_qrtl,
1352
&plane.mode_qacro,
1353
&plane.mode_loiter_qland,
1354
#if QAUTOTUNE_ENABLED
1355
&plane.mode_qautotune,
1356
#endif
1357
};
1358
1359
// Quadplane modes must be enabled
1360
if (plane.quadplane.available()) {
1361
mode_count += ARRAY_SIZE(q_modes);
1362
}
1363
#endif // HAL_QUADPLANE_ENABLED
1364
1365
1366
// Convert to zero indexed
1367
const uint8_t index_zero = index - 1;
1368
if (index_zero >= mode_count) {
1369
// Mode does not exist!?
1370
return mode_count;
1371
}
1372
1373
// Ask the mode for its name and number
1374
const char* name;
1375
uint8_t mode_number;
1376
1377
if (index_zero < fw_mode_count) {
1378
// A fixedwing mode
1379
name = fw_modes[index_zero]->name();
1380
mode_number = (uint8_t)fw_modes[index_zero]->mode_number();
1381
1382
} else {
1383
#if HAL_QUADPLANE_ENABLED
1384
// A Quadplane mode
1385
const uint8_t q_index = index_zero - fw_mode_count;
1386
name = q_modes[q_index]->name();
1387
mode_number = (uint8_t)q_modes[q_index]->mode_number();
1388
#else
1389
// Should not endup here
1390
return mode_count;
1391
#endif
1392
}
1393
1394
mavlink_msg_available_modes_send(
1395
chan,
1396
mode_count,
1397
index,
1398
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
1399
mode_number,
1400
0, // MAV_MODE_PROPERTY bitmask
1401
name
1402
);
1403
1404
return mode_count;
1405
}
1406
1407