Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/GCS_MAVLink_Rover.cpp
9448 views
1
#include "Rover.h"
2
3
#include "GCS_MAVLink_Rover.h"
4
5
#include <AP_RPM/AP_RPM_config.h>
6
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
7
#include <AP_EFI/AP_EFI_config.h>
8
#include <AC_Avoidance/AP_OADatabase.h>
9
10
MAV_TYPE GCS_Rover::frame_type() const
11
{
12
if (rover.is_boat()) {
13
return MAV_TYPE_SURFACE_BOAT;
14
}
15
return MAV_TYPE_GROUND_ROVER;
16
}
17
18
uint8_t GCS_MAVLINK_Rover::base_mode() const
19
{
20
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
21
22
// work out the base_mode. This value is not very useful
23
// for APM, but we calculate it as best we can so a generic
24
// MAVLink enabled ground station can work out something about
25
// what the MAV is up to. The actual bit values are highly
26
// ambiguous for most of the APM flight modes. In practice, you
27
// only get useful information from the custom_mode, which maps to
28
// the APM flight mode and has a well defined meaning in the
29
// ArduPlane documentation
30
if (rover.control_mode->has_manual_input()) {
31
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
32
}
33
34
if (rover.control_mode->is_autopilot_mode()) {
35
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
36
}
37
38
if (rover.g2.stick_mixing > 0 && rover.control_mode != &rover.mode_initializing) {
39
// all modes except INITIALISING have some form of manual
40
// override if stick mixing is enabled
41
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
42
}
43
44
// we are armed if we are not initialising
45
if (rover.control_mode != &rover.mode_initializing && rover.arming.is_armed()) {
46
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
47
}
48
49
// indicate we have set a custom mode
50
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
51
52
return _base_mode;
53
}
54
55
uint32_t GCS_Rover::custom_mode() const
56
{
57
return (uint32_t)rover.control_mode->mode_number();
58
}
59
60
MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const
61
{
62
if ((rover.failsafe.triggered != 0) || rover.failsafe.ekf) {
63
return MAV_STATE_CRITICAL;
64
}
65
if (rover.control_mode == &rover.mode_initializing) {
66
return MAV_STATE_CALIBRATING;
67
}
68
if (rover.control_mode == &rover.mode_hold) {
69
return MAV_STATE_STANDBY;
70
}
71
72
return MAV_STATE_ACTIVE;
73
}
74
75
void GCS_MAVLINK_Rover::send_position_target_global_int()
76
{
77
Location target;
78
if (!rover.control_mode->get_desired_location(target)) {
79
return;
80
}
81
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;
82
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
83
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
84
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
85
mavlink_msg_position_target_global_int_send(
86
chan,
87
AP_HAL::millis(), // time_boot_ms
88
MAV_FRAME_GLOBAL, // targets are always global altitude
89
TYPE_MASK, // ignore everything except the x/y/z components
90
target.lat, // latitude as 1e7
91
target.lng, // longitude as 1e7
92
target.alt * 0.01f, // altitude is sent as a float
93
0.0f, // vx
94
0.0f, // vy
95
0.0f, // vz
96
0.0f, // afx
97
0.0f, // afy
98
0.0f, // afz
99
0.0f, // yaw
100
0.0f); // yaw_rate
101
}
102
103
void GCS_MAVLINK_Rover::send_nav_controller_output() const
104
{
105
if (!rover.control_mode->is_autopilot_mode()) {
106
return;
107
}
108
109
const Mode *control_mode = rover.control_mode;
110
111
mavlink_msg_nav_controller_output_send(
112
chan,
113
0, // roll
114
degrees(rover.g2.attitude_control.get_desired_pitch()),
115
control_mode->nav_bearing(),
116
control_mode->wp_bearing(),
117
MIN(control_mode->get_distance_to_destination(), UINT16_MAX),
118
0,
119
control_mode->speed_error(),
120
control_mode->crosstrack_error());
121
}
122
123
void GCS_MAVLINK_Rover::send_servo_out()
124
{
125
float motor1, motor3;
126
if (rover.g2.motors.have_skid_steering()) {
127
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) * 0.001f);
128
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) * 0.001f);
129
} else {
130
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_steering) / 4500.0f);
131
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f);
132
}
133
mavlink_msg_rc_channels_scaled_send(
134
chan,
135
millis(),
136
0, // port 0
137
motor1,
138
0,
139
motor3,
140
0,
141
0,
142
0,
143
0,
144
0,
145
#if AP_RSSI_ENABLED
146
receiver_rssi()
147
#else
148
UINT8_MAX
149
#endif
150
);
151
}
152
153
int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
154
{
155
return rover.g2.motors.get_throttle();
156
}
157
158
#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
159
void GCS_MAVLINK_Rover::send_rangefinder() const
160
{
161
float distance = 0;
162
float voltage = 0;
163
bool got_one = false;
164
165
// report smaller distance of all rangefinders
166
for (uint8_t i=0; i<rover.rangefinder.num_sensors(); i++) {
167
AP_RangeFinder_Backend *s = rover.rangefinder.get_backend(i);
168
if (s == nullptr) {
169
continue;
170
}
171
if (!got_one ||
172
s->distance() < distance) {
173
distance = s->distance();
174
voltage = s->voltage_mv();
175
got_one = true;
176
}
177
}
178
if (!got_one) {
179
// no relevant data found
180
return;
181
}
182
183
mavlink_msg_rangefinder_send(
184
chan,
185
distance,
186
voltage);
187
}
188
#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED
189
190
#if AP_RANGEFINDER_ENABLED
191
void GCS_MAVLINK_Rover::send_water_depth()
192
{
193
if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) {
194
return;
195
}
196
197
// only send for boats:
198
if (!rover.is_boat()) {
199
return;
200
}
201
202
RangeFinder *rangefinder = RangeFinder::get_singleton();
203
204
if (rangefinder == nullptr) {
205
return;
206
}
207
208
// depth can only be measured by a downward-facing rangefinder:
209
if (!rangefinder->has_orientation(ROTATION_PITCH_270)) {
210
return;
211
}
212
213
// get position
214
const AP_AHRS &ahrs = AP::ahrs();
215
Location loc;
216
IGNORE_RETURN(ahrs.get_location(loc));
217
218
const auto num_sensors = rangefinder->num_sensors();
219
for (uint8_t i=0; i<num_sensors; i++) {
220
last_WATER_DEPTH_index += 1;
221
if (last_WATER_DEPTH_index >= num_sensors) {
222
last_WATER_DEPTH_index = 0;
223
}
224
225
const AP_RangeFinder_Backend *s = rangefinder->get_backend(last_WATER_DEPTH_index);
226
227
if (s == nullptr || s->orientation() != ROTATION_PITCH_270 || !s->has_data()) {
228
continue;
229
}
230
231
// get temperature
232
float temp_C;
233
if (!s->get_temp(temp_C)) {
234
temp_C = 0.0f;
235
}
236
237
const bool sensor_healthy = (s->status() == RangeFinder::Status::Good);
238
239
mavlink_msg_water_depth_send(
240
chan,
241
AP_HAL::millis(), // time since system boot TODO: take time of measurement
242
last_WATER_DEPTH_index, // rangefinder instance
243
sensor_healthy, // sensor healthy
244
loc.lat, // latitude of vehicle
245
loc.lng, // longitude of vehicle
246
loc.alt * 0.01f, // altitude of vehicle (MSL)
247
ahrs.get_roll_rad(), // roll in radians
248
ahrs.get_pitch_rad(), // pitch in radians
249
ahrs.get_yaw_rad(), // yaw in radians
250
s->distance(), // distance in meters
251
temp_C); // temperature in degC
252
253
break; // only send one WATER_DEPTH message per loop
254
}
255
256
}
257
#endif // AP_RANGEFINDER_ENABLED
258
259
/*
260
send PID tuning message
261
*/
262
void GCS_MAVLINK_Rover::send_pid_tuning()
263
{
264
Parameters &g = rover.g;
265
ParametersG2 &g2 = rover.g2;
266
267
const AP_PIDInfo *pid_info;
268
269
// steering PID
270
if (g.gcs_pid_mask & 1) {
271
pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info();
272
mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER,
273
degrees(pid_info->target),
274
degrees(pid_info->actual),
275
pid_info->FF,
276
pid_info->P,
277
pid_info->I,
278
pid_info->D,
279
pid_info->slew_rate,
280
pid_info->Dmod);
281
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
282
return;
283
}
284
}
285
286
// speed to throttle PID
287
if (g.gcs_pid_mask & 2) {
288
pid_info = &g2.attitude_control.get_throttle_speed_pid_info();
289
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
290
pid_info->target,
291
pid_info->actual,
292
pid_info->FF,
293
pid_info->P,
294
pid_info->I,
295
pid_info->D,
296
pid_info->slew_rate,
297
pid_info->Dmod);
298
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
299
return;
300
}
301
}
302
303
// pitch to throttle pid
304
if (g.gcs_pid_mask & 4) {
305
pid_info = &g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info();
306
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
307
degrees(pid_info->target),
308
degrees(pid_info->actual),
309
pid_info->FF,
310
pid_info->P,
311
pid_info->I,
312
pid_info->D,
313
pid_info->slew_rate,
314
pid_info->Dmod);
315
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
316
return;
317
}
318
}
319
320
// left wheel rate control pid
321
if (g.gcs_pid_mask & 8) {
322
pid_info = &g2.wheel_rate_control.get_pid(0).get_pid_info();
323
mavlink_msg_pid_tuning_send(chan, 7,
324
pid_info->target,
325
pid_info->actual,
326
pid_info->FF,
327
pid_info->P,
328
pid_info->I,
329
pid_info->D,
330
pid_info->slew_rate,
331
pid_info->Dmod);
332
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
333
return;
334
}
335
}
336
337
// right wheel rate control pid
338
if (g.gcs_pid_mask & 16) {
339
pid_info = &g2.wheel_rate_control.get_pid(1).get_pid_info();
340
mavlink_msg_pid_tuning_send(chan, 8,
341
pid_info->target,
342
pid_info->actual,
343
pid_info->FF,
344
pid_info->P,
345
pid_info->I,
346
pid_info->D,
347
pid_info->slew_rate,
348
pid_info->Dmod);
349
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
350
return;
351
}
352
}
353
354
// sailboat heel to mainsail pid
355
if (g.gcs_pid_mask & 32) {
356
pid_info = &g2.attitude_control.get_sailboat_heel_pid().get_pid_info();
357
mavlink_msg_pid_tuning_send(chan, 9,
358
pid_info->target,
359
pid_info->actual,
360
pid_info->FF,
361
pid_info->P,
362
pid_info->I,
363
pid_info->D,
364
pid_info->slew_rate,
365
pid_info->Dmod);
366
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
367
return;
368
}
369
}
370
371
// Position Controller Velocity North PID
372
if (g.gcs_pid_mask & 64) {
373
pid_info = &g2.pos_control.get_vel_pid().get_pid_info_x();
374
mavlink_msg_pid_tuning_send(chan, 10,
375
pid_info->target,
376
pid_info->actual,
377
pid_info->FF,
378
pid_info->P,
379
pid_info->I,
380
pid_info->D,
381
pid_info->slew_rate,
382
pid_info->Dmod);
383
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
384
return;
385
}
386
}
387
388
// Position Controller Velocity East PID
389
if (g.gcs_pid_mask & 128) {
390
pid_info = &g2.pos_control.get_vel_pid().get_pid_info_y();
391
mavlink_msg_pid_tuning_send(chan, 11,
392
pid_info->target,
393
pid_info->actual,
394
pid_info->FF,
395
pid_info->P,
396
pid_info->I,
397
pid_info->D,
398
pid_info->slew_rate,
399
pid_info->Dmod);
400
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
401
return;
402
}
403
}
404
}
405
406
void Rover::send_wheel_encoder_distance(const mavlink_channel_t chan)
407
{
408
// send wheel encoder data using wheel_distance message
409
if (g2.wheel_encoder.num_sensors() > 0) {
410
double distances[MAVLINK_MSG_WHEEL_DISTANCE_FIELD_DISTANCE_LEN] {};
411
for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) {
412
distances[i] = wheel_encoder_last_distance_m[i];
413
}
414
mavlink_msg_wheel_distance_send(chan, 1000UL * AP_HAL::millis(), g2.wheel_encoder.num_sensors(), distances);
415
}
416
}
417
418
bool GCS_Rover::vehicle_initialised() const
419
{
420
return rover.control_mode != &rover.mode_initializing;
421
}
422
423
// try to send a message, return false if it won't fit in the serial tx buffer
424
bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
425
{
426
switch (id) {
427
428
case MSG_SERVO_OUT:
429
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
430
send_servo_out();
431
break;
432
433
case MSG_WHEEL_DISTANCE:
434
CHECK_PAYLOAD_SIZE(WHEEL_DISTANCE);
435
rover.send_wheel_encoder_distance(chan);
436
break;
437
438
case MSG_WIND:
439
CHECK_PAYLOAD_SIZE(WIND);
440
rover.g2.windvane.send_wind(chan);
441
break;
442
443
#if AP_OADATABASE_ENABLED
444
case MSG_ADSB_VEHICLE: {
445
AP_OADatabase *oadb = AP::oadatabase();
446
if (oadb != nullptr) {
447
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
448
uint16_t interval_ms = 0;
449
if (get_ap_message_interval(id, interval_ms)) {
450
oadb->send_adsb_vehicle(chan, interval_ms);
451
}
452
}
453
break;
454
}
455
#endif
456
457
#if AP_RANGEFINDER_ENABLED
458
case MSG_WATER_DEPTH:
459
CHECK_PAYLOAD_SIZE(WATER_DEPTH);
460
send_water_depth();
461
break;
462
#endif // AP_RANGEFINDER_ENABLED
463
464
default:
465
return GCS_MAVLINK::try_send_message(id);
466
}
467
return true;
468
}
469
bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd)
470
{
471
if (!rover.control_mode->in_guided_mode()) {
472
// only accept position updates when in GUIDED mode
473
return false;
474
}
475
476
// make any new wp uploaded instant (in case we are already in Guided mode)
477
return rover.mode_guided.set_desired_location(cmd.content.location);
478
}
479
480
MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
481
{
482
switch (packet.y) {
483
case 1:
484
if (rover.g2.windvane.start_direction_calibration()) {
485
return MAV_RESULT_ACCEPTED;
486
} else {
487
return MAV_RESULT_FAILED;
488
}
489
490
case 2:
491
if (rover.g2.windvane.start_speed_calibration()) {
492
return MAV_RESULT_ACCEPTED;
493
} else {
494
return MAV_RESULT_FAILED;
495
}
496
497
default:
498
break;
499
500
}
501
502
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
503
}
504
505
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
506
{
507
switch (packet.command) {
508
509
case MAV_CMD_DO_CHANGE_SPEED:
510
// param1 : type
511
// param2 : new speed in m/s
512
switch (SPEED_TYPE(packet.param1)) {
513
case SPEED_TYPE_CLIMB_SPEED:
514
case SPEED_TYPE_DESCENT_SPEED:
515
case SPEED_TYPE_ENUM_END:
516
return MAV_RESULT_DENIED;
517
518
case SPEED_TYPE_AIRSPEED: // Airspeed is treated as ground speed for GCS compatibility
519
case SPEED_TYPE_GROUNDSPEED:
520
break;
521
}
522
if (!rover.control_mode->set_desired_speed(packet.param2)) {
523
return MAV_RESULT_FAILED;
524
}
525
return MAV_RESULT_ACCEPTED;
526
527
case MAV_CMD_DO_REPOSITION:
528
return handle_command_int_do_reposition(packet);
529
530
case MAV_CMD_DO_SET_REVERSE:
531
// param1 : Direction (0=Forward, 1=Reverse)
532
rover.control_mode->set_reversed(is_equal(packet.param1,1.0f));
533
return MAV_RESULT_ACCEPTED;
534
535
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
536
if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) {
537
return MAV_RESULT_ACCEPTED;
538
}
539
return MAV_RESULT_FAILED;
540
541
case MAV_CMD_DO_MOTOR_TEST:
542
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
543
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
544
// param3 : throttle (range depends upon param2)
545
// param4 : timeout (in seconds)
546
return rover.mavlink_motor_test_start(*this,
547
(AP_MotorsUGV::motor_test_order)packet.param1,
548
static_cast<uint8_t>(packet.param2),
549
static_cast<int16_t>(packet.param3),
550
packet.param4);
551
552
case MAV_CMD_MISSION_START:
553
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
554
// first-item/last item not supported
555
return MAV_RESULT_DENIED;
556
}
557
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
558
return MAV_RESULT_ACCEPTED;
559
}
560
return MAV_RESULT_FAILED;
561
562
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
563
case MAV_CMD_NAV_SET_YAW_SPEED:
564
send_received_message_deprecation_warning("MAV_CMD_NAV_SET_YAW_SPEED");
565
return handle_command_nav_set_yaw_speed(packet, msg);
566
#endif
567
568
default:
569
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
570
}
571
}
572
573
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
574
MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
575
{
576
// param1 : yaw angle (may be absolute or relative)
577
// param2 : Speed - in metres/second
578
// param3 : 0 = param1 is absolute, 1 = param1 is relative
579
580
// exit if vehicle is not in Guided mode
581
if (!rover.control_mode->in_guided_mode()) {
582
return MAV_RESULT_FAILED;
583
}
584
585
// get final angle, 1 = Relative, 0 = Absolute
586
if (packet.param3 > 0) {
587
// relative angle
588
rover.mode_guided.set_desired_heading_delta_and_speed(packet.param1 * 100.0f, packet.param2);
589
} else {
590
// absolute angle
591
rover.mode_guided.set_desired_heading_and_speed(packet.param1 * 100.0f, packet.param2);
592
}
593
return MAV_RESULT_ACCEPTED;
594
}
595
#endif
596
597
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
598
{
599
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
600
if (!rover.control_mode->in_guided_mode() && !change_modes) {
601
return MAV_RESULT_DENIED;
602
}
603
604
// sanity check location
605
if (!check_latlng(packet.x, packet.y)) {
606
return MAV_RESULT_DENIED;
607
}
608
if (packet.x == 0 && packet.y == 0) {
609
return MAV_RESULT_DENIED;
610
}
611
612
Location requested_location {};
613
if (!location_from_command_t(packet, requested_location)) {
614
return MAV_RESULT_DENIED;
615
}
616
617
if (!rover.control_mode->in_guided_mode()) {
618
if (!rover.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {
619
return MAV_RESULT_FAILED;
620
}
621
}
622
623
if (is_positive(packet.param1)) {
624
if (!rover.control_mode->set_desired_speed(packet.param1)) {
625
return MAV_RESULT_FAILED;
626
}
627
}
628
629
// set the destination
630
if (!rover.mode_guided.set_desired_location(requested_location)) {
631
return MAV_RESULT_FAILED;
632
}
633
634
return MAV_RESULT_ACCEPTED;
635
}
636
637
void GCS_MAVLINK_Rover::handle_message(const mavlink_message_t &msg)
638
{
639
switch (msg.msgid) {
640
641
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
642
handle_set_attitude_target(msg);
643
break;
644
645
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
646
handle_set_position_target_local_ned(msg);
647
break;
648
649
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
650
handle_set_position_target_global_int(msg);
651
break;
652
653
default:
654
GCS_MAVLINK::handle_message(msg);
655
break;
656
}
657
}
658
659
void GCS_MAVLINK_Rover::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
660
{
661
manual_override(rover.channel_steer, packet.y, 1000, 2000, tnow);
662
manual_override(rover.channel_throttle, packet.z, 1000, 2000, tnow);
663
}
664
665
void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
666
{
667
// decode packet
668
mavlink_set_attitude_target_t packet;
669
mavlink_msg_set_attitude_target_decode(&msg, &packet);
670
671
// exit if vehicle is not in Guided mode
672
if (!rover.control_mode->in_guided_mode()) {
673
return;
674
}
675
676
// ensure type_mask specifies to use thrust
677
if ((packet.type_mask & MAVLINK_SET_ATT_TYPE_MASK_THROTTLE_IGNORE) != 0) {
678
return;
679
}
680
681
// convert thrust to ground speed
682
packet.thrust = constrain_float(packet.thrust, -1.0f, 1.0f);
683
const float target_speed = rover.control_mode->get_speed_default() * packet.thrust;
684
685
// if the body_yaw_rate field is ignored, convert quaternion to heading
686
if ((packet.type_mask & MAVLINK_SET_ATT_TYPE_MASK_YAW_RATE_IGNORE) != 0) {
687
// convert quaternion to heading
688
float target_heading_cd = degrees(Quaternion(packet.q[0], packet.q[1], packet.q[2], packet.q[3]).get_euler_yaw()) * 100.0f;
689
rover.mode_guided.set_desired_heading_and_speed(target_heading_cd, target_speed);
690
} else {
691
// use body_yaw_rate field
692
rover.mode_guided.set_desired_turn_rate_and_speed((RAD_TO_DEG * packet.body_yaw_rate) * 100.0f, target_speed);
693
}
694
}
695
696
// if we receive a message where the user has not masked out
697
// acceleration from the input packet we send a curt message
698
// informing them:
699
void GCS_MAVLINK_Rover::send_acc_ignore_must_be_set_message(const char *msgname)
700
{
701
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Ignoring %s; set ACC_IGNORE in mask", msgname);
702
}
703
704
void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_message_t &msg)
705
{
706
// decode packet
707
mavlink_set_position_target_local_ned_t packet;
708
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
709
710
// exit if vehicle is not in Guided mode
711
if (!rover.control_mode->in_guided_mode()) {
712
return;
713
}
714
715
// need ekf origin
716
Location ekf_origin;
717
if (!rover.ahrs.get_origin(ekf_origin)) {
718
return;
719
}
720
721
// check for supported coordinate frames
722
switch (packet.coordinate_frame) {
723
case MAV_FRAME_LOCAL_NED:
724
case MAV_FRAME_LOCAL_OFFSET_NED:
725
case MAV_FRAME_BODY_NED:
726
case MAV_FRAME_BODY_OFFSET_NED:
727
break;
728
729
default:
730
return;
731
}
732
733
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
734
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
735
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
736
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
737
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
738
739
// prepare target position
740
Location target_loc = rover.current_loc;
741
if (!pos_ignore) {
742
switch (packet.coordinate_frame) {
743
case MAV_FRAME_BODY_NED:
744
case MAV_FRAME_BODY_OFFSET_NED: {
745
// rotate from body-frame to NE frame
746
const float ne_x = packet.x * rover.ahrs.cos_yaw() - packet.y * rover.ahrs.sin_yaw();
747
const float ne_y = packet.x * rover.ahrs.sin_yaw() + packet.y * rover.ahrs.cos_yaw();
748
// add offset to current location
749
target_loc.offset(ne_x, ne_y);
750
}
751
break;
752
753
case MAV_FRAME_LOCAL_OFFSET_NED:
754
// add offset to current location
755
target_loc.offset(packet.x, packet.y);
756
break;
757
758
case MAV_FRAME_LOCAL_NED:
759
default:
760
// MAV_FRAME_LOCAL_NED is interpreted as an offset from EKF origin
761
target_loc = ekf_origin;
762
target_loc.offset(packet.x, packet.y);
763
break;
764
}
765
}
766
767
float target_speed = 0.0f;
768
float target_yaw_cd = 0.0f;
769
770
// consume velocity and convert to target speed and heading
771
if (!vel_ignore) {
772
const float speed_max = rover.control_mode->get_speed_default();
773
// convert vector length into a speed
774
target_speed = constrain_float(safe_sqrt(sq(packet.vx) + sq(packet.vy)), -speed_max, speed_max);
775
// convert vector direction to target yaw
776
target_yaw_cd = degrees(atan2f(packet.vy, packet.vx)) * 100.0f;
777
778
// rotate target yaw if provided in body-frame
779
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
780
target_yaw_cd = wrap_180_cd(target_yaw_cd + rover.ahrs.yaw_sensor);
781
}
782
}
783
784
// consume yaw heading
785
if (!yaw_ignore) {
786
target_yaw_cd = degrees(packet.yaw) * 100.0f;
787
// rotate target yaw if provided in body-frame
788
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
789
target_yaw_cd = wrap_180_cd(target_yaw_cd + rover.ahrs.yaw_sensor);
790
}
791
}
792
// consume yaw rate
793
float target_turn_rate_cds = 0.0f;
794
if (!yaw_rate_ignore) {
795
target_turn_rate_cds = degrees(packet.yaw_rate) * 100.0f;
796
}
797
798
// handling case when both velocity and either yaw or yaw-rate are provided
799
// by default, we consider that the rover will drive forward
800
float speed_dir = 1.0f;
801
if (!vel_ignore && (!yaw_ignore || !yaw_rate_ignore)) {
802
// Note: we are using the x-axis velocity to determine direction even though
803
// the frame may have been provided in MAV_FRAME_LOCAL_OFFSET_NED or MAV_FRAME_LOCAL_NED
804
if (is_negative(packet.vx)) {
805
speed_dir = -1.0f;
806
}
807
}
808
809
if (!acc_ignore) {
810
// ignore any command where acceleration is not ignored
811
send_acc_ignore_must_be_set_message("SET_POSITION_TARGET_LOCAL_NED");
812
return;
813
}
814
815
// set guided mode targets
816
if (!pos_ignore) {
817
// consume position target
818
if (!rover.mode_guided.set_desired_location(target_loc)) {
819
// GCS will need to monitor desired location to
820
// see if they are having an effect.
821
}
822
return;
823
}
824
825
if (!vel_ignore && yaw_ignore && yaw_rate_ignore) {
826
// consume velocity
827
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
828
} else if (!vel_ignore && yaw_ignore && !yaw_rate_ignore) {
829
// consume velocity and turn rate
830
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
831
} else if (!vel_ignore && !yaw_ignore && yaw_rate_ignore) {
832
// consume velocity and heading
833
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
834
} else if (vel_ignore && !yaw_ignore && yaw_rate_ignore) {
835
// consume just target heading (probably only skid steering vehicles can do this)
836
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
837
} else if (vel_ignore && yaw_ignore && !yaw_rate_ignore) {
838
// consume just turn rate (probably only skid steering vehicles can do this)
839
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
840
}
841
}
842
843
void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_message_t &msg)
844
{
845
// decode packet
846
mavlink_set_position_target_global_int_t packet;
847
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
848
849
// exit if vehicle is not in Guided mode
850
if (!rover.control_mode->in_guided_mode()) {
851
return;
852
}
853
// check for supported coordinate frames
854
switch (packet.coordinate_frame) {
855
case MAV_FRAME_GLOBAL:
856
case MAV_FRAME_GLOBAL_INT:
857
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
858
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
859
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
860
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
861
break;
862
863
default:
864
return;
865
}
866
867
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
868
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
869
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
870
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
871
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
872
873
// prepare target position
874
Location target_loc = rover.current_loc;
875
if (!pos_ignore) {
876
// sanity check location
877
if (!check_latlng(packet.lat_int, packet.lon_int)) {
878
// result = MAV_RESULT_FAILED;
879
return;
880
}
881
target_loc.lat = packet.lat_int;
882
target_loc.lng = packet.lon_int;
883
}
884
885
float target_speed = 0.0f;
886
float target_yaw_cd = 0.0f;
887
888
// consume velocity and convert to target speed and heading
889
if (!vel_ignore) {
890
const float speed_max = rover.control_mode->get_speed_default();
891
// convert vector length into a speed
892
target_speed = constrain_float(safe_sqrt(sq(packet.vx) + sq(packet.vy)), -speed_max, speed_max);
893
// convert vector direction to target yaw
894
target_yaw_cd = degrees(atan2f(packet.vy, packet.vx)) * 100.0f;
895
}
896
897
// consume yaw heading
898
if (!yaw_ignore) {
899
target_yaw_cd = degrees(packet.yaw) * 100.0f;
900
}
901
902
// consume yaw rate
903
float target_turn_rate_cds = 0.0f;
904
if (!yaw_rate_ignore) {
905
target_turn_rate_cds = degrees(packet.yaw_rate) * 100.0f;
906
}
907
908
// handling case when both velocity and either yaw or yaw-rate are provided
909
// by default, we consider that the rover will drive forward
910
float speed_dir = 1.0f;
911
if (!vel_ignore && (!yaw_ignore || !yaw_rate_ignore)) {
912
// Note: we are using the x-axis velocity to determine direction even though
913
// the frame is provided in MAV_FRAME_GLOBAL_xxx
914
if (is_negative(packet.vx)) {
915
speed_dir = -1.0f;
916
}
917
}
918
919
if (!acc_ignore) {
920
// ignore any command where acceleration is not ignored
921
send_acc_ignore_must_be_set_message("SET_POSITION_TARGET_GLOBAL_INT");
922
return;
923
}
924
925
// set guided mode targets
926
if (!pos_ignore) {
927
// consume position target
928
if (!rover.mode_guided.set_desired_location(target_loc)) {
929
// GCS will just need to look at desired location
930
// outputs to see if it having an effect.
931
}
932
return;
933
}
934
935
if (!vel_ignore && yaw_ignore && yaw_rate_ignore) {
936
// consume velocity
937
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
938
} else if (!vel_ignore && yaw_ignore && !yaw_rate_ignore) {
939
// consume velocity and turn rate
940
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
941
} else if (!vel_ignore && !yaw_ignore && yaw_rate_ignore) {
942
// consume velocity
943
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
944
} else if (vel_ignore && !yaw_ignore && yaw_rate_ignore) {
945
// consume just target heading (probably only skid steering vehicles can do this)
946
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
947
} else if (vel_ignore && yaw_ignore && !yaw_rate_ignore) {
948
// consume just turn rate(probably only skid steering vehicles can do this)
949
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
950
}
951
}
952
953
/*
954
handle a LANDING_TARGET command. The timestamp has been jitter corrected
955
*/
956
void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
957
{
958
#if AC_PRECLAND_ENABLED
959
rover.precland.handle_msg(packet, timestamp_ms);
960
#endif
961
}
962
963
uint64_t GCS_MAVLINK_Rover::capabilities() const
964
{
965
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
966
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
967
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
968
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
969
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
970
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
971
GCS_MAVLINK::capabilities());
972
}
973
974
#if HAL_HIGH_LATENCY2_ENABLED
975
uint8_t GCS_MAVLINK_Rover::high_latency_tgt_heading() const
976
{
977
const Mode *control_mode = rover.control_mode;
978
if (rover.control_mode->is_autopilot_mode()) {
979
// need to convert -180->180 to 0->360/2
980
return wrap_360(control_mode->wp_bearing()) / 2;
981
}
982
return 0;
983
}
984
985
uint16_t GCS_MAVLINK_Rover::high_latency_tgt_dist() const
986
{
987
const Mode *control_mode = rover.control_mode;
988
if (rover.control_mode->is_autopilot_mode()) {
989
// return units are dm
990
return MIN((control_mode->get_distance_to_destination()) / 10, UINT16_MAX);
991
}
992
return 0;
993
}
994
995
uint8_t GCS_MAVLINK_Rover::high_latency_tgt_airspeed() const
996
{
997
const Mode *control_mode = rover.control_mode;
998
if (rover.control_mode->is_autopilot_mode()) {
999
// return units are m/s*5
1000
return MIN((vfr_hud_airspeed() - control_mode->speed_error()) * 5, UINT8_MAX);
1001
}
1002
return 0;
1003
}
1004
1005
uint8_t GCS_MAVLINK_Rover::high_latency_wind_speed() const
1006
{
1007
if (rover.g2.windvane.enabled()) {
1008
// return units are m/s*5
1009
return MIN(rover.g2.windvane.get_true_wind_speed() * 5, UINT8_MAX);
1010
}
1011
return 0;
1012
}
1013
1014
uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const
1015
{
1016
if (rover.g2.windvane.enabled()) {
1017
// return units are deg/2
1018
return wrap_360(degrees(rover.g2.windvane.get_true_wind_direction_rad())) / 2;
1019
}
1020
return 0;
1021
}
1022
#endif // HAL_HIGH_LATENCY2_ENABLED
1023
1024
// Send the mode with the given index (not mode number!) return the total number of modes
1025
// Index starts at 1
1026
uint8_t GCS_MAVLINK_Rover::send_available_mode(uint8_t index) const
1027
{
1028
const Mode* modes[] {
1029
&rover.mode_manual,
1030
&rover.mode_acro,
1031
&rover.mode_steering,
1032
&rover.mode_hold,
1033
&rover.mode_loiter,
1034
#if MODE_FOLLOW_ENABLED
1035
&rover.mode_follow,
1036
#endif
1037
&rover.mode_simple,
1038
&rover.g2.mode_circle,
1039
&rover.mode_auto,
1040
&rover.mode_rtl,
1041
&rover.mode_smartrtl,
1042
&rover.mode_guided,
1043
&rover.mode_initializing,
1044
#if MODE_DOCK_ENABLED
1045
(Mode *)rover.g2.mode_dock_ptr,
1046
#endif
1047
};
1048
1049
const uint8_t mode_count = ARRAY_SIZE(modes);
1050
1051
// Convert to zero indexed
1052
const uint8_t index_zero = index - 1;
1053
if (index_zero >= mode_count) {
1054
// Mode does not exist!?
1055
return mode_count;
1056
}
1057
1058
// Ask the mode for its name and number
1059
const char* name = modes[index_zero]->name();
1060
const uint8_t mode_number = (uint8_t)modes[index_zero]->mode_number();
1061
1062
mavlink_msg_available_modes_send(
1063
chan,
1064
mode_count,
1065
index,
1066
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
1067
mode_number,
1068
0, // MAV_MODE_PROPERTY bitmask
1069
name
1070
);
1071
1072
return mode_count;
1073
}
1074
1075