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/ArduSub/GCS_MAVLink_Sub.cpp
Views: 1798
1
#include "Sub.h"
2
3
#include "GCS_MAVLink_Sub.h"
4
#include <AP_RPM/AP_RPM_config.h>
5
6
MAV_TYPE GCS_Sub::frame_type() const
7
{
8
return MAV_TYPE_SUBMARINE;
9
}
10
11
MAV_MODE GCS_MAVLINK_Sub::base_mode() const
12
{
13
uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
14
15
// work out the base_mode. This value is not very useful
16
// for APM, but we calculate it as best we can so a generic
17
// MAVLink enabled ground station can work out something about
18
// what the MAV is up to. The actual bit values are highly
19
// ambiguous for most of the APM flight modes. In practice, you
20
// only get useful information from the custom_mode, which maps to
21
// the APM flight mode and has a well defined meaning in the
22
// ArduPlane documentation
23
switch (sub.control_mode) {
24
case Mode::Number::AUTO:
25
case Mode::Number::GUIDED:
26
case Mode::Number::CIRCLE:
27
case Mode::Number::POSHOLD:
28
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
29
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
30
// APM does in any mode, as that is defined as "system finds its own goal
31
// positions", which APM does not currently do
32
break;
33
default:
34
break;
35
}
36
37
// all modes except INITIALISING have some form of manual
38
// override if stick mixing is enabled
39
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
40
41
if (sub.motors.armed()) {
42
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
43
}
44
45
// indicate we have set a custom mode
46
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
47
48
return (MAV_MODE)_base_mode;
49
}
50
51
uint32_t GCS_Sub::custom_mode() const
52
{
53
return (uint32_t)sub.control_mode;
54
}
55
56
MAV_STATE GCS_MAVLINK_Sub::vehicle_system_status() const
57
{
58
// set system as critical if any failsafe have triggered
59
if (sub.any_failsafe_triggered()) {
60
return MAV_STATE_CRITICAL;
61
}
62
63
if (sub.motors.armed()) {
64
return MAV_STATE_ACTIVE;
65
}
66
if (!sub.ap.initialised) {
67
return MAV_STATE_BOOT;
68
}
69
70
return MAV_STATE_STANDBY;
71
}
72
73
void GCS_MAVLINK_Sub::send_banner()
74
{
75
GCS_MAVLINK::send_banner();
76
send_text(MAV_SEVERITY_INFO, "Frame: %s", sub.motors.get_frame_string());
77
}
78
79
void GCS_MAVLINK_Sub::send_nav_controller_output() const
80
{
81
const Vector3f &targets = sub.attitude_control.get_att_target_euler_cd();
82
mavlink_msg_nav_controller_output_send(
83
chan,
84
targets.x * 1.0e-2f,
85
targets.y * 1.0e-2f,
86
targets.z * 1.0e-2f,
87
sub.wp_nav.get_wp_bearing_to_destination() * 1.0e-2f,
88
MIN(sub.wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX),
89
sub.pos_control.get_pos_error_z_cm() * 1.0e-2f,
90
0,
91
0);
92
}
93
94
int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const
95
{
96
return (int16_t)(sub.motors.get_throttle() * 100);
97
}
98
99
float GCS_MAVLINK_Sub::vfr_hud_alt() const
100
{
101
return sub.get_alt_msl();
102
}
103
104
// Work around to get temperature sensor data out
105
void GCS_MAVLINK_Sub::send_scaled_pressure3()
106
{
107
#if AP_TEMPERATURE_SENSOR_ENABLED
108
float temperature;
109
if (!sub.temperature_sensor.get_temperature(temperature)) {
110
return;
111
}
112
mavlink_msg_scaled_pressure3_send(
113
chan,
114
AP_HAL::millis(),
115
0,
116
0,
117
temperature * 100,
118
0); // TODO: use differential pressure temperature
119
#endif
120
}
121
122
bool GCS_MAVLINK_Sub::send_info()
123
{
124
// Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok
125
// Name is char[10]
126
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
127
send_named_float("CamTilt",
128
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));
129
130
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
131
send_named_float("CamPan",
132
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));
133
134
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
135
send_named_float("TetherTrn",
136
sub.quarter_turn_count/4);
137
138
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
139
send_named_float("Lights1",
140
SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f);
141
142
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
143
send_named_float("Lights2",
144
SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);
145
146
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
147
send_named_float("PilotGain", sub.gain);
148
149
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
150
send_named_float("InputHold", sub.input_hold_engaged);
151
152
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
153
send_named_float("RollPitch", sub.roll_pitch_flag);
154
155
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
156
send_named_float("RFTarget", sub.mode_surftrak.get_rangefinder_target_cm() * 0.01f);
157
158
return true;
159
}
160
161
/*
162
send PID tuning message
163
*/
164
void GCS_MAVLINK_Sub::send_pid_tuning()
165
{
166
const Parameters &g = sub.g;
167
AP_AHRS &ahrs = AP::ahrs();
168
AC_AttitudeControl_Sub &attitude_control = sub.attitude_control;
169
170
const Vector3f &gyro = ahrs.get_gyro();
171
if (g.gcs_pid_mask & 1) {
172
const AP_PIDInfo &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();
173
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
174
pid_info.target*0.01f,
175
degrees(gyro.x),
176
pid_info.FF*0.01f,
177
pid_info.P*0.01f,
178
pid_info.I*0.01f,
179
pid_info.D*0.01f,
180
pid_info.slew_rate,
181
pid_info.Dmod);
182
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
183
return;
184
}
185
}
186
if (g.gcs_pid_mask & 2) {
187
const AP_PIDInfo &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info();
188
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
189
pid_info.target*0.01f,
190
degrees(gyro.y),
191
pid_info.FF*0.01f,
192
pid_info.P*0.01f,
193
pid_info.I*0.01f,
194
pid_info.D*0.01f,
195
pid_info.slew_rate,
196
pid_info.Dmod);
197
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
198
return;
199
}
200
}
201
if (g.gcs_pid_mask & 4) {
202
const AP_PIDInfo &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info();
203
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
204
pid_info.target*0.01f,
205
degrees(gyro.z),
206
pid_info.FF*0.01f,
207
pid_info.P*0.01f,
208
pid_info.I*0.01f,
209
pid_info.D*0.01f,
210
pid_info.slew_rate,
211
pid_info.Dmod);
212
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
213
return;
214
}
215
}
216
if (g.gcs_pid_mask & 8) {
217
const AP_PIDInfo &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info();
218
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
219
pid_info.target*0.01f,
220
-(ahrs.get_accel_ef().z + GRAVITY_MSS),
221
pid_info.FF*0.01f,
222
pid_info.P*0.01f,
223
pid_info.I*0.01f,
224
pid_info.D*0.01f,
225
pid_info.slew_rate,
226
pid_info.Dmod);
227
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
228
return;
229
}
230
}
231
}
232
233
uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const
234
{
235
return sub.g.sysid_my_gcs;
236
}
237
238
bool GCS_Sub::vehicle_initialised() const {
239
return sub.ap.initialised;
240
}
241
242
// try to send a message, return false if it won't fit in the serial tx buffer
243
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
244
{
245
switch (id) {
246
247
case MSG_NAMED_FLOAT:
248
send_info();
249
break;
250
251
#if AP_TERRAIN_AVAILABLE
252
case MSG_TERRAIN_REQUEST:
253
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
254
sub.terrain.send_request(chan);
255
break;
256
case MSG_TERRAIN_REPORT:
257
CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);
258
sub.terrain.send_report(chan);
259
break;
260
#endif
261
262
default:
263
return GCS_MAVLINK::try_send_message(id);
264
}
265
266
return true;
267
}
268
269
270
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
271
// @Param: RAW_SENS
272
// @DisplayName: Raw sensor stream rate
273
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, AIRSPEED, and SENSOR_OFFSETS to ground station
274
// @Units: Hz
275
// @Range: 0 50
276
// @Increment: 1
277
// @RebootRequired: True
278
// @User: Advanced
279
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 2),
280
281
// @Param: EXT_STAT
282
// @DisplayName: Extended status stream rate to ground station
283
// @Description: Stream rate of SYS_STATUS, MEMINFO, MISSION_CURRENT, GPS_RAW_INT, NAV_CONTROLLER_OUTPUT, and LIMITS_STATUS to ground station
284
// @Units: Hz
285
// @Range: 0 50
286
// @Increment: 1
287
// @RebootRequired: True
288
// @User: Advanced
289
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 2),
290
291
// @Param: RC_CHAN
292
// @DisplayName: RC Channel stream rate to ground station
293
// @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS_RAW to ground station
294
// @Units: Hz
295
// @Range: 0 50
296
// @Increment: 1
297
// @RebootRequired: True
298
// @User: Advanced
299
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 2),
300
301
// @Param: POSITION
302
// @DisplayName: Position stream rate to ground station
303
// @Description: Stream rate of GLOBAL_POSITION_INT to ground station
304
// @Units: Hz
305
// @Range: 0 50
306
// @Increment: 1
307
// @RebootRequired: True
308
// @User: Advanced
309
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 3),
310
311
// @Param: EXTRA1
312
// @DisplayName: Extra data type 1 stream rate to ground station
313
// @Description: Stream rate of ATTITUDE and SIMSTATE (SITL only) to ground station
314
// @Units: Hz
315
// @Range: 0 50
316
// @Increment: 1
317
// @RebootRequired: True
318
// @User: Advanced
319
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 10),
320
321
// @Param: EXTRA2
322
// @DisplayName: Extra data type 2 stream rate to ground station
323
// @Description: Stream rate of VFR_HUD to ground station
324
// @Units: Hz
325
// @Range: 0 50
326
// @Increment: 1
327
// @RebootRequired: True
328
// @User: Advanced
329
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 10),
330
331
// @Param: EXTRA3
332
// @DisplayName: Extra data type 3 stream rate to ground station
333
// @Description: Stream rate of AHRS and SYSTEM_TIME to ground station
334
// @Units: Hz
335
// @Range: 0 50
336
// @Increment: 1
337
// @RebootRequired: True
338
// @User: Advanced
339
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 3),
340
341
// @Param: PARAMS
342
// @DisplayName: Parameter stream rate to ground station
343
// @Description: Stream rate of PARAM_VALUE to ground station
344
// @Units: Hz
345
// @Range: 0 50
346
// @Increment: 1
347
// @RebootRequired: True
348
// @User: Advanced
349
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_PARAMS], 0),
350
AP_GROUPEND
351
};
352
353
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
354
MSG_RAW_IMU,
355
MSG_SCALED_IMU2,
356
MSG_SCALED_IMU3,
357
MSG_SCALED_PRESSURE,
358
MSG_SCALED_PRESSURE2,
359
MSG_SCALED_PRESSURE3,
360
#if AP_AIRSPEED_ENABLED
361
MSG_AIRSPEED,
362
#endif
363
};
364
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
365
MSG_SYS_STATUS,
366
MSG_POWER_STATUS,
367
#if HAL_WITH_MCU_MONITORING
368
MSG_MCU_STATUS,
369
#endif
370
MSG_MEMINFO,
371
MSG_CURRENT_WAYPOINT,
372
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
373
MSG_GPS_RAW,
374
#endif
375
#if AP_GPS_GPS_RTK_SENDING_ENABLED
376
MSG_GPS_RTK,
377
#endif
378
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
379
MSG_GPS2_RAW,
380
#endif
381
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
382
MSG_GPS2_RTK,
383
#endif
384
MSG_NAV_CONTROLLER_OUTPUT,
385
#if AP_FENCE_ENABLED
386
MSG_FENCE_STATUS,
387
#endif
388
MSG_NAMED_FLOAT
389
};
390
static const ap_message STREAM_POSITION_msgs[] = {
391
MSG_LOCATION,
392
MSG_LOCAL_POSITION
393
};
394
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
395
MSG_SERVO_OUTPUT_RAW,
396
MSG_RC_CHANNELS,
397
#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED
398
MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
399
#endif
400
};
401
static const ap_message STREAM_EXTRA1_msgs[] = {
402
MSG_ATTITUDE,
403
#if AP_SIM_ENABLED
404
MSG_SIMSTATE,
405
#endif
406
MSG_AHRS2,
407
MSG_PID_TUNING
408
};
409
static const ap_message STREAM_EXTRA2_msgs[] = {
410
MSG_VFR_HUD
411
};
412
static const ap_message STREAM_EXTRA3_msgs[] = {
413
MSG_AHRS,
414
MSG_SYSTEM_TIME,
415
#if AP_RANGEFINDER_ENABLED
416
MSG_RANGEFINDER,
417
#endif
418
MSG_DISTANCE_SENSOR,
419
#if AP_TERRAIN_AVAILABLE
420
MSG_TERRAIN_REQUEST,
421
MSG_TERRAIN_REPORT,
422
#endif
423
#if AP_BATTERY_ENABLED
424
MSG_BATTERY_STATUS,
425
#endif
426
#if HAL_MOUNT_ENABLED
427
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
428
#endif
429
#if AP_OPTICALFLOW_ENABLED
430
MSG_OPTICAL_FLOW,
431
#endif
432
#if COMPASS_CAL_ENABLED
433
MSG_MAG_CAL_REPORT,
434
MSG_MAG_CAL_PROGRESS,
435
#endif
436
MSG_EKF_STATUS_REPORT,
437
MSG_VIBRATION,
438
#if AP_RPM_ENABLED
439
MSG_RPM,
440
#endif
441
#if HAL_WITH_ESC_TELEM
442
MSG_ESC_TELEMETRY,
443
#endif
444
};
445
static const ap_message STREAM_PARAMS_msgs[] = {
446
MSG_NEXT_PARAM,
447
MSG_AVAILABLE_MODES
448
};
449
450
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
451
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
452
MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
453
MAV_STREAM_ENTRY(STREAM_POSITION),
454
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
455
MAV_STREAM_ENTRY(STREAM_EXTRA1),
456
MAV_STREAM_ENTRY(STREAM_EXTRA2),
457
MAV_STREAM_ENTRY(STREAM_EXTRA3),
458
MAV_STREAM_ENTRY(STREAM_PARAMS),
459
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
460
};
461
462
bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
463
{
464
return sub.do_guided(cmd);
465
}
466
467
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)
468
{
469
if (sub.motors.armed()) {
470
gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");
471
return MAV_RESULT_FAILED;
472
}
473
474
if (!sub.control_check_barometer()) {
475
return MAV_RESULT_FAILED;
476
}
477
478
AP::baro().calibrate(true);
479
return MAV_RESULT_ACCEPTED;
480
}
481
482
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
483
{
484
if (packet.y == 1) {
485
// compassmot calibration
486
//result = sub.mavlink_compassmot(chan);
487
gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");
488
return MAV_RESULT_UNSUPPORTED;
489
}
490
491
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
492
}
493
494
MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)
495
{
496
if (!roi_loc.check_latlng()) {
497
return MAV_RESULT_FAILED;
498
}
499
sub.mode_auto.set_auto_yaw_roi(roi_loc);
500
return MAV_RESULT_ACCEPTED;
501
}
502
503
MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
504
{
505
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
506
if (!sub.flightmode->in_guided_mode() && !change_modes) {
507
return MAV_RESULT_DENIED;
508
}
509
510
// sanity check location
511
if (!check_latlng(packet.x, packet.y)) {
512
return MAV_RESULT_DENIED;
513
}
514
515
Location request_location;
516
if (!location_from_command_t(packet, request_location)) {
517
return MAV_RESULT_DENIED;
518
}
519
520
if (request_location.sanitize(sub.current_loc)) {
521
// if the location wasn't already sane don't load it
522
return MAV_RESULT_DENIED; // failed as the location is not valid
523
}
524
525
// we need to do this first, as we don't want to change the flight mode unless we can also set the target
526
if (!sub.mode_guided.guided_set_destination(request_location)) {
527
return MAV_RESULT_FAILED;
528
}
529
530
if (!sub.flightmode->in_guided_mode()) {
531
if (!sub.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {
532
return MAV_RESULT_FAILED;
533
}
534
// the position won't have been loaded if we had to change the flight mode, so load it again
535
if (!sub.mode_guided.guided_set_destination(request_location)) {
536
return MAV_RESULT_FAILED;
537
}
538
}
539
540
return MAV_RESULT_ACCEPTED;
541
}
542
543
MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
544
{
545
switch(packet.command) {
546
547
case MAV_CMD_CONDITION_YAW:
548
return handle_MAV_CMD_CONDITION_YAW(packet);
549
550
case MAV_CMD_DO_CHANGE_SPEED:
551
return handle_MAV_CMD_DO_CHANGE_SPEED(packet);
552
553
case MAV_CMD_DO_MOTOR_TEST:
554
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
555
556
case MAV_CMD_DO_REPOSITION:
557
return handle_command_int_do_reposition(packet);
558
559
case MAV_CMD_MISSION_START:
560
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
561
// first-item/last item not supported
562
return MAV_RESULT_DENIED;
563
}
564
return handle_MAV_CMD_MISSION_START(packet);
565
566
case MAV_CMD_NAV_LOITER_UNLIM:
567
return handle_MAV_CMD_NAV_LOITER_UNLIM(packet);
568
569
case MAV_CMD_NAV_LAND:
570
return handle_MAV_CMD_NAV_LAND(packet);
571
572
}
573
574
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
575
}
576
577
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet)
578
{
579
if (!sub.set_mode(Mode::Number::POSHOLD, ModeReason::GCS_COMMAND)) {
580
return MAV_RESULT_FAILED;
581
}
582
return MAV_RESULT_ACCEPTED;
583
}
584
585
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet)
586
{
587
if (!sub.set_mode(Mode::Number::SURFACE, ModeReason::GCS_COMMAND)) {
588
return MAV_RESULT_FAILED;
589
}
590
return MAV_RESULT_ACCEPTED;
591
}
592
593
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)
594
{
595
// param1 : target angle [0-360]
596
// param2 : speed during change [deg per second]
597
// param3 : direction (-1:ccw, +1:cw)
598
// param4 : relative offset (1) or absolute angle (0)
599
if ((packet.param1 >= 0.0f) &&
600
(packet.param1 <= 360.0f) &&
601
(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {
602
sub.mode_auto.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
603
return MAV_RESULT_ACCEPTED;
604
}
605
return MAV_RESULT_DENIED;
606
}
607
608
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
609
{
610
// param1 : unused
611
// param2 : new speed in m/s
612
// param3 : unused
613
// param4 : unused
614
if (packet.param2 > 0.0f) {
615
sub.wp_nav.set_speed_xy(packet.param2 * 100.0f);
616
return MAV_RESULT_ACCEPTED;
617
}
618
return MAV_RESULT_FAILED;
619
}
620
621
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
622
{
623
if (sub.motors.armed() && sub.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
624
return MAV_RESULT_ACCEPTED;
625
}
626
return MAV_RESULT_FAILED;
627
}
628
629
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
630
{
631
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
632
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
633
// param3 : throttle (range depends upon param2)
634
// param4 : timeout (in seconds)
635
if (!sub.handle_do_motor_test(packet)) {
636
return MAV_RESULT_FAILED;
637
}
638
return MAV_RESULT_ACCEPTED;
639
}
640
641
void GCS_MAVLINK_Sub::handle_message(const mavlink_message_t &msg)
642
{
643
switch (msg.msgid) {
644
645
case MAVLINK_MSG_ID_MANUAL_CONTROL: { // MAV ID: 69
646
if (msg.sysid != sub.g.sysid_my_gcs) {
647
break; // Only accept control from our gcs
648
}
649
mavlink_manual_control_t packet;
650
mavlink_msg_manual_control_decode(&msg, &packet);
651
652
if (packet.target != sub.g.sysid_this_mav) {
653
break; // only accept control aimed at us
654
}
655
656
sub.transform_manual_control_to_rc_override(
657
packet.x,
658
packet.y,
659
packet.z,
660
packet.r,
661
packet.buttons,
662
packet.buttons2,
663
packet.enabled_extensions,
664
packet.s,
665
packet.t,
666
packet.aux1,
667
packet.aux2,
668
packet.aux3,
669
packet.aux4,
670
packet.aux5,
671
packet.aux6
672
);
673
674
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
675
// a RC override message is considered to be a 'heartbeat'
676
// from the ground station for failsafe purposes
677
gcs().sysid_myggcs_seen(AP_HAL::millis());
678
break;
679
}
680
681
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { // MAV ID: 70
682
if (msg.sysid != sub.g.sysid_my_gcs) {
683
break; // Only accept control from our gcs
684
}
685
686
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
687
// a RC override message is considered to be a 'heartbeat'
688
// from the ground station for failsafe purposes
689
690
handle_rc_channels_override(msg);
691
break;
692
}
693
694
695
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82
696
// decode packet
697
mavlink_set_attitude_target_t packet;
698
mavlink_msg_set_attitude_target_decode(&msg, &packet);
699
700
// ensure type_mask specifies to use attitude
701
// the thrust can be used from the altitude hold
702
if (packet.type_mask & (1<<6)) {
703
sub.set_attitude_target_no_gps = {AP_HAL::millis(), packet};
704
}
705
706
// ensure type_mask specifies to use attitude and thrust
707
if ((packet.type_mask & ((1<<7)|(1<<6))) != 0) {
708
break;
709
}
710
711
// convert thrust to climb rate
712
packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);
713
float climb_rate_cms = 0.0f;
714
if (is_equal(packet.thrust, 0.5f)) {
715
climb_rate_cms = 0.0f;
716
} else if (packet.thrust > 0.5f) {
717
// climb at up to WPNAV_SPEED_UP
718
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_up();
719
} else {
720
// descend at up to WPNAV_SPEED_DN
721
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_down();
722
}
723
sub.mode_guided.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms);
724
break;
725
}
726
727
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // MAV ID: 84
728
// decode packet
729
mavlink_set_position_target_local_ned_t packet;
730
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
731
732
// exit if vehicle is not in Guided mode or Auto-Guided mode
733
if ((sub.control_mode != Mode::Number::GUIDED) && !(sub.control_mode == Mode::Number::AUTO && sub.auto_mode == Auto_NavGuided)) {
734
break;
735
}
736
737
// check for supported coordinate frames
738
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
739
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
740
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
741
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED &&
742
packet.coordinate_frame != MAV_FRAME_BODY_FRD) {
743
break;
744
}
745
746
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
747
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
748
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
749
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
750
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
751
752
// prepare position
753
Vector3f pos_vector;
754
if (!pos_ignore) {
755
// convert to cm
756
pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f);
757
// rotate from body-frame if necessary
758
if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||
759
packet.coordinate_frame == MAV_FRAME_BODY_FRD ||
760
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
761
sub.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y);
762
}
763
// add body offset if necessary
764
if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||
765
packet.coordinate_frame == MAV_FRAME_BODY_NED ||
766
packet.coordinate_frame == MAV_FRAME_BODY_FRD ||
767
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
768
pos_vector += sub.inertial_nav.get_position_neu_cm();
769
}
770
}
771
772
// prepare velocity
773
Vector3f vel_vector;
774
if (!vel_ignore) {
775
// convert to cm
776
vel_vector = Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f);
777
// rotate from body-frame if necessary
778
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_FRD || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
779
sub.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y);
780
}
781
}
782
783
// prepare yaw
784
float yaw_cd = 0.0f;
785
bool yaw_relative = false;
786
float yaw_rate_cds = 0.0f;
787
if (!yaw_ignore) {
788
yaw_cd = ToDeg(packet.yaw) * 100.0f;
789
yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED;
790
}
791
if (!yaw_rate_ignore) {
792
yaw_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;
793
}
794
795
// send request
796
if (!pos_ignore && !vel_ignore && acc_ignore) {
797
sub.mode_guided.guided_set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
798
} else if (pos_ignore && !vel_ignore && acc_ignore) {
799
sub.mode_guided.guided_set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
800
} else if (!pos_ignore && vel_ignore && acc_ignore) {
801
sub.mode_guided.guided_set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
802
}
803
804
break;
805
}
806
807
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: { // MAV ID: 86
808
// decode packet
809
mavlink_set_position_target_global_int_t packet;
810
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
811
812
// exit if vehicle is not in Guided, Auto-Guided, or Depth Hold modes
813
if ((sub.control_mode != Mode::Number::GUIDED)
814
&& !(sub.control_mode == Mode::Number::AUTO && sub.auto_mode == Auto_NavGuided)
815
&& !(sub.control_mode == Mode::Number::ALT_HOLD)) {
816
break;
817
}
818
819
bool z_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE;
820
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
821
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
822
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
823
824
/*
825
* for future use:
826
* bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
827
* bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
828
* bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
829
*/
830
831
if (!z_ignore && sub.control_mode == Mode::Number::ALT_HOLD) { // Control only target depth when in ALT_HOLD
832
sub.pos_control.set_pos_desired_z_cm(packet.alt*100);
833
break;
834
}
835
836
Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters
837
838
if (!pos_ignore) {
839
// sanity check location
840
if (!check_latlng(packet.lat_int, packet.lon_int)) {
841
break;
842
}
843
Location::AltFrame frame;
844
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {
845
// unknown coordinate frame
846
break;
847
}
848
const Location loc{
849
packet.lat_int,
850
packet.lon_int,
851
int32_t(packet.alt*100),
852
frame,
853
};
854
if (!loc.get_vector_from_origin_NEU(pos_neu_cm)) {
855
break;
856
}
857
}
858
859
if (!pos_ignore && !vel_ignore && acc_ignore) {
860
sub.mode_guided.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
861
} else if (pos_ignore && !vel_ignore && acc_ignore) {
862
sub.mode_guided.guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
863
} else if (!pos_ignore && vel_ignore && acc_ignore) {
864
sub.mode_guided.guided_set_destination(pos_neu_cm);
865
}
866
867
break;
868
}
869
870
case MAVLINK_MSG_ID_TERRAIN_DATA:
871
case MAVLINK_MSG_ID_TERRAIN_CHECK:
872
#if AP_TERRAIN_AVAILABLE
873
sub.terrain.handle_data(chan, msg);
874
#endif
875
break;
876
877
// This adds support for leak detectors in a separate enclosure
878
// connected to a mavlink enabled subsystem
879
case MAVLINK_MSG_ID_SYS_STATUS: {
880
uint32_t MAV_SENSOR_WATER = 0x20000000;
881
mavlink_sys_status_t packet;
882
mavlink_msg_sys_status_decode(&msg, &packet);
883
if ((packet.onboard_control_sensors_enabled & MAV_SENSOR_WATER) && !(packet.onboard_control_sensors_health & MAV_SENSOR_WATER)) {
884
sub.leak_detector.set_detect();
885
}
886
}
887
break;
888
889
default:
890
GCS_MAVLINK::handle_message(msg);
891
break;
892
} // end switch
893
} // end handle mavlink
894
895
uint64_t GCS_MAVLINK_Sub::capabilities() const
896
{
897
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
898
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
899
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
900
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
901
MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
902
#if AP_TERRAIN_AVAILABLE
903
(sub.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
904
#endif
905
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
906
GCS_MAVLINK::capabilities()
907
);
908
}
909
910
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet)
911
{
912
if (packet.param1 > 0.5f) {
913
sub.arming.disarm(AP_Arming::Method::TERMINATION);
914
return MAV_RESULT_ACCEPTED;
915
}
916
return MAV_RESULT_FAILED;
917
}
918
919
int32_t GCS_MAVLINK_Sub::global_position_int_alt() const
920
{
921
return static_cast<int32_t>(sub.get_alt_msl() * 1000.0f);
922
}
923
924
int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const
925
{
926
return static_cast<int32_t>(sub.get_alt_rel() * 1000.0f);
927
}
928
929
#if HAL_HIGH_LATENCY2_ENABLED
930
int16_t GCS_MAVLINK_Sub::high_latency_target_altitude() const
931
{
932
AP_AHRS &ahrs = AP::ahrs();
933
Location global_position_current;
934
UNUSED_RESULT(ahrs.get_location(global_position_current));
935
936
//return units are m
937
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
938
return 0.01 * (global_position_current.alt + sub.pos_control.get_pos_error_z_cm());
939
}
940
return 0;
941
942
}
943
944
uint8_t GCS_MAVLINK_Sub::high_latency_tgt_heading() const
945
{
946
// return units are deg/2
947
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
948
// need to convert -18000->18000 to 0->360/2
949
return wrap_360_cd(sub.wp_nav.get_wp_bearing_to_destination()) / 200;
950
}
951
return 0;
952
}
953
954
uint16_t GCS_MAVLINK_Sub::high_latency_tgt_dist() const
955
{
956
// return units are dm
957
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
958
return MIN(sub.wp_nav.get_wp_distance_to_destination() * 0.001, UINT16_MAX);
959
}
960
return 0;
961
}
962
963
uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const
964
{
965
// return units are m/s*5
966
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
967
return MIN((sub.pos_control.get_vel_desired_cms().length()/100) * 5, UINT8_MAX);
968
}
969
return 0;
970
}
971
#endif // HAL_HIGH_LATENCY2_ENABLED
972
973
// Send the mode with the given index (not mode number!) return the total number of modes
974
// Index starts at 1
975
uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const
976
{
977
const Mode* modes[] {
978
&sub.mode_manual,
979
&sub.mode_stabilize,
980
&sub.mode_acro,
981
&sub.mode_althold,
982
&sub.mode_surftrak,
983
&sub.mode_poshold,
984
&sub.mode_auto,
985
&sub.mode_guided,
986
&sub.mode_circle,
987
&sub.mode_surface,
988
&sub.mode_motordetect,
989
};
990
991
const uint8_t mode_count = ARRAY_SIZE(modes);
992
993
// Convert to zero indexed
994
const uint8_t index_zero = index - 1;
995
if (index_zero >= mode_count) {
996
// Mode does not exist!?
997
return mode_count;
998
}
999
1000
// Ask the mode for its name and number
1001
const char* name = modes[index_zero]->name();
1002
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
1003
1004
mavlink_msg_available_modes_send(
1005
chan,
1006
mode_count,
1007
index,
1008
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
1009
mode_number,
1010
0, // MAV_MODE_PROPERTY bitmask
1011
name
1012
);
1013
1014
return mode_count;
1015
}
1016
1017