Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/GCS_MAVLink_Sub.cpp
9388 views
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
uint8_t 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 _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_cd() * 1.0e-2f,
88
MIN(sub.wp_nav.get_wp_distance_to_destination_cm() * 1.0e-2f, UINT16_MAX),
89
sub.pos_control.get_pos_error_U_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
// Fall back to original behaviour
111
GCS_MAVLINK::send_scaled_pressure3();
112
return;
113
}
114
mavlink_msg_scaled_pressure3_send(
115
chan,
116
AP_HAL::millis(),
117
0,
118
0,
119
temperature * 100,
120
0); // TODO: use differential pressure temperature
121
#else
122
// Fall back to standard behaviour
123
GCS_MAVLINK::send_scaled_pressure3();
124
#endif
125
}
126
127
bool GCS_MAVLINK_Sub::send_info()
128
{
129
// Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok
130
// Name is char[10]
131
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
132
send_named_float("CamTilt",
133
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));
134
135
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
136
send_named_float("CamPan",
137
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));
138
139
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
140
send_named_float("TetherTrn",
141
(float)sub.quarter_turn_count / 4);
142
143
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
144
send_named_float("Lights1",
145
SRV_Channels::get_output_norm(SRV_Channel::k_lights1) / 2.0f + 0.5f);
146
147
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
148
send_named_float("Lights2",
149
SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);
150
151
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
152
send_named_float("PilotGain", sub.gain);
153
154
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
155
send_named_float("InputHold", sub.input_hold_engaged);
156
157
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
158
send_named_float("RollPitch", sub.roll_pitch_flag);
159
160
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
161
send_named_float("RFTarget", sub.mode_surftrak.get_rangefinder_target_cm() * 0.01f);
162
163
return true;
164
}
165
166
/*
167
send PID tuning message
168
*/
169
void GCS_MAVLINK_Sub::send_pid_tuning()
170
{
171
const Parameters &g = sub.g;
172
AP_AHRS &ahrs = AP::ahrs();
173
AC_AttitudeControl_Sub &attitude_control = sub.attitude_control;
174
175
const Vector3f &gyro = ahrs.get_gyro();
176
if (g.gcs_pid_mask & 1) {
177
const AP_PIDInfo &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();
178
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
179
pid_info.target*0.01f,
180
degrees(gyro.x),
181
pid_info.FF*0.01f,
182
pid_info.P*0.01f,
183
pid_info.I*0.01f,
184
pid_info.D*0.01f,
185
pid_info.slew_rate,
186
pid_info.Dmod);
187
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
188
return;
189
}
190
}
191
if (g.gcs_pid_mask & 2) {
192
const AP_PIDInfo &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info();
193
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
194
pid_info.target*0.01f,
195
degrees(gyro.y),
196
pid_info.FF*0.01f,
197
pid_info.P*0.01f,
198
pid_info.I*0.01f,
199
pid_info.D*0.01f,
200
pid_info.slew_rate,
201
pid_info.Dmod);
202
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
203
return;
204
}
205
}
206
if (g.gcs_pid_mask & 4) {
207
const AP_PIDInfo &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info();
208
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
209
pid_info.target*0.01f,
210
degrees(gyro.z),
211
pid_info.FF*0.01f,
212
pid_info.P*0.01f,
213
pid_info.I*0.01f,
214
pid_info.D*0.01f,
215
pid_info.slew_rate,
216
pid_info.Dmod);
217
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
218
return;
219
}
220
}
221
if (g.gcs_pid_mask & 8) {
222
const AP_PIDInfo &pid_info = sub.pos_control.D_get_accel_pid().get_pid_info();
223
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
224
pid_info.target*0.01f,
225
-(ahrs.get_accel_ef().z + GRAVITY_MSS),
226
pid_info.FF*0.01f,
227
pid_info.P*0.01f,
228
pid_info.I*0.01f,
229
pid_info.D*0.01f,
230
pid_info.slew_rate,
231
pid_info.Dmod);
232
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
233
return;
234
}
235
}
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
case MSG_WIND: // other vehicles do something custom with wind:
252
return true;
253
254
default:
255
return GCS_MAVLINK::try_send_message(id);
256
}
257
258
return true;
259
}
260
261
bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
262
{
263
return sub.do_guided(cmd);
264
}
265
266
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)
267
{
268
if (sub.motors.armed()) {
269
gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");
270
return MAV_RESULT_FAILED;
271
}
272
273
if (!sub.control_check_barometer()) {
274
return MAV_RESULT_FAILED;
275
}
276
277
AP::baro().calibrate(true);
278
return MAV_RESULT_ACCEPTED;
279
}
280
281
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
282
{
283
if (packet.y == 1) {
284
// compassmot calibration
285
//result = sub.mavlink_compassmot(chan);
286
gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");
287
return MAV_RESULT_UNSUPPORTED;
288
}
289
290
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
291
}
292
293
MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)
294
{
295
if (!roi_loc.check_latlng()) {
296
return MAV_RESULT_FAILED;
297
}
298
sub.mode_auto.set_auto_yaw_roi(roi_loc);
299
return MAV_RESULT_ACCEPTED;
300
}
301
302
MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
303
{
304
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
305
if (!sub.flightmode->in_guided_mode() && !change_modes) {
306
return MAV_RESULT_DENIED;
307
}
308
309
// sanity check location
310
if (!check_latlng(packet.x, packet.y)) {
311
return MAV_RESULT_DENIED;
312
}
313
314
Location request_location;
315
if (!location_from_command_t(packet, request_location)) {
316
return MAV_RESULT_DENIED;
317
}
318
319
if (request_location.sanitize(sub.current_loc)) {
320
// if the location wasn't already sane don't load it
321
return MAV_RESULT_DENIED; // failed as the location is not valid
322
}
323
324
// we need to do this first, as we don't want to change the flight mode unless we can also set the target
325
if (!sub.mode_guided.guided_set_destination(request_location)) {
326
return MAV_RESULT_FAILED;
327
}
328
329
if (!sub.flightmode->in_guided_mode()) {
330
if (!sub.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {
331
return MAV_RESULT_FAILED;
332
}
333
// the position won't have been loaded if we had to change the flight mode, so load it again
334
if (!sub.mode_guided.guided_set_destination(request_location)) {
335
return MAV_RESULT_FAILED;
336
}
337
}
338
339
return MAV_RESULT_ACCEPTED;
340
}
341
342
MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
343
{
344
switch(packet.command) {
345
346
case MAV_CMD_CONDITION_YAW:
347
return handle_MAV_CMD_CONDITION_YAW(packet);
348
349
case MAV_CMD_DO_CHANGE_SPEED:
350
return handle_MAV_CMD_DO_CHANGE_SPEED(packet);
351
352
case MAV_CMD_DO_MOTOR_TEST:
353
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
354
355
case MAV_CMD_DO_REPOSITION:
356
return handle_command_int_do_reposition(packet);
357
358
case MAV_CMD_MISSION_START:
359
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
360
// first-item/last item not supported
361
return MAV_RESULT_DENIED;
362
}
363
return handle_MAV_CMD_MISSION_START(packet);
364
365
case MAV_CMD_NAV_LOITER_UNLIM:
366
return handle_MAV_CMD_NAV_LOITER_UNLIM(packet);
367
368
case MAV_CMD_NAV_LAND:
369
return handle_MAV_CMD_NAV_LAND(packet);
370
371
}
372
373
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
374
}
375
376
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet)
377
{
378
if (!sub.set_mode(Mode::Number::POSHOLD, ModeReason::GCS_COMMAND)) {
379
return MAV_RESULT_FAILED;
380
}
381
return MAV_RESULT_ACCEPTED;
382
}
383
384
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet)
385
{
386
if (!sub.set_mode(Mode::Number::SURFACE, ModeReason::GCS_COMMAND)) {
387
return MAV_RESULT_FAILED;
388
}
389
return MAV_RESULT_ACCEPTED;
390
}
391
392
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)
393
{
394
// param1 : target angle [0-360]
395
// param2 : speed during change [deg per second]
396
// param3 : direction (-1:ccw, +1:cw)
397
// param4 : relative offset (1) or absolute angle (0)
398
if ((packet.param1 >= 0.0f) &&
399
(packet.param1 <= 360.0f) &&
400
(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {
401
sub.mode_auto.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
402
return MAV_RESULT_ACCEPTED;
403
}
404
return MAV_RESULT_DENIED;
405
}
406
407
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
408
{
409
if (!is_positive(packet.param2)) {
410
// Target speed must be larger than zero
411
return MAV_RESULT_DENIED;
412
}
413
414
switch (SPEED_TYPE(packet.param1)) {
415
case SPEED_TYPE_CLIMB_SPEED:
416
case SPEED_TYPE_DESCENT_SPEED:
417
case SPEED_TYPE_ENUM_END:
418
break;
419
420
case SPEED_TYPE_AIRSPEED: // Airspeed is treated as ground speed for GCS compatibility
421
case SPEED_TYPE_GROUNDSPEED:
422
sub.wp_nav.set_speed_NE_cms(packet.param2 * 100.0);
423
return MAV_RESULT_ACCEPTED;
424
}
425
426
return MAV_RESULT_DENIED;
427
}
428
429
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
430
{
431
if (sub.motors.armed() && sub.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
432
return MAV_RESULT_ACCEPTED;
433
}
434
return MAV_RESULT_FAILED;
435
}
436
437
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
438
{
439
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
440
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
441
// param3 : throttle (range depends upon param2)
442
// param4 : timeout (in seconds)
443
if (!sub.handle_do_motor_test(packet)) {
444
return MAV_RESULT_FAILED;
445
}
446
return MAV_RESULT_ACCEPTED;
447
}
448
449
// this is called on receipt of a MANUAL_CONTROL packet and is
450
// expected to call manual_override to override RC input on desired
451
// axes.
452
void GCS_MAVLINK_Sub::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
453
{
454
sub.transform_manual_control_to_rc_override(
455
packet.x,
456
packet.y,
457
packet.z,
458
packet.r,
459
packet.buttons,
460
packet.buttons2,
461
packet.enabled_extensions,
462
packet.s,
463
packet.t,
464
packet.aux1,
465
packet.aux2,
466
packet.aux3,
467
packet.aux4,
468
packet.aux5,
469
packet.aux6
470
);
471
472
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
473
}
474
475
void GCS_MAVLINK_Sub::handle_message(const mavlink_message_t &msg)
476
{
477
switch (msg.msgid) {
478
479
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { // MAV ID: 70
480
if (!gcs().sysid_is_gcs(msg.sysid)) {
481
break; // Only accept control from our gcs
482
}
483
484
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
485
// a RC override message is considered to be a 'heartbeat'
486
// from the ground station for failsafe purposes
487
488
handle_rc_channels_override(msg);
489
break;
490
}
491
492
493
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82
494
// decode packet
495
mavlink_set_attitude_target_t packet;
496
mavlink_msg_set_attitude_target_decode(&msg, &packet);
497
498
// ensure type_mask specifies to use attitude
499
// the thrust can be used from the altitude hold
500
if (packet.type_mask & (1<<6)) {
501
sub.set_attitude_target_no_gps = {AP_HAL::millis(), packet};
502
}
503
504
// ensure type_mask specifies to use attitude and thrust
505
if ((packet.type_mask & ((1<<7)|(1<<6))) != 0) {
506
break;
507
}
508
509
// convert thrust to climb rate
510
packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);
511
float climb_rate_cms = 0.0f;
512
if (is_equal(packet.thrust, 0.5f)) {
513
climb_rate_cms = 0.0f;
514
} else if (packet.thrust > 0.5f) {
515
// climb at up to WPNAV_SPEED_UP
516
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_up_cms();
517
} else {
518
// descend at up to WPNAV_SPEED_DN
519
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_down_cms();
520
}
521
sub.mode_guided.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms);
522
break;
523
}
524
525
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // MAV ID: 84
526
// decode packet
527
mavlink_set_position_target_local_ned_t packet;
528
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
529
530
// exit if vehicle is not in Guided mode or Auto-Guided mode
531
if ((sub.control_mode != Mode::Number::GUIDED) && !(sub.control_mode == Mode::Number::AUTO && sub.auto_mode == Auto_NavGuided)) {
532
break;
533
}
534
535
// check for supported coordinate frames
536
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
537
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
538
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
539
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED &&
540
packet.coordinate_frame != MAV_FRAME_BODY_FRD) {
541
break;
542
}
543
544
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
545
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
546
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
547
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
548
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
549
550
// prepare position
551
Vector3f pos_vector;
552
if (!pos_ignore) {
553
// convert to cm
554
pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f);
555
// rotate from body-frame if necessary
556
if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||
557
packet.coordinate_frame == MAV_FRAME_BODY_FRD ||
558
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
559
sub.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y);
560
}
561
// add body offset if necessary
562
if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||
563
packet.coordinate_frame == MAV_FRAME_BODY_NED ||
564
packet.coordinate_frame == MAV_FRAME_BODY_FRD ||
565
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
566
pos_vector += sub.inertial_nav.get_position_neu_cm();
567
}
568
}
569
570
// prepare velocity
571
Vector3f vel_vector;
572
if (!vel_ignore) {
573
// convert to cm
574
vel_vector = Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f);
575
// rotate from body-frame if necessary
576
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_FRD || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
577
sub.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y);
578
}
579
}
580
581
// prepare yaw
582
float yaw_cd = 0.0f;
583
bool yaw_relative = false;
584
float yaw_rate_cds = 0.0f;
585
if (!yaw_ignore) {
586
yaw_cd = degrees(packet.yaw) * 100.0f;
587
yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED;
588
}
589
if (!yaw_rate_ignore) {
590
yaw_rate_cds = degrees(packet.yaw_rate) * 100.0f;
591
}
592
593
// send request
594
if (!pos_ignore && !vel_ignore && acc_ignore) {
595
sub.mode_guided.guided_set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
596
} else if (pos_ignore && !vel_ignore && acc_ignore) {
597
sub.mode_guided.guided_set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
598
} else if (!pos_ignore && vel_ignore && acc_ignore) {
599
sub.mode_guided.guided_set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
600
}
601
602
break;
603
}
604
605
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: { // MAV ID: 86
606
// decode packet
607
mavlink_set_position_target_global_int_t packet;
608
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
609
610
// exit if vehicle is not in Guided, Auto-Guided, or Depth Hold modes
611
if ((sub.control_mode != Mode::Number::GUIDED)
612
&& !(sub.control_mode == Mode::Number::AUTO && sub.auto_mode == Auto_NavGuided)
613
&& !(sub.control_mode == Mode::Number::ALT_HOLD)) {
614
break;
615
}
616
617
bool z_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE;
618
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
619
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
620
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
621
622
/*
623
* for future use:
624
* bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
625
* bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
626
* bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
627
*/
628
629
if (!z_ignore && sub.control_mode == Mode::Number::ALT_HOLD) { // Control only target depth when in ALT_HOLD
630
sub.pos_control.set_pos_desired_U_cm(packet.alt*100);
631
break;
632
}
633
634
Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters
635
636
if (!pos_ignore) {
637
// sanity check location
638
if (!check_latlng(packet.lat_int, packet.lon_int)) {
639
break;
640
}
641
Location::AltFrame frame;
642
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {
643
// unknown coordinate frame
644
break;
645
}
646
const Location loc{
647
packet.lat_int,
648
packet.lon_int,
649
int32_t(packet.alt*100),
650
frame,
651
};
652
if (!loc.get_vector_from_origin_NEU_cm(pos_neu_cm)) {
653
break;
654
}
655
}
656
657
if (!pos_ignore && !vel_ignore && acc_ignore) {
658
sub.mode_guided.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
659
} else if (pos_ignore && !vel_ignore && acc_ignore) {
660
sub.mode_guided.guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
661
} else if (!pos_ignore && vel_ignore && acc_ignore) {
662
sub.mode_guided.guided_set_destination(pos_neu_cm);
663
}
664
665
break;
666
}
667
668
// This adds support for leak detectors in a separate enclosure
669
// connected to a mavlink enabled subsystem
670
case MAVLINK_MSG_ID_SYS_STATUS: {
671
uint32_t MAV_SENSOR_WATER = 0x20000000;
672
mavlink_sys_status_t packet;
673
mavlink_msg_sys_status_decode(&msg, &packet);
674
if ((packet.onboard_control_sensors_enabled & MAV_SENSOR_WATER) && !(packet.onboard_control_sensors_health & MAV_SENSOR_WATER)) {
675
sub.leak_detector.set_detect();
676
}
677
}
678
break;
679
680
default:
681
GCS_MAVLINK::handle_message(msg);
682
break;
683
} // end switch
684
} // end handle mavlink
685
686
uint64_t GCS_MAVLINK_Sub::capabilities() const
687
{
688
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
689
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
690
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
691
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
692
MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
693
#if AP_TERRAIN_AVAILABLE
694
(sub.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
695
#endif
696
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
697
GCS_MAVLINK::capabilities()
698
);
699
}
700
701
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet)
702
{
703
if (packet.param1 > 0.5f) {
704
sub.arming.disarm(AP_Arming::Method::TERMINATION);
705
return MAV_RESULT_ACCEPTED;
706
}
707
return MAV_RESULT_FAILED;
708
}
709
710
int32_t GCS_MAVLINK_Sub::global_position_int_alt() const
711
{
712
return static_cast<int32_t>(sub.get_alt_msl() * 1000.0f);
713
}
714
715
int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const
716
{
717
return static_cast<int32_t>(sub.get_alt_rel() * 1000.0f);
718
}
719
720
#if HAL_HIGH_LATENCY2_ENABLED
721
int16_t GCS_MAVLINK_Sub::high_latency_target_altitude() const
722
{
723
AP_AHRS &ahrs = AP::ahrs();
724
Location global_position_current;
725
UNUSED_RESULT(ahrs.get_location(global_position_current));
726
727
//return units are m
728
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
729
return 0.01 * (global_position_current.alt + sub.pos_control.get_pos_error_U_cm());
730
}
731
return 0;
732
733
}
734
735
uint8_t GCS_MAVLINK_Sub::high_latency_tgt_heading() const
736
{
737
// return units are deg/2
738
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
739
// need to convert -18000->18000 to 0->360/2
740
return wrap_360_cd(sub.wp_nav.get_wp_bearing_to_destination_cd()) / 200;
741
}
742
return 0;
743
}
744
745
uint16_t GCS_MAVLINK_Sub::high_latency_tgt_dist() const
746
{
747
// return units are dm
748
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
749
return MIN(sub.wp_nav.get_wp_distance_to_destination_cm() * 0.001, UINT16_MAX);
750
}
751
return 0;
752
}
753
754
uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const
755
{
756
// return units are m/s*5
757
if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {
758
return MIN((sub.pos_control.get_vel_desired_NEU_cms().length()/100) * 5, UINT8_MAX);
759
}
760
return 0;
761
}
762
#endif // HAL_HIGH_LATENCY2_ENABLED
763
764
// Send the mode with the given index (not mode number!) return the total number of modes
765
// Index starts at 1
766
uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const
767
{
768
const Mode* modes[] {
769
&sub.mode_manual,
770
&sub.mode_stabilize,
771
&sub.mode_acro,
772
&sub.mode_althold,
773
&sub.mode_surftrak,
774
&sub.mode_poshold,
775
&sub.mode_auto,
776
&sub.mode_guided,
777
&sub.mode_circle,
778
&sub.mode_surface,
779
&sub.mode_motordetect,
780
};
781
782
const uint8_t mode_count = ARRAY_SIZE(modes);
783
784
// Convert to zero indexed
785
const uint8_t index_zero = index - 1;
786
if (index_zero >= mode_count) {
787
// Mode does not exist!?
788
return mode_count;
789
}
790
791
// Ask the mode for its name and number
792
const char* name = modes[index_zero]->name();
793
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
794
795
mavlink_msg_available_modes_send(
796
chan,
797
mode_count,
798
index,
799
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
800
mode_number,
801
0, // MAV_MODE_PROPERTY bitmask
802
name
803
);
804
805
return mode_count;
806
}
807
808