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/AntennaTracker/GCS_MAVLink_Tracker.cpp
Views: 1798
1
#include "GCS_MAVLink_Tracker.h"
2
#include "Tracker.h"
3
4
MAV_TYPE GCS_Tracker::frame_type() const
5
{
6
return MAV_TYPE_ANTENNA_TRACKER;
7
}
8
9
MAV_MODE GCS_MAVLINK_Tracker::base_mode() const
10
{
11
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
12
// work out the base_mode. This value is not very useful
13
// for APM, but we calculate it as best we can so a generic
14
// MAVLink enabled ground station can work out something about
15
// what the MAV is up to. The actual bit values are highly
16
// ambiguous for most of the APM flight modes. In practice, you
17
// only get useful information from the custom_mode, which maps to
18
// the APM flight mode and has a well defined meaning in the
19
// ArduPlane documentation
20
switch (tracker.mode->number()) {
21
case Mode::Number::MANUAL:
22
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
23
break;
24
25
case Mode::Number::STOP:
26
break;
27
28
case Mode::Number::SCAN:
29
case Mode::Number::SERVOTEST:
30
case Mode::Number::AUTO:
31
case Mode::Number::GUIDED:
32
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED |
33
MAV_MODE_FLAG_STABILIZE_ENABLED;
34
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
35
// APM does in any mode, as that is defined as "system finds its own goal
36
// positions", which APM does not currently do
37
break;
38
39
case Mode::Number::INITIALISING:
40
break;
41
}
42
43
// we are armed if safety switch is not disarmed
44
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED &&
45
tracker.mode != &tracker.mode_initialising &&
46
hal.util->get_soft_armed()) {
47
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
48
}
49
50
return (MAV_MODE)_base_mode;
51
}
52
53
uint32_t GCS_Tracker::custom_mode() const
54
{
55
return (uint32_t)tracker.mode->number();
56
}
57
58
MAV_STATE GCS_MAVLINK_Tracker::vehicle_system_status() const
59
{
60
if (tracker.mode == &tracker.mode_initialising) {
61
return MAV_STATE_CALIBRATING;
62
}
63
return MAV_STATE_ACTIVE;
64
}
65
66
void GCS_MAVLINK_Tracker::send_nav_controller_output() const
67
{
68
float alt_diff = (tracker.g.alt_source == ALT_SOURCE_BARO) ? tracker.nav_status.alt_difference_baro : tracker.nav_status.alt_difference_gps;
69
70
mavlink_msg_nav_controller_output_send(
71
chan,
72
0,
73
tracker.nav_status.pitch,
74
tracker.nav_status.bearing,
75
tracker.nav_status.bearing,
76
MIN(tracker.nav_status.distance, UINT16_MAX),
77
alt_diff,
78
0,
79
0);
80
}
81
82
void GCS_MAVLINK_Tracker::handle_set_attitude_target(const mavlink_message_t &msg)
83
{
84
// decode packet
85
mavlink_set_attitude_target_t packet;
86
mavlink_msg_set_attitude_target_decode(&msg, &packet);
87
88
// exit if vehicle is not in Guided mode
89
if (tracker.mode != &tracker.mode_guided) {
90
return;
91
}
92
93
// sanity checks:
94
if (!is_zero(packet.body_roll_rate)) {
95
return;
96
}
97
if (!(packet.type_mask & (1<<0))) {
98
// not told to ignore body roll rate
99
return;
100
}
101
if (!(packet.type_mask & (1<<6))) {
102
// not told to ignore throttle
103
return;
104
}
105
if (packet.type_mask & (1<<7)) {
106
// told to ignore attitude (we don't allow continuous motion yet)
107
return;
108
}
109
if ((packet.type_mask & (1<<3)) && (packet.type_mask&(1<<4))) {
110
// told to ignore both pitch and yaw rates - nothing to do?!
111
return;
112
}
113
114
const bool use_yaw_rate = !(packet.type_mask & (1<<2));
115
116
tracker.mode_guided.set_angle(
117
Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),
118
use_yaw_rate,
119
packet.body_yaw_rate);
120
}
121
122
/*
123
send PID tuning message
124
*/
125
void GCS_MAVLINK_Tracker::send_pid_tuning()
126
{
127
const Parameters &g = tracker.g;
128
129
// Pitch PID
130
if (g.gcs_pid_mask & 1) {
131
const AP_PIDInfo *pid_info = &g.pidPitch2Srv.get_pid_info();
132
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
133
pid_info->target,
134
pid_info->actual,
135
pid_info->FF,
136
pid_info->P,
137
pid_info->I,
138
pid_info->D,
139
pid_info->slew_rate,
140
pid_info->Dmod);
141
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
142
return;
143
}
144
}
145
146
// Yaw PID
147
if (g.gcs_pid_mask & 2) {
148
const AP_PIDInfo *pid_info = &g.pidYaw2Srv.get_pid_info();
149
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
150
pid_info->target,
151
pid_info->actual,
152
pid_info->FF,
153
pid_info->P,
154
pid_info->I,
155
pid_info->D,
156
pid_info->slew_rate,
157
pid_info->Dmod);
158
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
159
return;
160
}
161
}
162
}
163
164
/*
165
default stream rates to 1Hz
166
*/
167
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
168
// @Param: RAW_SENS
169
// @DisplayName: Raw sensor stream rate
170
// @Description: Raw sensor stream rate to ground station
171
// @Units: Hz
172
// @Range: 0 50
173
// @Increment: 1
174
// @RebootRequired: True
175
// @User: Advanced
176
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),
177
178
// @Param: EXT_STAT
179
// @DisplayName: Extended status stream rate to ground station
180
// @Description: Extended status stream rate to ground station
181
// @Units: Hz
182
// @Range: 0 50
183
// @Increment: 1
184
// @RebootRequired: True
185
// @User: Advanced
186
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),
187
188
// @Param: RC_CHAN
189
// @DisplayName: RC Channel stream rate to ground station
190
// @Description: RC Channel stream rate to ground station
191
// @Units: Hz
192
// @Range: 0 50
193
// @Increment: 1
194
// @RebootRequired: True
195
// @User: Advanced
196
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),
197
198
// @Param: RAW_CTRL
199
// @DisplayName: Raw Control stream rate to ground station
200
// @Description: Raw Control stream rate to ground station
201
// @Units: Hz
202
// @Range: 0 50
203
// @Increment: 1
204
// @RebootRequired: True
205
// @User: Advanced
206
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),
207
208
// @Param: POSITION
209
// @DisplayName: Position stream rate to ground station
210
// @Description: Position stream rate to ground station
211
// @Units: Hz
212
// @Range: 0 50
213
// @Increment: 1
214
// @RebootRequired: True
215
// @User: Advanced
216
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1),
217
218
// @Param: EXTRA1
219
// @DisplayName: Extra data type 1 stream rate to ground station
220
// @Description: Extra data type 1 stream rate to ground station
221
// @Units: Hz
222
// @Range: 0 50
223
// @Increment: 1
224
// @RebootRequired: True
225
// @User: Advanced
226
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),
227
228
// @Param: EXTRA2
229
// @DisplayName: Extra data type 2 stream rate to ground station
230
// @Description: Extra data type 2 stream rate to ground station
231
// @Units: Hz
232
// @Range: 0 50
233
// @Increment: 1
234
// @RebootRequired: True
235
// @User: Advanced
236
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),
237
238
// @Param: EXTRA3
239
// @DisplayName: Extra data type 3 stream rate to ground station
240
// @Description: Extra data type 3 stream rate to ground station
241
// @Units: Hz
242
// @Range: 0 50
243
// @Increment: 1
244
// @RebootRequired: True
245
// @User: Advanced
246
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),
247
248
// @Param: PARAMS
249
// @DisplayName: Parameter stream rate to ground station
250
// @Description: Parameter stream rate to ground station
251
// @Units: Hz
252
// @Range: 0 50
253
// @Increment: 1
254
// @RebootRequired: True
255
// @User: Advanced
256
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),
257
AP_GROUPEND
258
};
259
260
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
261
MSG_RAW_IMU,
262
MSG_SCALED_IMU2,
263
MSG_SCALED_IMU3,
264
MSG_SCALED_PRESSURE,
265
MSG_SCALED_PRESSURE2,
266
MSG_SCALED_PRESSURE3,
267
#if AP_AIRSPEED_ENABLED
268
MSG_AIRSPEED,
269
#endif
270
};
271
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
272
MSG_SYS_STATUS,
273
MSG_POWER_STATUS,
274
#if HAL_WITH_MCU_MONITORING
275
MSG_MCU_STATUS,
276
#endif
277
MSG_MEMINFO,
278
MSG_NAV_CONTROLLER_OUTPUT,
279
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
280
MSG_GPS_RAW,
281
#endif
282
#if AP_GPS_GPS_RTK_SENDING_ENABLED
283
MSG_GPS_RTK,
284
#endif
285
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
286
MSG_GPS2_RAW,
287
#endif
288
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
289
MSG_GPS2_RTK,
290
#endif
291
};
292
static const ap_message STREAM_POSITION_msgs[] = {
293
MSG_LOCATION,
294
MSG_LOCAL_POSITION
295
};
296
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
297
MSG_SERVO_OUTPUT_RAW,
298
};
299
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
300
MSG_RC_CHANNELS,
301
#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED
302
MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
303
#endif
304
};
305
static const ap_message STREAM_EXTRA1_msgs[] = {
306
MSG_ATTITUDE,
307
MSG_PID_TUNING,
308
};
309
static const ap_message STREAM_EXTRA3_msgs[] = {
310
MSG_AHRS,
311
#if AP_SIM_ENABLED
312
MSG_SIMSTATE,
313
#endif
314
MSG_SYSTEM_TIME,
315
MSG_AHRS2,
316
#if COMPASS_CAL_ENABLED
317
MSG_MAG_CAL_REPORT,
318
MSG_MAG_CAL_PROGRESS,
319
#endif
320
MSG_EKF_STATUS_REPORT,
321
MSG_BATTERY_STATUS,
322
};
323
static const ap_message STREAM_PARAMS_msgs[] = {
324
MSG_NEXT_PARAM,
325
MSG_AVAILABLE_MODES
326
};
327
328
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
329
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
330
MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
331
MAV_STREAM_ENTRY(STREAM_POSITION),
332
MAV_STREAM_ENTRY(STREAM_RAW_CONTROLLER),
333
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
334
MAV_STREAM_ENTRY(STREAM_EXTRA1),
335
MAV_STREAM_ENTRY(STREAM_EXTRA3),
336
MAV_STREAM_ENTRY(STREAM_PARAMS),
337
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
338
};
339
340
/*
341
We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and
342
MAVLINK_MSG_ID_SCALED_PRESSUREs
343
*/
344
void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,
345
const mavlink_message_t &msg)
346
{
347
// return immediately if sysid doesn't match our target sysid
348
if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {
349
GCS_MAVLINK::packetReceived(status, msg);
350
return;
351
}
352
353
switch (msg.msgid) {
354
case MAVLINK_MSG_ID_HEARTBEAT:
355
{
356
mavlink_check_target(msg);
357
break;
358
}
359
360
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
361
{
362
// decode
363
mavlink_global_position_int_t packet;
364
mavlink_msg_global_position_int_decode(&msg, &packet);
365
tracker.tracking_update_position(packet);
366
break;
367
}
368
369
case MAVLINK_MSG_ID_SCALED_PRESSURE:
370
{
371
// decode
372
mavlink_scaled_pressure_t packet;
373
mavlink_msg_scaled_pressure_decode(&msg, &packet);
374
tracker.tracking_update_pressure(packet);
375
break;
376
}
377
}
378
GCS_MAVLINK::packetReceived(status, msg);
379
}
380
381
// locks onto a particular target sysid and sets it's position data stream to at least 1hz
382
void GCS_MAVLINK_Tracker::mavlink_check_target(const mavlink_message_t &msg)
383
{
384
// exit immediately if the target has already been set
385
if (tracker.target_set) {
386
return;
387
}
388
389
// decode
390
mavlink_heartbeat_t packet;
391
mavlink_msg_heartbeat_decode(&msg, &packet);
392
393
// exit immediately if this is not a vehicle we would track
394
if ((packet.type == MAV_TYPE_ANTENNA_TRACKER) ||
395
(packet.type == MAV_TYPE_GCS) ||
396
(packet.type == MAV_TYPE_ONBOARD_CONTROLLER) ||
397
(packet.type == MAV_TYPE_GIMBAL)) {
398
return;
399
}
400
401
// set our sysid to the target, this ensures we lock onto a single vehicle
402
if (tracker.g.sysid_target == 0) {
403
tracker.g.sysid_target.set(msg.sysid);
404
}
405
406
// send data stream request to target on all channels
407
// Note: this doesn't check success for all sends meaning it's not guaranteed the vehicle's positions will be sent at 1hz
408
tracker.gcs().request_datastream_position(msg.sysid, msg.compid);
409
tracker.gcs().request_datastream_airpressure(msg.sysid, msg.compid);
410
411
// flag target has been set
412
tracker.target_set = true;
413
}
414
415
uint8_t GCS_MAVLINK_Tracker::sysid_my_gcs() const
416
{
417
return tracker.g.sysid_my_gcs;
418
}
419
420
MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)
421
{
422
MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro(msg);
423
if (ret == MAV_RESULT_ACCEPTED) {
424
// zero the altitude difference on next baro update
425
tracker.nav_status.need_altitude_calibration = true;
426
}
427
return ret;
428
}
429
430
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_int_t &packet)
431
{
432
if (is_equal(packet.param1,1.0f)) {
433
tracker.arm_servos();
434
return MAV_RESULT_ACCEPTED;
435
}
436
if (is_zero(packet.param1)) {
437
tracker.disarm_servos();
438
return MAV_RESULT_ACCEPTED;
439
}
440
return MAV_RESULT_UNSUPPORTED;
441
}
442
443
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
444
{
445
switch(packet.command) {
446
447
case MAV_CMD_DO_SET_SERVO:
448
// ensure we are in servo test mode
449
tracker.set_mode(tracker.mode_servotest, ModeReason::SERVOTEST);
450
451
if (!tracker.mode_servotest.set_servo(packet.param1, packet.param2)) {
452
return MAV_RESULT_FAILED;
453
}
454
return MAV_RESULT_ACCEPTED;
455
456
// mavproxy/mavutil sends this when auto command is entered
457
case MAV_CMD_MISSION_START:
458
tracker.set_mode(tracker.mode_auto, ModeReason::GCS_COMMAND);
459
return MAV_RESULT_ACCEPTED;
460
461
default:
462
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
463
}
464
}
465
466
void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg)
467
{
468
switch (msg.msgid) {
469
470
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
471
handle_set_attitude_target(msg);
472
break;
473
474
#if AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED
475
// When mavproxy 'wp sethome'
476
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
477
handle_message_mission_write_partial_list(msg);
478
break;
479
480
// XXX receive a WP from GCS and store in EEPROM if it is HOME
481
case MAVLINK_MSG_ID_MISSION_ITEM:
482
handle_message_mission_item(msg);
483
break;
484
#endif
485
486
case MAVLINK_MSG_ID_MANUAL_CONTROL:
487
handle_message_manual_control(msg);
488
break;
489
490
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
491
handle_message_global_position_int(msg);
492
break;
493
494
case MAVLINK_MSG_ID_SCALED_PRESSURE:
495
handle_message_scaled_pressure(msg);
496
break;
497
}
498
499
GCS_MAVLINK::handle_message(msg);
500
}
501
502
503
#if AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED
504
void GCS_MAVLINK_Tracker::handle_message_mission_write_partial_list(const mavlink_message_t &msg)
505
{
506
// decode
507
mavlink_mission_write_partial_list_t packet;
508
mavlink_msg_mission_write_partial_list_decode(&msg, &packet);
509
if (packet.start_index == 0)
510
{
511
// New home at wp index 0. Ask for it
512
waypoint_receiving = true;
513
send_message(MSG_NEXT_MISSION_REQUEST_WAYPOINTS);
514
}
515
}
516
517
void GCS_MAVLINK_Tracker::handle_message_mission_item(const mavlink_message_t &msg)
518
{
519
mavlink_mission_item_t packet;
520
MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;
521
522
mavlink_msg_mission_item_decode(&msg, &packet);
523
524
Location tell_command;
525
526
switch (packet.frame)
527
{
528
case MAV_FRAME_MISSION:
529
case MAV_FRAME_GLOBAL:
530
{
531
tell_command = Location{
532
int32_t(1.0e7f*packet.x), // in as DD converted to * t7
533
int32_t(1.0e7f*packet.y), // in as DD converted to * t7
534
int32_t(packet.z*1.0e2f), // in as m converted to cm
535
Location::AltFrame::ABSOLUTE
536
};
537
break;
538
}
539
540
#ifdef MAV_FRAME_LOCAL_NED
541
case MAV_FRAME_LOCAL_NED: // local (relative to home position)
542
{
543
tell_command = Location{
544
int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),
545
int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),
546
int32_t(-packet.z*1.0e2f),
547
Location::AltFrame::ABOVE_HOME
548
};
549
break;
550
}
551
#endif
552
553
#ifdef MAV_FRAME_LOCAL
554
case MAV_FRAME_LOCAL: // local (relative to home position)
555
{
556
tell_command = {
557
int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),
558
int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),
559
int32_t(packet.z*1.0e2f),
560
Location::AltFrame::ABOVE_HOME
561
};
562
break;
563
}
564
#endif
565
566
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
567
{
568
tell_command = {
569
int32_t(1.0e7f * packet.x), // in as DD converted to * t7
570
int32_t(1.0e7f * packet.y), // in as DD converted to * t7
571
int32_t(packet.z * 1.0e2f),
572
Location::AltFrame::ABOVE_HOME
573
};
574
break;
575
}
576
577
default:
578
result = MAV_MISSION_UNSUPPORTED_FRAME;
579
break;
580
}
581
582
if (result != MAV_MISSION_ACCEPTED) goto mission_failed;
583
584
// Check if receiving waypoints (mission upload expected)
585
if (!waypoint_receiving) {
586
result = MAV_MISSION_ERROR;
587
goto mission_failed;
588
}
589
590
// check if this is the HOME wp
591
if (packet.seq == 0) {
592
if (!tracker.set_home(tell_command, false)) {
593
result = MAV_MISSION_ERROR;
594
goto mission_failed;
595
}
596
send_text(MAV_SEVERITY_INFO,"New HOME received");
597
waypoint_receiving = false;
598
}
599
600
mission_failed:
601
// send ACK (including in success case)
602
mavlink_msg_mission_ack_send(
603
chan,
604
msg.sysid,
605
msg.compid,
606
result,
607
MAV_MISSION_TYPE_MISSION);
608
}
609
#endif
610
611
void GCS_MAVLINK_Tracker::handle_message_manual_control(const mavlink_message_t &msg)
612
{
613
mavlink_manual_control_t packet;
614
mavlink_msg_manual_control_decode(&msg, &packet);
615
tracker.tracking_manual_control(packet);
616
}
617
618
void GCS_MAVLINK_Tracker::handle_message_global_position_int(const mavlink_message_t &msg)
619
{
620
// decode
621
mavlink_global_position_int_t packet;
622
mavlink_msg_global_position_int_decode(&msg, &packet);
623
tracker.tracking_update_position(packet);
624
}
625
626
void GCS_MAVLINK_Tracker::handle_message_scaled_pressure(const mavlink_message_t &msg)
627
{
628
mavlink_scaled_pressure_t packet;
629
mavlink_msg_scaled_pressure_decode(&msg, &packet);
630
tracker.tracking_update_pressure(packet);
631
}
632
633
// send position tracker is using
634
void GCS_MAVLINK_Tracker::send_global_position_int()
635
{
636
if (!tracker.stationary) {
637
GCS_MAVLINK::send_global_position_int();
638
return;
639
}
640
641
mavlink_msg_global_position_int_send(
642
chan,
643
AP_HAL::millis(),
644
tracker.current_loc.lat, // in 1E7 degrees
645
tracker.current_loc.lng, // in 1E7 degrees
646
tracker.current_loc.alt, // millimeters above ground/sea level
647
0, // millimeters above home
648
0, // X speed cm/s (+ve North)
649
0, // Y speed cm/s (+ve East)
650
0, // Z speed cm/s (+ve Down)
651
tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree
652
}
653
654
// Send the mode with the given index (not mode number!) return the total number of modes
655
// Index starts at 1
656
uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const
657
{
658
const Mode* modes[] {
659
&tracker.mode_manual,
660
&tracker.mode_stop,
661
&tracker.mode_scan,
662
&tracker.mode_guided,
663
&tracker.mode_servotest,
664
&tracker.mode_auto,
665
&tracker.mode_initialising,
666
};
667
668
const uint8_t mode_count = ARRAY_SIZE(modes);
669
670
// Convert to zero indexed
671
const uint8_t index_zero = index - 1;
672
if (index_zero >= mode_count) {
673
// Mode does not exist!?
674
return mode_count;
675
}
676
677
// Ask the mode for its name and number
678
const char* name = modes[index_zero]->name();
679
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
680
681
mavlink_msg_available_modes_send(
682
chan,
683
mode_count,
684
index,
685
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
686
mode_number,
687
0, // MAV_MODE_PROPERTY bitmask
688
name
689
);
690
691
return mode_count;
692
}
693
694