CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/GCS_MAVLink_Plane.cpp
Views: 1798
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
MAV_MODE 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 (MAV_MODE)_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();
136
float p = ahrs.get_pitch();
137
float y = ahrs.get_yaw();
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 = quadplane.inertial_nav.get_position_xy_cm();
215
const Vector2f& target_pos = quadplane.pos_control->get_pos_target_cm().xy().tofloat();
216
const Vector2f error = (target_pos - curr_pos) * 0.01;
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.angle()),
224
MIN(error.length(), UINT16_MAX),
225
(plane.control_mode != &plane.mode_qstabilize) ? quadplane.pos_control->get_pos_error_z_cm() * 0.01 : 0,
226
plane.airspeed_error * 100, // incorrect units; see PR#7933
227
quadplane.wp_nav->crosstrack_error());
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_estimate(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->get_accel_z_pid().get_pid_info();
401
send_pid_info(pid_info, PID_TUNING_ACCZ, pid_info->actual);
402
}
403
#endif
404
}
405
406
uint8_t GCS_MAVLINK_Plane::sysid_my_gcs() const
407
{
408
return plane.g.sysid_my_gcs;
409
}
410
bool GCS_MAVLINK_Plane::sysid_enforce() const
411
{
412
return plane.g2.sysid_enforce;
413
}
414
415
uint32_t GCS_MAVLINK_Plane::telem_delay() const
416
{
417
return (uint32_t)(plane.g.telem_delay);
418
}
419
420
// try to send a message, return false if it won't fit in the serial tx buffer
421
bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
422
{
423
switch (id) {
424
425
case MSG_SERVO_OUT:
426
// unused
427
break;
428
429
#if AP_TERRAIN_AVAILABLE
430
case MSG_TERRAIN_REQUEST:
431
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
432
plane.terrain.send_request(chan);
433
break;
434
case MSG_TERRAIN_REPORT:
435
CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);
436
plane.terrain.send_report(chan);
437
break;
438
#endif
439
440
case MSG_WIND:
441
CHECK_PAYLOAD_SIZE(WIND);
442
send_wind();
443
break;
444
445
case MSG_ADSB_VEHICLE:
446
#if HAL_ADSB_ENABLED
447
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
448
plane.adsb.send_adsb_vehicle(chan);
449
#endif
450
break;
451
452
case MSG_AOA_SSA:
453
CHECK_PAYLOAD_SIZE(AOA_SSA);
454
send_aoa_ssa();
455
break;
456
case MSG_LANDING:
457
plane.landing.send_landing_message(chan);
458
break;
459
460
case MSG_HYGROMETER:
461
#if AP_AIRSPEED_HYGROMETER_ENABLE
462
CHECK_PAYLOAD_SIZE(HYGROMETER_SENSOR);
463
send_hygrometer();
464
#endif
465
break;
466
467
default:
468
return GCS_MAVLINK::try_send_message(id);
469
}
470
return true;
471
}
472
473
#if AP_AIRSPEED_HYGROMETER_ENABLE
474
void GCS_MAVLINK_Plane::send_hygrometer()
475
{
476
if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) {
477
return;
478
}
479
480
const auto *airspeed = AP::airspeed();
481
if (airspeed == nullptr) {
482
return;
483
}
484
const uint32_t now = AP_HAL::millis();
485
486
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
487
uint8_t idx = (i+last_hygrometer_send_idx+1) % AIRSPEED_MAX_SENSORS;
488
float temperature, humidity;
489
uint32_t last_sample_ms;
490
if (!airspeed->get_hygrometer(idx, last_sample_ms, temperature, humidity)) {
491
continue;
492
}
493
if (now - last_sample_ms > 2000) {
494
// not updating, stop sending
495
continue;
496
}
497
if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) {
498
return;
499
}
500
501
mavlink_msg_hygrometer_sensor_send(
502
chan,
503
idx,
504
int16_t(temperature*100),
505
uint16_t(humidity*100));
506
last_hygrometer_send_idx = idx;
507
}
508
}
509
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
510
511
512
/*
513
default stream rates to 1Hz
514
*/
515
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
516
// @Param: RAW_SENS
517
// @DisplayName: Raw sensor stream rate
518
// @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED
519
// @Units: Hz
520
// @Range: 0 50
521
// @Increment: 1
522
// @RebootRequired: True
523
// @User: Advanced
524
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),
525
526
// @Param: EXT_STAT
527
// @DisplayName: Extended status stream rate
528
// @Description: MAVLink Stream rate of SYS_STATUS, POWER_STATUS, MCU_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW_INT (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, FENCE_STATUS, and GLOBAL_TARGET_POS_INT
529
// @Units: Hz
530
// @Range: 0 50
531
// @Increment: 1
532
// @RebootRequired: True
533
// @User: Advanced
534
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),
535
536
// @Param: RC_CHAN
537
// @DisplayName: RC Channel stream rate
538
// @Description: MAVLink Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS
539
// @Units: Hz
540
// @Range: 0 50
541
// @Increment: 1
542
// @RebootRequired: True
543
// @User: Advanced
544
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),
545
546
// @Param: RAW_CTRL
547
// @DisplayName: Raw Control stream rate
548
// @Description: MAVLink Raw Control stream rate of SERVO_OUT
549
// @Units: Hz
550
// @Range: 0 50
551
// @Increment: 1
552
// @RebootRequired: True
553
// @User: Advanced
554
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),
555
556
// @Param: POSITION
557
// @DisplayName: Position stream rate
558
// @Description: MAVLink Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED
559
// @Units: Hz
560
// @Range: 0 50
561
// @Increment: 1
562
// @RebootRequired: True
563
// @User: Advanced
564
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1),
565
566
// @Param: EXTRA1
567
// @DisplayName: Extra data type 1 stream rate
568
// @Description: MAVLink Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2, RPM, AOA_SSA, LANDING,ESC_TELEMETRY,EFI_STATUS, and PID_TUNING
569
// @Units: Hz
570
// @Range: 0 50
571
// @Increment: 1
572
// @RebootRequired: True
573
// @User: Advanced
574
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),
575
576
// @Param: EXTRA2
577
// @DisplayName: Extra data type 2 stream rate
578
// @Description: MAVLink Stream rate of VFR_HUD
579
// @Range: 0 50
580
// @Increment: 1
581
// @RebootRequired: True
582
// @User: Advanced
583
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),
584
585
// @Param: EXTRA3
586
// @DisplayName: Extra data type 3 stream rate
587
// @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, and BATTERY_STATUS
588
// @Units: Hz
589
// @Range: 0 50
590
// @Increment: 1
591
// @RebootRequired: True
592
// @User: Advanced
593
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),
594
595
// @Param: PARAMS
596
// @DisplayName: Parameter stream rate
597
// @Description: MAVLink Stream rate of PARAM_VALUE
598
// @Units: Hz
599
// @Range: 0 50
600
// @Increment: 1
601
// @RebootRequired: True
602
// @User: Advanced
603
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),
604
605
// @Param: ADSB
606
// @DisplayName: ADSB stream rate
607
// @Description: MAVLink ADSB stream rate
608
// @Units: Hz
609
// @Range: 0 50
610
// @Increment: 1
611
// @RebootRequired: True
612
// @User: Advanced
613
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 5),
614
AP_GROUPEND
615
};
616
617
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
618
MSG_RAW_IMU,
619
MSG_SCALED_IMU2,
620
MSG_SCALED_IMU3,
621
MSG_SCALED_PRESSURE,
622
MSG_SCALED_PRESSURE2,
623
MSG_SCALED_PRESSURE3,
624
#if AP_AIRSPEED_ENABLED
625
MSG_AIRSPEED,
626
#endif
627
};
628
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
629
MSG_SYS_STATUS,
630
MSG_POWER_STATUS,
631
#if HAL_WITH_MCU_MONITORING
632
MSG_MCU_STATUS,
633
#endif
634
MSG_MEMINFO,
635
MSG_CURRENT_WAYPOINT,
636
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
637
MSG_GPS_RAW,
638
#endif
639
#if AP_GPS_GPS_RTK_SENDING_ENABLED
640
MSG_GPS_RTK,
641
#endif
642
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
643
MSG_GPS2_RAW,
644
#endif
645
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
646
MSG_GPS2_RTK,
647
#endif
648
MSG_NAV_CONTROLLER_OUTPUT,
649
#if AP_FENCE_ENABLED
650
MSG_FENCE_STATUS,
651
#endif
652
MSG_POSITION_TARGET_GLOBAL_INT,
653
};
654
static const ap_message STREAM_POSITION_msgs[] = {
655
MSG_LOCATION,
656
MSG_LOCAL_POSITION
657
};
658
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
659
MSG_SERVO_OUT,
660
};
661
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
662
MSG_SERVO_OUTPUT_RAW,
663
MSG_RC_CHANNELS,
664
#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED
665
MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
666
#endif
667
};
668
static const ap_message STREAM_EXTRA1_msgs[] = {
669
MSG_ATTITUDE,
670
#if AP_SIM_ENABLED
671
MSG_SIMSTATE,
672
#endif
673
MSG_AHRS2,
674
#if AP_RPM_ENABLED
675
MSG_RPM,
676
#endif
677
MSG_AOA_SSA,
678
MSG_PID_TUNING,
679
MSG_LANDING,
680
#if HAL_WITH_ESC_TELEM
681
MSG_ESC_TELEMETRY,
682
#endif
683
#if HAL_EFI_ENABLED
684
MSG_EFI_STATUS,
685
#endif
686
#if AP_AIRSPEED_HYGROMETER_ENABLE
687
MSG_HYGROMETER,
688
#endif
689
};
690
static const ap_message STREAM_EXTRA2_msgs[] = {
691
MSG_VFR_HUD
692
};
693
static const ap_message STREAM_EXTRA3_msgs[] = {
694
MSG_AHRS,
695
MSG_WIND,
696
#if AP_RANGEFINDER_ENABLED
697
MSG_RANGEFINDER,
698
#endif
699
MSG_DISTANCE_SENSOR,
700
MSG_SYSTEM_TIME,
701
#if AP_TERRAIN_AVAILABLE
702
MSG_TERRAIN_REPORT,
703
MSG_TERRAIN_REQUEST,
704
#endif
705
#if AP_BATTERY_ENABLED
706
MSG_BATTERY_STATUS,
707
#endif
708
#if HAL_MOUNT_ENABLED
709
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
710
#endif
711
#if AP_OPTICALFLOW_ENABLED
712
MSG_OPTICAL_FLOW,
713
#endif
714
#if COMPASS_CAL_ENABLED
715
MSG_MAG_CAL_REPORT,
716
MSG_MAG_CAL_PROGRESS,
717
#endif
718
MSG_EKF_STATUS_REPORT,
719
MSG_VIBRATION,
720
};
721
static const ap_message STREAM_PARAMS_msgs[] = {
722
MSG_NEXT_PARAM,
723
MSG_AVAILABLE_MODES
724
};
725
static const ap_message STREAM_ADSB_msgs[] = {
726
MSG_ADSB_VEHICLE,
727
#if AP_AIS_ENABLED
728
MSG_AIS_VESSEL,
729
#endif
730
};
731
732
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
733
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
734
MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
735
MAV_STREAM_ENTRY(STREAM_POSITION),
736
MAV_STREAM_ENTRY(STREAM_RAW_CONTROLLER),
737
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
738
MAV_STREAM_ENTRY(STREAM_EXTRA1),
739
MAV_STREAM_ENTRY(STREAM_EXTRA2),
740
MAV_STREAM_ENTRY(STREAM_EXTRA3),
741
MAV_STREAM_ENTRY(STREAM_PARAMS),
742
MAV_STREAM_ENTRY(STREAM_ADSB),
743
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
744
};
745
746
/*
747
handle a request to switch to guided mode. This happens via a
748
callback from handle_mission_item()
749
*/
750
bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)
751
{
752
return plane.control_mode->handle_guided_request(cmd.content.location);
753
}
754
755
/*
756
handle a request to change current WP altitude. This happens via a
757
callback from handle_mission_item()
758
*/
759
void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
760
{
761
plane.next_WP_loc.alt = cmd.content.location.alt;
762
if (cmd.content.location.relative_alt) {
763
plane.next_WP_loc.alt += plane.home.alt;
764
}
765
plane.next_WP_loc.relative_alt = false;
766
plane.next_WP_loc.terrain_alt = cmd.content.location.terrain_alt;
767
plane.reset_offset_altitude();
768
}
769
770
771
/*
772
handle a LANDING_TARGET command. The timestamp has been jitter corrected
773
*/
774
void GCS_MAVLINK_Plane::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
775
{
776
#if AC_PRECLAND_ENABLED
777
plane.g2.precland.handle_msg(packet, timestamp_ms);
778
#endif
779
}
780
781
MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
782
{
783
plane.in_calibration = true;
784
MAV_RESULT ret = GCS_MAVLINK::handle_command_preflight_calibration(packet, msg);
785
plane.in_calibration = false;
786
787
return ret;
788
}
789
790
void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
791
const mavlink_message_t &msg)
792
{
793
#if HAL_ADSB_ENABLED
794
plane.avoidance_adsb.handle_msg(msg);
795
#endif
796
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
797
// pass message to follow library
798
plane.g2.follow.handle_msg(msg);
799
#endif
800
GCS_MAVLINK::packetReceived(status, msg);
801
}
802
803
804
bool Plane::set_home_to_current_location(bool _lock)
805
{
806
if (!set_home_persistently(AP::gps().location())) {
807
return false;
808
}
809
if (_lock) {
810
AP::ahrs().lock_home();
811
}
812
if ((control_mode == &mode_rtl)
813
#if HAL_QUADPLANE_ENABLED
814
|| (control_mode == &mode_qrtl)
815
#endif
816
) {
817
// if in RTL head to the updated home location
818
control_mode->enter();
819
}
820
return true;
821
}
822
bool Plane::set_home(const Location& loc, bool _lock)
823
{
824
if (!AP::ahrs().set_home(loc)) {
825
return false;
826
}
827
if (_lock) {
828
AP::ahrs().lock_home();
829
}
830
if ((control_mode == &mode_rtl)
831
#if HAL_QUADPLANE_ENABLED
832
|| (control_mode == &mode_qrtl)
833
#endif
834
) {
835
// if in RTL head to the updated home location
836
control_mode->enter();
837
}
838
return true;
839
}
840
841
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
842
{
843
// sanity check location
844
if (!check_latlng(packet.x, packet.y)) {
845
return MAV_RESULT_DENIED;
846
}
847
848
Location requested_position;
849
if (!location_from_command_t(packet, requested_position)) {
850
return MAV_RESULT_DENIED;
851
}
852
853
if (isnan(packet.param4) || is_zero(packet.param4)) {
854
requested_position.loiter_ccw = 0;
855
} else {
856
requested_position.loiter_ccw = 1;
857
}
858
859
if (requested_position.sanitize(plane.current_loc)) {
860
// if the location wasn't already sane don't load it
861
return MAV_RESULT_DENIED;
862
}
863
864
#if AP_FENCE_ENABLED
865
// reject destination if outside the fence
866
if (!plane.fence.check_destination_within_fence(requested_position)) {
867
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
868
return MAV_RESULT_DENIED;
869
}
870
#endif
871
872
// location is valid load and set
873
if (((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) ||
874
(plane.control_mode == &plane.mode_guided)) {
875
plane.set_mode(plane.mode_guided, ModeReason::GCS_COMMAND);
876
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
877
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
878
#endif
879
880
// add home alt if needed
881
if (requested_position.relative_alt) {
882
requested_position.alt += plane.home.alt;
883
requested_position.relative_alt = 0;
884
}
885
886
plane.set_guided_WP(requested_position);
887
888
// Loiter radius for planes. Positive radius in meters, direction is controlled by Yaw (param4) value, parsed above
889
if (!isnan(packet.param3) && packet.param3 > 0) {
890
plane.mode_guided.set_radius_and_direction(packet.param3, requested_position.loiter_ccw);
891
}
892
893
return MAV_RESULT_ACCEPTED;
894
}
895
return MAV_RESULT_FAILED;
896
}
897
898
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
899
// these are GUIDED mode commands that are RATE or slew enabled, so you can have more powerful control than default controls.
900
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet)
901
{
902
switch(packet.command) {
903
case MAV_CMD_GUIDED_CHANGE_SPEED: {
904
// command is only valid in guided mode
905
if (plane.control_mode != &plane.mode_guided) {
906
return MAV_RESULT_FAILED;
907
}
908
909
// only airspeed commands are supported right now...
910
if (int(packet.param1) != SPEED_TYPE_AIRSPEED) { // since SPEED_TYPE is int in range 0-1 and packet.param1 is a *float* this works.
911
return MAV_RESULT_DENIED;
912
}
913
914
// reject airspeeds that are outside of the tuning envelope
915
if (packet.param2 > plane.aparm.airspeed_max || packet.param2 < plane.aparm.airspeed_min) {
916
return MAV_RESULT_DENIED;
917
}
918
919
// no need to process any new packet/s with the
920
// same airspeed any further, if we are already doing it.
921
float new_target_airspeed_cm = packet.param2 * 100;
922
if ( is_equal(new_target_airspeed_cm,plane.guided_state.target_airspeed_cm)) {
923
return MAV_RESULT_ACCEPTED;
924
}
925
plane.guided_state.target_airspeed_cm = new_target_airspeed_cm;
926
plane.guided_state.target_airspeed_time_ms = AP_HAL::millis();
927
928
if (is_zero(packet.param3)) {
929
// the user wanted /maximum acceleration, pick a large value as close enough
930
plane.guided_state.target_airspeed_accel = 1000.0f;
931
} else {
932
plane.guided_state.target_airspeed_accel = fabsf(packet.param3);
933
}
934
935
// assign an acceleration direction
936
if (plane.guided_state.target_airspeed_cm < plane.target_airspeed_cm) {
937
plane.guided_state.target_airspeed_accel *= -1.0f;
938
}
939
return MAV_RESULT_ACCEPTED;
940
}
941
942
case MAV_CMD_GUIDED_CHANGE_ALTITUDE: {
943
// command is only valid in guided
944
if (plane.control_mode != &plane.mode_guided) {
945
return MAV_RESULT_FAILED;
946
}
947
948
// disallow default value of -1 and dangerous value of zero
949
if (is_equal(packet.z, -1.0f) || is_equal(packet.z, 0.0f)){
950
return MAV_RESULT_DENIED;
951
}
952
953
Location::AltFrame new_target_alt_frame;
954
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.frame, new_target_alt_frame)) {
955
return MAV_RESULT_DENIED;
956
}
957
// keep a copy of what came in via MAVLink - this is needed for logging, but not for anything else
958
plane.guided_state.target_mav_frame = packet.frame;
959
960
const int32_t new_target_alt_cm = packet.z * 100;
961
plane.guided_state.target_location.set_alt_cm(new_target_alt_cm, new_target_alt_frame);
962
plane.guided_state.target_alt_time_ms = AP_HAL::millis();
963
964
// param3 contains the desired vertical velocity (not acceleration)
965
if (is_zero(packet.param3)) {
966
// the user wanted /maximum altitude change rate, pick a large value as close enough
967
plane.guided_state.target_alt_rate = 1000.0;
968
} else {
969
plane.guided_state.target_alt_rate = fabsf(packet.param3);
970
}
971
972
return MAV_RESULT_ACCEPTED;
973
}
974
975
case MAV_CMD_GUIDED_CHANGE_HEADING: {
976
977
// command is only valid in guided mode
978
if (plane.control_mode != &plane.mode_guided) {
979
return MAV_RESULT_FAILED;
980
}
981
982
// don't accept packets outside of [0-360] degree range
983
if (packet.param2 < 0.0f || packet.param2 >= 360.0f) {
984
return MAV_RESULT_DENIED;
985
}
986
987
float new_target_heading = radians(wrap_180(packet.param2));
988
989
switch(HEADING_TYPE(packet.param1)) {
990
case HEADING_TYPE_COURSE_OVER_GROUND:
991
// course over ground
992
plane.guided_state.target_heading_type = GUIDED_HEADING_COG;
993
plane.prev_WP_loc = plane.current_loc;
994
break;
995
case HEADING_TYPE_HEADING:
996
// normal vehicle heading
997
plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING;
998
break;
999
case HEADING_TYPE_DEFAULT:
1000
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
1001
return MAV_RESULT_ACCEPTED;
1002
default:
1003
// MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters).
1004
return MAV_RESULT_DENIED;
1005
}
1006
1007
plane.g2.guidedHeading.reset_I();
1008
1009
plane.guided_state.target_heading = new_target_heading;
1010
plane.guided_state.target_heading_accel_limit = MAX(packet.param3, 0.05f);
1011
plane.guided_state.target_heading_time_ms = AP_HAL::millis();
1012
return MAV_RESULT_ACCEPTED;
1013
}
1014
}
1015
// anything else ...
1016
return MAV_RESULT_UNSUPPORTED;
1017
}
1018
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
1019
1020
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
1021
{
1022
switch(packet.command) {
1023
1024
case MAV_CMD_DO_AUTOTUNE_ENABLE:
1025
return handle_MAV_CMD_DO_AUTOTUNE_ENABLE(packet);
1026
1027
case MAV_CMD_DO_REPOSITION:
1028
return handle_command_int_do_reposition(packet);
1029
1030
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
1031
// special 'slew-enabled' guided commands here... for speed,alt, and direction commands
1032
case MAV_CMD_GUIDED_CHANGE_SPEED:
1033
case MAV_CMD_GUIDED_CHANGE_ALTITUDE:
1034
case MAV_CMD_GUIDED_CHANGE_HEADING:
1035
return handle_command_int_guided_slew_commands(packet);
1036
#endif
1037
1038
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
1039
case MAV_CMD_DO_FOLLOW:
1040
// param1: sysid of target to follow
1041
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
1042
plane.g2.follow.set_target_sysid((uint8_t)packet.param1);
1043
return MAV_RESULT_ACCEPTED;
1044
}
1045
return MAV_RESULT_DENIED;
1046
#endif
1047
1048
#if AP_ICENGINE_ENABLED
1049
case MAV_CMD_DO_ENGINE_CONTROL:
1050
if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3, (uint32_t)packet.param4)) {
1051
return MAV_RESULT_FAILED;
1052
}
1053
return MAV_RESULT_ACCEPTED;
1054
#endif
1055
1056
case MAV_CMD_DO_CHANGE_SPEED:
1057
return handle_command_DO_CHANGE_SPEED(packet);
1058
1059
#if HAL_PARACHUTE_ENABLED
1060
case MAV_CMD_DO_PARACHUTE:
1061
return handle_MAV_CMD_DO_PARACHUTE(packet);
1062
#endif
1063
1064
#if HAL_QUADPLANE_ENABLED
1065
case MAV_CMD_DO_MOTOR_TEST:
1066
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
1067
1068
case MAV_CMD_DO_VTOL_TRANSITION:
1069
return handle_command_DO_VTOL_TRANSITION(packet);
1070
1071
case MAV_CMD_NAV_TAKEOFF:
1072
return handle_command_MAV_CMD_NAV_TAKEOFF(packet);
1073
#endif
1074
1075
case MAV_CMD_DO_GO_AROUND:
1076
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
1077
1078
case MAV_CMD_DO_RETURN_PATH_START:
1079
// attempt to rejoin after the next DO_RETURN_PATH_START command in the mission
1080
if (plane.have_position && plane.mission.jump_to_closest_mission_leg(plane.current_loc)) {
1081
plane.mission.set_force_resume(true);
1082
if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {
1083
return MAV_RESULT_ACCEPTED;
1084
}
1085
// mode change failed, revert force resume flag
1086
plane.mission.set_force_resume(false);
1087
}
1088
return MAV_RESULT_FAILED;
1089
1090
case MAV_CMD_DO_LAND_START:
1091
// attempt to switch to next DO_LAND_START command in the mission
1092
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
1093
plane.mission.set_force_resume(true);
1094
if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {
1095
return MAV_RESULT_ACCEPTED;
1096
}
1097
// mode change failed, revert force resume flag
1098
plane.mission.set_force_resume(false);
1099
}
1100
return MAV_RESULT_FAILED;
1101
1102
case MAV_CMD_MISSION_START:
1103
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
1104
// first-item/last item not supported
1105
return MAV_RESULT_DENIED;
1106
}
1107
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
1108
return MAV_RESULT_ACCEPTED;
1109
1110
case MAV_CMD_NAV_LOITER_UNLIM:
1111
plane.set_mode(plane.mode_loiter, ModeReason::GCS_COMMAND);
1112
return MAV_RESULT_ACCEPTED;
1113
1114
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1115
plane.set_mode(plane.mode_rtl, ModeReason::GCS_COMMAND);
1116
return MAV_RESULT_ACCEPTED;
1117
1118
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
1119
case MAV_CMD_SET_HAGL:
1120
plane.handle_external_hagl(packet);
1121
return MAV_RESULT_ACCEPTED;
1122
#endif
1123
1124
default:
1125
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
1126
}
1127
}
1128
1129
MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
1130
{
1131
// if we're in failsafe modes (e.g., RTL, LOITER) or in pilot
1132
// controlled modes (e.g., MANUAL, TRAINING)
1133
// this command should be ignored since it comes in from GCS
1134
// or a companion computer:
1135
if ((!plane.control_mode->is_guided_mode()) &&
1136
(plane.control_mode != &plane.mode_auto)) {
1137
// failed
1138
return MAV_RESULT_FAILED;
1139
}
1140
1141
if (plane.do_change_speed(packet.param1, packet.param2, packet.param3)) {
1142
return MAV_RESULT_ACCEPTED;
1143
}
1144
return MAV_RESULT_FAILED;
1145
}
1146
1147
#if HAL_QUADPLANE_ENABLED
1148
#if AP_MAVLINK_COMMAND_LONG_ENABLED
1149
void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out)
1150
{
1151
// convert to MAV_FRAME_LOCAL_OFFSET_NED, "NED local tangent frame
1152
// with origin that travels with the vehicle"
1153
out = {};
1154
out.target_system = in.target_system;
1155
out.target_component = in.target_component;
1156
out.frame = MAV_FRAME_LOCAL_OFFSET_NED;
1157
out.command = in.command;
1158
// out.current = 0;
1159
// out.autocontinue = 0;
1160
// out.param1 = in.param1; // we only use the "z" parameter in this command:
1161
// out.param2 = in.param2;
1162
// out.param3 = in.param3;
1163
// out.param4 = in.param4;
1164
// out.x = 0; // we don't handle positioning when doing takeoffs
1165
// out.y = 0;
1166
out.z = -in.param7; // up -> down
1167
}
1168
1169
void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame)
1170
{
1171
switch (in.command) {
1172
case MAV_CMD_NAV_TAKEOFF:
1173
convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(in, out);
1174
return;
1175
}
1176
return GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(in, out, frame);
1177
}
1178
#endif // AP_MAVLINK_COMMAND_LONG_ENABLED
1179
1180
MAV_RESULT GCS_MAVLINK_Plane::handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet)
1181
{
1182
float takeoff_alt = packet.z;
1183
switch (packet.frame) {
1184
case MAV_FRAME_LOCAL_OFFSET_NED: // "NED local tangent frame with origin that travels with the vehicle"
1185
takeoff_alt = -takeoff_alt; // down -> up
1186
break;
1187
default:
1188
return MAV_RESULT_DENIED; // "is supported but has invalid parameters"
1189
}
1190
if (!plane.quadplane.available()) {
1191
return MAV_RESULT_FAILED;
1192
}
1193
if (!plane.quadplane.do_user_takeoff(takeoff_alt)) {
1194
return MAV_RESULT_FAILED;
1195
}
1196
return MAV_RESULT_ACCEPTED;
1197
}
1198
#endif
1199
1200
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet)
1201
{
1202
// param1 : enable/disable
1203
plane.autotune_enable(!is_zero(packet.param1));
1204
return MAV_RESULT_ACCEPTED;
1205
}
1206
1207
#if HAL_PARACHUTE_ENABLED
1208
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
1209
{
1210
// configure or release parachute
1211
switch ((uint16_t)packet.param1) {
1212
case PARACHUTE_DISABLE:
1213
plane.parachute.enabled(false);
1214
return MAV_RESULT_ACCEPTED;
1215
case PARACHUTE_ENABLE:
1216
plane.parachute.enabled(true);
1217
return MAV_RESULT_ACCEPTED;
1218
case PARACHUTE_RELEASE:
1219
// treat as a manual release which performs some additional check of altitude
1220
if (plane.parachute.released()) {
1221
gcs().send_text(MAV_SEVERITY_NOTICE, "Parachute already released");
1222
return MAV_RESULT_FAILED;
1223
}
1224
if (!plane.parachute.enabled()) {
1225
gcs().send_text(MAV_SEVERITY_NOTICE, "Parachute not enabled");
1226
return MAV_RESULT_FAILED;
1227
}
1228
if (!plane.parachute_manual_release()) {
1229
return MAV_RESULT_FAILED;
1230
}
1231
return MAV_RESULT_ACCEPTED;
1232
default:
1233
break;
1234
}
1235
return MAV_RESULT_FAILED;
1236
}
1237
#endif
1238
1239
1240
#if HAL_QUADPLANE_ENABLED
1241
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
1242
{
1243
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
1244
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
1245
// param3 : throttle (range depends upon param2)
1246
// param4 : timeout (in seconds)
1247
// param5 : motor count (number of motors to test in sequence)
1248
return plane.quadplane.mavlink_motor_test_start(chan,
1249
(uint8_t)packet.param1,
1250
(uint8_t)packet.param2,
1251
(uint16_t)packet.param3,
1252
packet.param4,
1253
(uint8_t)packet.x);
1254
}
1255
1256
MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet)
1257
{
1258
if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) {
1259
return MAV_RESULT_FAILED;
1260
}
1261
return MAV_RESULT_ACCEPTED;
1262
}
1263
#endif
1264
1265
// this is called on receipt of a MANUAL_CONTROL packet and is
1266
// expected to call manual_override to override RC input on desired
1267
// axes.
1268
void GCS_MAVLINK_Plane::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
1269
{
1270
manual_override(plane.channel_roll, packet.y, 1000, 2000, tnow);
1271
manual_override(plane.channel_pitch, packet.x, 1000, 2000, tnow, true);
1272
manual_override(plane.channel_throttle, packet.z, 0, 1000, tnow);
1273
manual_override(plane.channel_rudder, packet.r, 1000, 2000, tnow);
1274
}
1275
1276
void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)
1277
{
1278
switch (msg.msgid) {
1279
1280
case MAVLINK_MSG_ID_TERRAIN_DATA:
1281
case MAVLINK_MSG_ID_TERRAIN_CHECK:
1282
#if AP_TERRAIN_AVAILABLE
1283
plane.terrain.handle_data(chan, msg);
1284
#endif
1285
break;
1286
1287
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
1288
handle_set_attitude_target(msg);
1289
break;
1290
1291
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
1292
handle_set_position_target_local_ned(msg);
1293
break;
1294
1295
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
1296
handle_set_position_target_global_int(msg);
1297
break;
1298
1299
default:
1300
GCS_MAVLINK::handle_message(msg);
1301
break;
1302
} // end switch
1303
} // end handle mavlink
1304
1305
void GCS_MAVLINK_Plane::handle_set_attitude_target(const mavlink_message_t &msg)
1306
{
1307
// Only allow companion computer (or other external controller) to
1308
// control attitude in GUIDED mode. We DON'T want external control
1309
// in e.g., RTL, CICLE. Specifying a single mode for companion
1310
// computer control is more safe (even more so when using
1311
// FENCE_ACTION = 4 for geofence failures).
1312
if (plane.control_mode != &plane.mode_guided) { // don't screw up failsafes
1313
return;
1314
}
1315
1316
mavlink_set_attitude_target_t att_target;
1317
mavlink_msg_set_attitude_target_decode(&msg, &att_target);
1318
1319
// Mappings: If any of these bits are set, the corresponding input should be ignored.
1320
// NOTE, when parsing the bits we invert them for easier interpretation but transport has them inverted
1321
// bit 1: body roll rate
1322
// bit 2: body pitch rate
1323
// bit 3: body yaw rate
1324
// bit 4: unknown
1325
// bit 5: unknown
1326
// bit 6: reserved
1327
// bit 7: throttle
1328
// bit 8: attitude
1329
1330
// if not setting all Quaternion values, use _rate flags to indicate which fields.
1331
1332
// Extract the Euler roll angle from the Quaternion.
1333
Quaternion q(att_target.q[0], att_target.q[1],
1334
att_target.q[2], att_target.q[3]);
1335
1336
// NOTE: att_target.type_mask is inverted for easier interpretation
1337
att_target.type_mask = att_target.type_mask ^ 0xFF;
1338
1339
uint8_t attitude_mask = att_target.type_mask & 0b10000111; // q plus rpy
1340
1341
uint32_t now = AP_HAL::millis();
1342
if ((attitude_mask & 0b10000001) || // partial, including roll
1343
(attitude_mask == 0b10000000)) { // all angles
1344
plane.guided_state.forced_rpy_cd.x = degrees(q.get_euler_roll()) * 100.0f;
1345
1346
// Update timer for external roll to the nav control
1347
plane.guided_state.last_forced_rpy_ms.x = now;
1348
}
1349
1350
if ((attitude_mask & 0b10000010) || // partial, including pitch
1351
(attitude_mask == 0b10000000)) { // all angles
1352
plane.guided_state.forced_rpy_cd.y = degrees(q.get_euler_pitch()) * 100.0f;
1353
1354
// Update timer for external pitch to the nav control
1355
plane.guided_state.last_forced_rpy_ms.y = now;
1356
}
1357
1358
if ((attitude_mask & 0b10000100) || // partial, including yaw
1359
(attitude_mask == 0b10000000)) { // all angles
1360
plane.guided_state.forced_rpy_cd.z = degrees(q.get_euler_yaw()) * 100.0f;
1361
1362
// Update timer for external yaw to the nav control
1363
plane.guided_state.last_forced_rpy_ms.z = now;
1364
}
1365
if (att_target.type_mask & 0b01000000) { // throttle
1366
plane.guided_state.forced_throttle = att_target.thrust * 100.0f;
1367
1368
// Update timer for external throttle
1369
plane.guided_state.last_forced_throttle_ms = now;
1370
}
1371
}
1372
1373
void GCS_MAVLINK_Plane::handle_set_position_target_local_ned(const mavlink_message_t &msg)
1374
{
1375
// decode packet
1376
mavlink_set_position_target_local_ned_t packet;
1377
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
1378
1379
// exit if vehicle is not in Guided mode
1380
if (plane.control_mode != &plane.mode_guided) {
1381
return;
1382
}
1383
1384
// only local moves for now
1385
if (packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
1386
return;
1387
}
1388
1389
// just do altitude for now
1390
plane.next_WP_loc.alt += -packet.z*100.0;
1391
gcs().send_text(MAV_SEVERITY_INFO, "Change alt to %.1f",
1392
(double)((plane.next_WP_loc.alt - plane.home.alt)*0.01));
1393
}
1394
1395
void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_message_t &msg)
1396
{
1397
// Only want to allow companion computer position control when
1398
// in a certain mode to avoid inadvertently sending these
1399
// kinds of commands when the autopilot is responding to problems
1400
// in modes such as RTL, CIRCLE, etc. Specifying ONLY one mode
1401
// for companion computer control is more safe (provided
1402
// one uses the FENCE_ACTION = 4 (RTL) for geofence failures).
1403
if (plane.control_mode != &plane.mode_guided) {
1404
//don't screw up failsafes
1405
return;
1406
}
1407
1408
mavlink_set_position_target_global_int_t pos_target;
1409
mavlink_msg_set_position_target_global_int_decode(&msg, &pos_target);
1410
1411
Location::AltFrame frame;
1412
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)pos_target.coordinate_frame, frame)) {
1413
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
1414
// Even though other parts of the command may be valid, reject the whole thing.
1415
return;
1416
}
1417
1418
// Unexpectedly, the mask is expecting "ones" for dimensions that should
1419
// be IGNORNED rather than INCLUDED. See mavlink documentation of the
1420
// SET_POSITION_TARGET_GLOBAL_INT message, type_mask field.
1421
const uint16_t alt_mask = 0b1111111111111011; // (z mask at bit 3)
1422
1423
AP_Mission::Mission_Command cmd = {0};
1424
1425
if (pos_target.type_mask & alt_mask)
1426
{
1427
const int32_t alt_cm = pos_target.alt * 100;
1428
cmd.content.location.set_alt_cm(alt_cm, frame);
1429
handle_change_alt_request(cmd);
1430
}
1431
}
1432
1433
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
1434
{
1435
const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet);
1436
if (result != MAV_RESULT_ACCEPTED) {
1437
return result;
1438
}
1439
1440
// if you change this you must change handle_mission_set_current
1441
plane.auto_state.next_wp_crosstrack = false;
1442
if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) {
1443
plane.mission.resume();
1444
}
1445
1446
return result;
1447
}
1448
1449
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
1450
void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg)
1451
{
1452
// if you change this you must change handle_command_do_set_mission_current
1453
plane.auto_state.next_wp_crosstrack = false;
1454
GCS_MAVLINK::handle_mission_set_current(mission, msg);
1455
if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) {
1456
plane.mission.resume();
1457
}
1458
}
1459
#endif
1460
1461
uint64_t GCS_MAVLINK_Plane::capabilities() const
1462
{
1463
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
1464
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
1465
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
1466
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
1467
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
1468
#if AP_TERRAIN_AVAILABLE
1469
(plane.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
1470
#endif
1471
GCS_MAVLINK::capabilities());
1472
}
1473
1474
#if HAL_HIGH_LATENCY2_ENABLED
1475
int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const
1476
{
1477
AP_AHRS &ahrs = AP::ahrs();
1478
Location global_position_current;
1479
UNUSED_RESULT(ahrs.get_location(global_position_current));
1480
1481
#if HAL_QUADPLANE_ENABLED
1482
const QuadPlane &quadplane = plane.quadplane;
1483
//return units are m
1484
if (quadplane.show_vtol_view()) {
1485
return (plane.control_mode != &plane.mode_qstabilize) ? 0.01 * (global_position_current.alt + quadplane.pos_control->get_pos_error_z_cm()) : 0;
1486
}
1487
#endif
1488
return 0.01 * (global_position_current.alt + plane.calc_altitude_error_cm());
1489
}
1490
1491
uint8_t GCS_MAVLINK_Plane::high_latency_tgt_heading() const
1492
{
1493
// return units are deg/2
1494
#if HAL_QUADPLANE_ENABLED
1495
const QuadPlane &quadplane = plane.quadplane;
1496
if (quadplane.show_vtol_view()) {
1497
const Vector3f &targets = quadplane.attitude_control->get_att_target_euler_cd();
1498
return ((uint16_t)(targets.z * 0.01)) / 2;
1499
}
1500
#endif
1501
const AP_Navigation *nav_controller = plane.nav_controller;
1502
// need to convert -18000->18000 to 0->360/2
1503
return wrap_360_cd(nav_controller->target_bearing_cd() ) / 200;
1504
}
1505
1506
// return units are dm
1507
uint16_t GCS_MAVLINK_Plane::high_latency_tgt_dist() const
1508
{
1509
#if HAL_QUADPLANE_ENABLED
1510
const QuadPlane &quadplane = plane.quadplane;
1511
if (quadplane.show_vtol_view()) {
1512
bool wp_nav_valid = quadplane.using_wp_nav();
1513
return (wp_nav_valid ? MIN(quadplane.wp_nav->get_wp_distance_to_destination(), UINT16_MAX) : 0) / 10;
1514
}
1515
#endif
1516
1517
return MIN(plane.auto_state.wp_distance, UINT16_MAX) / 10;
1518
}
1519
1520
uint8_t GCS_MAVLINK_Plane::high_latency_tgt_airspeed() const
1521
{
1522
// return units are m/s*5
1523
return plane.target_airspeed_cm * 0.05;
1524
}
1525
1526
uint8_t GCS_MAVLINK_Plane::high_latency_wind_speed() const
1527
{
1528
Vector3f wind;
1529
wind = AP::ahrs().wind_estimate();
1530
1531
// return units are m/s*5
1532
return MIN(wind.length() * 5, UINT8_MAX);
1533
}
1534
1535
uint8_t GCS_MAVLINK_Plane::high_latency_wind_direction() const
1536
{
1537
const Vector3f wind = AP::ahrs().wind_estimate();
1538
1539
// return units are deg/2
1540
// need to convert -180->180 to 0->360/2
1541
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
1542
}
1543
#endif // HAL_HIGH_LATENCY2_ENABLED
1544
1545
MAV_VTOL_STATE GCS_MAVLINK_Plane::vtol_state() const
1546
{
1547
#if !HAL_QUADPLANE_ENABLED
1548
return MAV_VTOL_STATE_UNDEFINED;
1549
#else
1550
if (!plane.quadplane.available()) {
1551
return MAV_VTOL_STATE_UNDEFINED;
1552
}
1553
1554
return plane.quadplane.transition->get_mav_vtol_state();
1555
#endif
1556
};
1557
1558
MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const
1559
{
1560
if (plane.is_flying()) {
1561
// note that Q-modes almost always consider themselves as flying
1562
return MAV_LANDED_STATE_IN_AIR;
1563
}
1564
1565
return MAV_LANDED_STATE_ON_GROUND;
1566
}
1567
1568
// Send the mode with the given index (not mode number!) return the total number of modes
1569
// Index starts at 1
1570
uint8_t GCS_MAVLINK_Plane::send_available_mode(uint8_t index) const
1571
{
1572
// Fixed wing modes
1573
const Mode* fw_modes[] {
1574
&plane.mode_manual,
1575
&plane.mode_circle,
1576
&plane.mode_stabilize,
1577
&plane.mode_training,
1578
&plane.mode_acro,
1579
&plane.mode_fbwa,
1580
&plane.mode_fbwb,
1581
&plane.mode_cruise,
1582
&plane.mode_autotune,
1583
&plane.mode_auto,
1584
&plane.mode_rtl,
1585
&plane.mode_loiter,
1586
#if HAL_ADSB_ENABLED
1587
&plane.mode_avoidADSB,
1588
#endif
1589
&plane.mode_guided,
1590
&plane.mode_initializing,
1591
&plane.mode_takeoff,
1592
#if HAL_SOARING_ENABLED
1593
&plane.mode_thermal,
1594
#endif
1595
#if MODE_AUTOLAND_ENABLED
1596
&plane.mode_autoland,
1597
#endif
1598
};
1599
1600
const uint8_t fw_mode_count = ARRAY_SIZE(fw_modes);
1601
1602
// Fixedwing modes are always present
1603
uint8_t mode_count = fw_mode_count;
1604
1605
#if HAL_QUADPLANE_ENABLED
1606
// Quadplane modes
1607
const Mode* q_modes[] {
1608
&plane.mode_qstabilize,
1609
&plane.mode_qhover,
1610
&plane.mode_qloiter,
1611
&plane.mode_qland,
1612
&plane.mode_qrtl,
1613
&plane.mode_qacro,
1614
&plane.mode_loiter_qland,
1615
#if QAUTOTUNE_ENABLED
1616
&plane.mode_qautotune,
1617
#endif
1618
};
1619
1620
// Quadplane modes must be enabled
1621
if (plane.quadplane.available()) {
1622
mode_count += ARRAY_SIZE(q_modes);
1623
}
1624
#endif // HAL_QUADPLANE_ENABLED
1625
1626
1627
// Convert to zero indexed
1628
const uint8_t index_zero = index - 1;
1629
if (index_zero >= mode_count) {
1630
// Mode does not exist!?
1631
return mode_count;
1632
}
1633
1634
// Ask the mode for its name and number
1635
const char* name;
1636
uint8_t mode_number;
1637
1638
if (index_zero < fw_mode_count) {
1639
// A fixedwing mode
1640
name = fw_modes[index_zero]->name();
1641
mode_number = (uint8_t)fw_modes[index_zero]->mode_number();
1642
1643
} else {
1644
#if HAL_QUADPLANE_ENABLED
1645
// A Quadplane mode
1646
const uint8_t q_index = index_zero - fw_mode_count;
1647
name = q_modes[q_index]->name();
1648
mode_number = (uint8_t)q_modes[q_index]->mode_number();
1649
#else
1650
// Should not endup here
1651
return mode_count;
1652
#endif
1653
}
1654
1655
mavlink_msg_available_modes_send(
1656
chan,
1657
mode_count,
1658
index,
1659
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
1660
mode_number,
1661
0, // MAV_MODE_PROPERTY bitmask
1662
name
1663
);
1664
1665
return mode_count;
1666
}
1667
1668