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