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/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp
Views: 1798
1
#include "AP_Frsky_SPort_Passthrough.h"
2
3
#if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
4
5
#include <AP_AHRS/AP_AHRS.h>
6
#include <AP_BattMonitor/AP_BattMonitor.h>
7
#include <AP_GPS/AP_GPS.h>
8
#include <AP_HAL/utility/RingBuffer.h>
9
#include <AP_InertialSensor/AP_InertialSensor.h>
10
#include <AP_Notify/AP_Notify.h>
11
#include <AP_RangeFinder/AP_RangeFinder.h>
12
#include <AP_RPM/AP_RPM.h>
13
#include <AP_Terrain/AP_Terrain.h>
14
#include <AC_Fence/AC_Fence.h>
15
#include <AP_Vehicle/AP_Vehicle.h>
16
#include <GCS_MAVLink/GCS.h>
17
#if APM_BUILD_TYPE(APM_BUILD_Rover)
18
#include <AP_WindVane/AP_WindVane.h>
19
#endif
20
21
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
22
#include "AP_Frsky_MAVlite.h"
23
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
24
#include "AP_Frsky_Parameters.h"
25
26
/*
27
for FrSky SPort Passthrough
28
*/
29
// data bits preparation
30
// for parameter data
31
#define PARAM_ID_OFFSET 24
32
#define PARAM_VALUE_LIMIT 0xFFFFFF
33
// for gps status data
34
#define GPS_SATS_LIMIT 0xF
35
#define GPS_STATUS_LIMIT 0x3
36
#define GPS_STATUS_OFFSET 4
37
#define GPS_HDOP_OFFSET 6
38
#define GPS_ADVSTATUS_OFFSET 14
39
#define GPS_ALTMSL_OFFSET 22
40
// for battery data
41
#define BATT_VOLTAGE_LIMIT 0x1FF
42
#define BATT_CURRENT_OFFSET 9
43
#define BATT_TOTALMAH_LIMIT 0x7FFF
44
#define BATT_TOTALMAH_OFFSET 17
45
// for autopilot status data
46
#define AP_CONTROL_MODE_LIMIT 0x1F
47
#define AP_SIMPLE_OFFSET 5
48
#define AP_SSIMPLE_OFFSET 6
49
#define AP_FLYING_OFFSET 7
50
#define AP_ARMED_OFFSET 8
51
#define AP_BATT_FS_OFFSET 9
52
#define AP_EKF_FS_OFFSET 10
53
#define AP_FS_OFFSET 12
54
#define AP_FENCE_PRESENT_OFFSET 13
55
#define AP_FENCE_BREACH_OFFSET 14
56
#define AP_THROTTLE_OFFSET 19
57
#define AP_IMU_TEMP_MIN 19.0f
58
#define AP_IMU_TEMP_MAX 82.0f
59
#define AP_IMU_TEMP_OFFSET 26
60
// for home position related data
61
#define HOME_ALT_OFFSET 12
62
#define HOME_BEARING_LIMIT 0x7F
63
#define HOME_BEARING_OFFSET 25
64
// for velocity and yaw data
65
#define VELANDYAW_XYVEL_OFFSET 9
66
#define VELANDYAW_YAW_LIMIT 0x7FF
67
#define VELANDYAW_YAW_OFFSET 17
68
#define VELANDYAW_ARSPD_OFFSET 28
69
// for attitude (roll, pitch) and range data
70
#define ATTIANDRNG_ROLL_LIMIT 0x7FF
71
#define ATTIANDRNG_PITCH_LIMIT 0x3FF
72
#define ATTIANDRNG_PITCH_OFFSET 11
73
#define ATTIANDRNG_RNGFND_OFFSET 21
74
// for terrain data
75
#define TERRAIN_UNHEALTHY_OFFSET 13
76
// for wind data
77
#define WIND_ANGLE_LIMIT 0x7F
78
#define WIND_SPEED_OFFSET 7
79
#define WIND_APPARENT_ANGLE_OFFSET 15
80
#define WIND_APPARENT_SPEED_OFFSET 22
81
// for waypoint data
82
#define WP_NUMBER_LIMIT 2047
83
#define WP_DISTANCE_LIMIT 1023000
84
#define WP_DISTANCE_OFFSET 11
85
#define WP_BEARING_OFFSET 23
86
87
extern const AP_HAL::HAL& hal;
88
89
AP_Frsky_SPort_Passthrough *AP_Frsky_SPort_Passthrough::singleton;
90
91
bool AP_Frsky_SPort_Passthrough::init()
92
{
93
if (!AP_RCTelemetry::init()) {
94
return false;
95
}
96
return AP_Frsky_SPort::init();
97
}
98
99
bool AP_Frsky_SPort_Passthrough::init_serial_port()
100
{
101
if (_use_external_data) {
102
return true;
103
}
104
return AP_Frsky_SPort::init_serial_port();
105
}
106
107
void AP_Frsky_SPort_Passthrough::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data)
108
{
109
if (_use_external_data) {
110
external_data.packet.frame = frame;
111
external_data.packet.appid = appid;
112
external_data.packet.data = data;
113
external_data.pending = true;
114
return;
115
}
116
117
return AP_Frsky_SPort::send_sport_frame(frame, appid, data);
118
}
119
120
/*
121
setup ready for passthrough telem
122
*/
123
void AP_Frsky_SPort_Passthrough::setup_wfq_scheduler(void)
124
{
125
// initialize packet weights for the WFQ scheduler
126
// priority[i] = 1/_scheduler.packet_weight[i]
127
// rate[i] = LinkRate * ( priority[i] / (sum(priority[1-n])) )
128
set_scheduler_entry(TEXT, 35, 28); // 0x5000 status text (dynamic)
129
set_scheduler_entry(ATTITUDE, 50, 38); // 0x5006 Attitude and range (dynamic)
130
set_scheduler_entry(GPS_LAT, 550, 280); // 0x800 GPS lat
131
set_scheduler_entry(GPS_LON, 550, 280); // 0x800 GPS lon
132
set_scheduler_entry(VEL_YAW, 400, 250); // 0x5005 Vel and Yaw
133
set_scheduler_entry(AP_STATUS, 700, 500); // 0x5001 AP status
134
set_scheduler_entry(GPS_STATUS, 700, 500); // 0x5002 GPS status
135
set_scheduler_entry(HOME, 400, 500); // 0x5004 Home
136
set_scheduler_entry(BATT_2, 1300, 500); // 0x5008 Battery 2 status
137
set_scheduler_entry(BATT_1, 1300, 500); // 0x5003 Battery 1 status
138
set_scheduler_entry(PARAM, 1700, 1000); // 0x5007 parameters
139
set_scheduler_entry(RPM, 300, 330); // 0x500A rpm sensors 1 and 2
140
set_scheduler_entry(TERRAIN, 700, 500); // 0x500B terrain data
141
set_scheduler_entry(WIND, 700, 500); // 0x500C wind data
142
set_scheduler_entry(WAYPOINT, 750, 500); // 0x500D waypoint data
143
set_scheduler_entry(UDATA, 5000, 200); // user data
144
145
// initialize default sport sensor ID
146
set_sensor_id(_frsky_parameters->_dnlink_id, downlink_sensor_id);
147
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
148
set_scheduler_entry(MAV, 35, 25); // mavlite
149
// initialize sport sensor IDs
150
set_sensor_id(_frsky_parameters->_uplink_id, _SPort_bidir.uplink_sensor_id);
151
set_sensor_id(_frsky_parameters->_dnlink1_id, _SPort_bidir.downlink1_sensor_id);
152
set_sensor_id(_frsky_parameters->_dnlink2_id, _SPort_bidir.downlink2_sensor_id);
153
// initialize sport
154
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Frsky_SPort_Passthrough::process_rx_queue, void));
155
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
156
}
157
158
/*
159
dynamically change scheduler priorities based on queue sizes
160
*/
161
void AP_Frsky_SPort_Passthrough::adjust_packet_weight(bool queue_empty)
162
{
163
/*
164
When queues are empty set a low priority (high weight), when queues
165
are not empty set a higher priority (low weight) based on the following
166
relative priority order: mavlite > status text > attitude.
167
*/
168
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
169
if (!_SPort_bidir.tx_packet_queue.is_empty()) {
170
_scheduler.packet_weight[MAV] = 30; // mavlite
171
if (!queue_empty) {
172
_scheduler.packet_weight[TEXT] = 45; // messages
173
_scheduler.packet_weight[ATTITUDE] = 80; // attitude
174
} else {
175
_scheduler.packet_weight[TEXT] = 5000; // messages
176
_scheduler.packet_weight[ATTITUDE] = 80; // attitude
177
}
178
} else {
179
_scheduler.packet_weight[MAV] = 5000; // mavlite
180
if (!queue_empty) {
181
_scheduler.packet_weight[TEXT] = 45; // messages
182
_scheduler.packet_weight[ATTITUDE] = 80; // attitude
183
} else {
184
_scheduler.packet_weight[TEXT] = 5000; // messages
185
_scheduler.packet_weight[ATTITUDE] = 45; // attitude
186
}
187
}
188
#else //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
189
if (!queue_empty) {
190
_scheduler.packet_weight[TEXT] = 45; // messages
191
_scheduler.packet_weight[ATTITUDE] = 80; // attitude
192
} else {
193
_scheduler.packet_weight[TEXT] = 5000; // messages
194
_scheduler.packet_weight[ATTITUDE] = 45; // attitude
195
}
196
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
197
// when using fport raise user data priority if any packets are pending
198
if (_use_external_data && _sport_push_buffer.pending) {
199
_scheduler.packet_weight[UDATA] = 250;
200
} else {
201
_scheduler.packet_weight[UDATA] = 5000; // user data
202
}
203
}
204
205
// WFQ scheduler
206
bool AP_Frsky_SPort_Passthrough::is_packet_ready(uint8_t idx, bool queue_empty)
207
{
208
bool packet_ready = false;
209
switch (idx) {
210
case TEXT:
211
packet_ready = !queue_empty;
212
break;
213
case GPS_LAT:
214
case GPS_LON:
215
// force gps coords to use default sensor ID, always send when used with external data
216
packet_ready = _use_external_data || (_passthrough.new_byte == downlink_sensor_id);
217
break;
218
case AP_STATUS:
219
packet_ready = gcs().vehicle_initialised();
220
break;
221
case BATT_2:
222
packet_ready = AP::battery().num_instances() > 1;
223
break;
224
case RPM:
225
{
226
packet_ready = false;
227
#if AP_RPM_ENABLED
228
const AP_RPM *rpm = AP::rpm();
229
if (rpm == nullptr) {
230
break;
231
}
232
packet_ready = rpm->num_sensors() > 0;
233
#endif
234
}
235
break;
236
case TERRAIN:
237
{
238
packet_ready = false;
239
#if AP_TERRAIN_AVAILABLE
240
const AP_Terrain *terrain = AP::terrain();
241
packet_ready = terrain && terrain->enabled();
242
#endif
243
}
244
break;
245
case WIND:
246
#if !APM_BUILD_TYPE(APM_BUILD_Rover)
247
{
248
float a;
249
WITH_SEMAPHORE(AP::ahrs().get_semaphore());
250
if (AP::ahrs().airspeed_estimate_true(a)) {
251
// if we have an airspeed estimate then we have a valid wind estimate
252
packet_ready = true;
253
}
254
}
255
#else
256
{
257
const AP_WindVane* windvane = AP_WindVane::get_singleton();
258
packet_ready = windvane != nullptr && windvane->enabled();
259
}
260
#endif
261
break;
262
case WAYPOINT:
263
{
264
const AP_Mission *mission = AP::mission();
265
packet_ready = mission != nullptr && mission->get_current_nav_index() > 0;
266
}
267
break;
268
case UDATA:
269
// when using fport user data is sent by scheduler
270
// when using sport user data is sent responding to custom polling
271
packet_ready = _use_external_data && _sport_push_buffer.pending;
272
break;
273
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
274
case MAV:
275
packet_ready = !_SPort_bidir.tx_packet_queue.is_empty();
276
break;
277
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
278
default:
279
packet_ready = true;
280
break;
281
}
282
283
return packet_ready;
284
}
285
286
/*
287
* WFQ scheduler
288
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
289
*/
290
void AP_Frsky_SPort_Passthrough::process_packet(uint8_t idx)
291
{
292
// send packet
293
switch (idx) {
294
case TEXT: // 0x5000 status text
295
if (get_next_msg_chunk()) {
296
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID, _msg_chunk.chunk);
297
}
298
break;
299
case ATTITUDE: // 0x5006 Attitude and range
300
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+6, calc_attiandrng());
301
break;
302
case GPS_LAT: // 0x800 GPS lat
303
// sample both lat and lon at the same time
304
send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(_passthrough.send_latitude)); // gps latitude or longitude
305
_passthrough.gps_lng_sample = calc_gps_latlng(_passthrough.send_latitude);
306
// force the scheduler to select GPS lon as packet that's been waiting the most
307
// this guarantees that lat and lon are sent as consecutive packets
308
_scheduler.packet_timer[GPS_LON] = _scheduler.packet_timer[GPS_LAT] - 10000;
309
break;
310
case GPS_LON: // 0x800 GPS lon
311
send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, _passthrough.gps_lng_sample); // gps longitude
312
break;
313
case VEL_YAW: // 0x5005 Vel and Yaw
314
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+5, calc_velandyaw());
315
break;
316
case AP_STATUS: // 0x5001 AP status
317
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+1, calc_ap_status());
318
break;
319
case GPS_STATUS: // 0x5002 GPS Status
320
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+2, calc_gps_status());
321
break;
322
case HOME: // 0x5004 Home
323
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+4, calc_home());
324
break;
325
case BATT_2: // 0x5008 Battery 2 status
326
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+8, calc_batt(1));
327
break;
328
case BATT_1: // 0x5003 Battery 1 status
329
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+3, calc_batt(0));
330
break;
331
case PARAM: // 0x5007 parameters
332
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+7, calc_param());
333
break;
334
case RPM: // 0x500A rpm sensors 1 and 2
335
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0A, calc_rpm());
336
break;
337
case TERRAIN: // 0x500B terrain data
338
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0B, calc_terrain());
339
break;
340
case WIND: // 0x500C terrain data
341
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0C, calc_wind());
342
break;
343
case WAYPOINT: // 0x500D waypoint data
344
send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0D, calc_waypoint());
345
break;
346
case UDATA: // user data
347
{
348
WITH_SEMAPHORE(_sport_push_buffer.sem);
349
if (_use_external_data && _sport_push_buffer.pending) {
350
send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);
351
_sport_push_buffer.pending = false;
352
}
353
}
354
break;
355
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
356
case MAV: // mavlite
357
process_tx_queue();
358
break;
359
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
360
}
361
}
362
363
/*
364
* send telemetry data
365
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
366
*/
367
void AP_Frsky_SPort_Passthrough::send(void)
368
{
369
const uint16_t numc = MIN(_port->available(), 1024U);
370
371
// this is the constant for hub data frame
372
if (_port->txspace() < 19) {
373
return;
374
}
375
// keep only the last two bytes of the data found in the serial buffer, as we shouldn't respond to old poll requests
376
uint8_t prev_byte = 0;
377
for (uint16_t i = 0; i < numc; i++) {
378
prev_byte = _passthrough.new_byte;
379
_passthrough.new_byte = _port->read();
380
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
381
AP_Frsky_SPort::sport_packet_t sp;
382
383
if (_sport_handler.process_byte(sp, _passthrough.new_byte)) {
384
queue_rx_packet(sp);
385
}
386
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
387
}
388
// check if we should respond to this polling byte
389
if (prev_byte == FRAME_HEAD) {
390
if (is_passthrough_byte(_passthrough.new_byte)) {
391
run_wfq_scheduler();
392
} else {
393
// respond to custom user data polling
394
WITH_SEMAPHORE(_sport_push_buffer.sem);
395
if (_sport_push_buffer.pending && _passthrough.new_byte == _sport_push_buffer.packet.sensor) {
396
send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);
397
_sport_push_buffer.pending = false;
398
}
399
}
400
}
401
}
402
403
/*
404
* grabs one "chunk" (4 bytes) of the queued message to be transmitted
405
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
406
*/
407
bool AP_Frsky_SPort_Passthrough::get_next_msg_chunk(void)
408
{
409
if (!_statustext.available) {
410
WITH_SEMAPHORE(_statustext.sem);
411
if (!_statustext.queue.pop(_statustext.next)) {
412
return false;
413
}
414
_statustext.available = true;
415
}
416
417
if (_msg_chunk.repeats == 0) { // if it's the first time get_next_msg_chunk is called for a given chunk
418
uint8_t character = 0;
419
_msg_chunk.chunk = 0; // clear the 4 bytes of the chunk buffer
420
421
for (uint8_t i = 0; i < 4 && _msg_chunk.char_index < sizeof(_statustext.next.text); i++) {
422
character = _statustext.next.text[_msg_chunk.char_index++];
423
424
if (!character) {
425
break;
426
}
427
428
_msg_chunk.chunk |= character << (3-i) * 8;
429
}
430
431
if (!character || (_msg_chunk.char_index == sizeof(_statustext.next.text))) { // we've reached the end of the message (string terminated by '\0' or last character of the string has been processed)
432
_msg_chunk.char_index = 0; // reset index to get ready to process the next message
433
// add severity which is sent as the MSB of the last three bytes of the last chunk (bits 24, 16, and 8) since a character is on 7 bits
434
_msg_chunk.chunk |= (_statustext.next.severity & 0x4)<<21;
435
_msg_chunk.chunk |= (_statustext.next.severity & 0x2)<<14;
436
_msg_chunk.chunk |= (_statustext.next.severity & 0x1)<<7;
437
}
438
}
439
440
// repeat each message chunk 3 times to ensure transmission
441
// on slow links reduce the number of duplicate chunks
442
uint8_t extra_chunks = 2;
443
444
if (_scheduler.avg_packet_rate < 20) {
445
// with 3 or more extra frsky sensors on the bus
446
// send messages only once
447
extra_chunks = 0;
448
} else if (_scheduler.avg_packet_rate < 30) {
449
// with 1 or 2 extra frsky sensors on the bus
450
// send messages twice
451
extra_chunks = 1;
452
}
453
454
if (_msg_chunk.repeats++ > extra_chunks ) {
455
_msg_chunk.repeats = 0;
456
if (_msg_chunk.char_index == 0) {
457
// we're ready for the next message
458
_statustext.available = false;
459
}
460
}
461
return true;
462
}
463
464
/*
465
* prepare parameter data
466
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
467
*/
468
uint32_t AP_Frsky_SPort_Passthrough::calc_param(void)
469
{
470
uint8_t param_id = _paramID; //cache it because it gets changed inside the switch
471
uint32_t param_value = 0;
472
473
switch (_paramID) {
474
case NONE:
475
case FRAME_TYPE:
476
param_value = gcs().frame_type(); // see MAV_TYPE in Mavlink definition file common.h
477
_paramID = BATT_CAPACITY_1;
478
break;
479
case BATT_CAPACITY_1:
480
param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(0)); // battery pack capacity in mAh
481
_paramID = AP::battery().num_instances() > 1 ? BATT_CAPACITY_2 : TELEMETRY_FEATURES;
482
break;
483
case BATT_CAPACITY_2:
484
param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(1)); // battery pack capacity in mAh
485
_paramID = TELEMETRY_FEATURES;
486
break;
487
case TELEMETRY_FEATURES:
488
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
489
BIT_SET(param_value,PassthroughFeatures::BIDIR);
490
#endif
491
#if AP_SCRIPTING_ENABLED
492
BIT_SET(param_value,PassthroughFeatures::SCRIPTING);
493
#endif
494
_paramID = FRAME_TYPE;
495
break;
496
}
497
//Reserve first 8 bits for param ID, use other 24 bits to store parameter value
498
return (param_id << PARAM_ID_OFFSET) | (param_value & PARAM_VALUE_LIMIT);
499
}
500
501
/*
502
* prepare gps status data
503
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
504
*/
505
uint32_t AP_Frsky_SPort_Passthrough::calc_gps_status(void)
506
{
507
const AP_GPS &gps = AP::gps();
508
509
// number of GPS satellites visible (limit to 15 (0xF) since the value is stored on 4 bits)
510
uint32_t gps_status = (gps.num_sats() < GPS_SATS_LIMIT) ? gps.num_sats() : GPS_SATS_LIMIT;
511
// GPS receiver status (limit to 0-3 (0x3) since the value is stored on 2 bits: NO_GPS = 0, NO_FIX = 1, GPS_OK_FIX_2D = 2, GPS_OK_FIX_3D or GPS_OK_FIX_3D_DGPS or GPS_OK_FIX_3D_RTK_FLOAT or GPS_OK_FIX_3D_RTK_FIXED = 3)
512
gps_status |= ((gps.status() < GPS_STATUS_LIMIT) ? gps.status() : GPS_STATUS_LIMIT)<<GPS_STATUS_OFFSET;
513
// GPS horizontal dilution of precision in dm
514
gps_status |= prep_number(roundf(gps.get_hdop() * 0.1f),2,1)<<GPS_HDOP_OFFSET;
515
// GPS receiver advanced status (0: no advanced fix, 1: GPS_OK_FIX_3D_DGPS, 2: GPS_OK_FIX_3D_RTK_FLOAT, 3: GPS_OK_FIX_3D_RTK_FIXED)
516
gps_status |= ((gps.status() > GPS_STATUS_LIMIT) ? gps.status()-GPS_STATUS_LIMIT : 0)<<GPS_ADVSTATUS_OFFSET;
517
// Altitude MSL in dm
518
const Location &loc = gps.location();
519
gps_status |= prep_number(roundf(loc.alt * 0.1f),2,2)<<GPS_ALTMSL_OFFSET;
520
return gps_status;
521
}
522
523
/*
524
* prepare battery data
525
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
526
*/
527
uint32_t AP_Frsky_SPort_Passthrough::calc_batt(uint8_t instance)
528
{
529
const AP_BattMonitor &_battery = AP::battery();
530
531
float current, consumed_mah;
532
if (!_battery.current_amps(current, instance)) {
533
current = 0;
534
}
535
if (!_battery.consumed_mah(consumed_mah, instance)) {
536
consumed_mah = 0;
537
}
538
539
// battery voltage in decivolts, can have up to a 12S battery (4.25Vx12S = 51.0V)
540
uint32_t batt = (((uint16_t)roundf(_battery.voltage(instance) * 10.0f)) & BATT_VOLTAGE_LIMIT);
541
// battery current draw in deciamps
542
batt |= prep_number(roundf(current * 10.0f), 2, 1)<<BATT_CURRENT_OFFSET;
543
// battery current drawn since power on in mAh (limit to 32767 (0x7FFF) since value is stored on 15 bits)
544
batt |= ((consumed_mah < BATT_TOTALMAH_LIMIT) ? ((uint16_t)roundf(consumed_mah) & BATT_TOTALMAH_LIMIT) : BATT_TOTALMAH_LIMIT)<<BATT_TOTALMAH_OFFSET;
545
return batt;
546
}
547
548
/*
549
* true if we need to respond to the last polling byte
550
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
551
*/
552
bool AP_Frsky_SPort_Passthrough::is_passthrough_byte(const uint8_t byte) const
553
{
554
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
555
if( byte == _SPort_bidir.downlink1_sensor_id || byte == _SPort_bidir.downlink2_sensor_id ) {
556
return true;
557
}
558
#endif
559
return byte == downlink_sensor_id;
560
}
561
562
/*
563
* prepare various autopilot status data
564
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
565
*/
566
uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void)
567
{
568
// IMU temperature: offset -19, 0 means temp =< 19°, 63 means temp => 82°
569
uint8_t imu_temp = 0;
570
#if AP_INERTIALSENSOR_ENABLED
571
imu_temp = (uint8_t) roundf(constrain_float(AP::ins().get_temperature(0), AP_IMU_TEMP_MIN, AP_IMU_TEMP_MAX) - AP_IMU_TEMP_MIN);
572
#endif
573
574
// control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits)
575
uint32_t ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT);
576
// simple/super simple modes flags
577
ap_status |= (uint8_t)(gcs().simple_input_active())<<AP_SIMPLE_OFFSET;
578
ap_status |= (uint8_t)(gcs().supersimple_input_active())<<AP_SSIMPLE_OFFSET;
579
// is_flying flag
580
ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET;
581
// armed flag
582
ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;
583
// battery failsafe flag
584
ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery)<<AP_BATT_FS_OFFSET;
585
// bad ekf flag
586
ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<<AP_EKF_FS_OFFSET;
587
// generic failsafe
588
ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery||AP_Notify::flags.failsafe_ekf||AP_Notify::flags.failsafe_gcs||AP_Notify::flags.failsafe_radio)<<AP_FS_OFFSET;
589
#if AP_FENCE_ENABLED
590
// fence status
591
AC_Fence *fence = AP::fence();
592
if (fence != nullptr) {
593
ap_status |= (uint8_t)(fence->enabled() && fence->present()) << AP_FENCE_PRESENT_OFFSET;
594
ap_status |= (uint8_t)(fence->get_breaches()>0) << AP_FENCE_BREACH_OFFSET;
595
}
596
#endif
597
// signed throttle [-100,100] scaled down to [-63,63] on 7 bits, MSB for sign + 6 bits for 0-63
598
ap_status |= prep_number(gcs().get_hud_throttle()*0.63, 2, 0)<<AP_THROTTLE_OFFSET;
599
// IMU temperature
600
ap_status |= imu_temp << AP_IMU_TEMP_OFFSET;
601
return ap_status;
602
}
603
604
/*
605
* prepare home position related data
606
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
607
*/
608
uint32_t AP_Frsky_SPort_Passthrough::calc_home(void)
609
{
610
uint32_t home = 0;
611
Location loc;
612
Location home_loc;
613
bool got_position = false;
614
float _relative_home_altitude = 0;
615
616
{
617
AP_AHRS &_ahrs = AP::ahrs();
618
WITH_SEMAPHORE(_ahrs.get_semaphore());
619
got_position = _ahrs.get_location(loc);
620
home_loc = _ahrs.get_home();
621
}
622
623
if (got_position) {
624
// check home_loc is valid
625
if (home_loc.lat != 0 || home_loc.lng != 0) {
626
// distance between vehicle and home_loc in meters
627
home = prep_number(roundf(home_loc.get_distance(loc)), 3, 2);
628
// angle from front of vehicle to the direction of home_loc in 3 degree increments (just in case, limit to 127 (0x7F) since the value is stored on 7 bits)
629
home |= (((uint8_t)roundf(loc.get_bearing_to(home_loc) * 0.00333f)) & HOME_BEARING_LIMIT)<<HOME_BEARING_OFFSET;
630
}
631
// altitude between vehicle and home_loc
632
_relative_home_altitude = loc.alt;
633
if (!loc.relative_alt) {
634
// loc.alt has home altitude added, remove it
635
_relative_home_altitude -= home_loc.alt;
636
}
637
}
638
// altitude above home in decimeters
639
home |= prep_number(roundf(_relative_home_altitude * 0.1f), 3, 2)<<HOME_ALT_OFFSET;
640
return home;
641
}
642
643
/*
644
* prepare velocity and yaw data
645
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
646
*/
647
uint32_t AP_Frsky_SPort_Passthrough::calc_velandyaw(void)
648
{
649
float vspd = AP_RCTelemetry::get_vspeed_ms();
650
// vertical velocity in dm/s
651
uint32_t velandyaw = prep_number(roundf(vspd * 10), 2, 1);
652
float airspeed_m; // m/s
653
float hspeed_m; // m/s
654
bool airspeed_estimate_true;
655
AP_AHRS &_ahrs = AP::ahrs();
656
{
657
WITH_SEMAPHORE(_ahrs.get_semaphore());
658
hspeed_m = _ahrs.groundspeed(); // default is to use groundspeed
659
airspeed_estimate_true = AP::ahrs().airspeed_estimate_true(airspeed_m);
660
}
661
bool option_airspeed_enabled = (_frsky_parameters->_options & frsky_options_e::OPTION_AIRSPEED_AND_GROUNDSPEED) != 0;
662
// airspeed estimate + airspeed option disabled (default) => send airspeed (we give priority to airspeed over groundspeed)
663
// airspeed estimate + airspeed option enabled => alternate airspeed/groundspeed, i.e send airspeed only when _passthrough.send_airspeed==true
664
if (airspeed_estimate_true && (!option_airspeed_enabled || _passthrough.send_airspeed)) {
665
hspeed_m = airspeed_m;
666
}
667
// horizontal velocity in dm/s
668
velandyaw |= prep_number(roundf(hspeed_m * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;
669
// yaw from [0;36000] centidegrees to .2 degree increments [0;1800] (just in case, limit to 2047 (0x7FF) since the value is stored on 11 bits)
670
velandyaw |= ((uint16_t)roundf(_ahrs.yaw_sensor * 0.05f) & VELANDYAW_YAW_LIMIT)<<VELANDYAW_YAW_OFFSET;
671
// flag the airspeed bit if required
672
if (airspeed_estimate_true && option_airspeed_enabled && _passthrough.send_airspeed) {
673
velandyaw |= 1U<<VELANDYAW_ARSPD_OFFSET;
674
}
675
// toggle air/ground speed selector
676
_passthrough.send_airspeed = !_passthrough.send_airspeed;
677
return velandyaw;
678
}
679
680
/*
681
* prepare attitude (roll, pitch) and range data
682
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
683
*/
684
uint32_t AP_Frsky_SPort_Passthrough::calc_attiandrng(void)
685
{
686
#if AP_RANGEFINDER_ENABLED
687
const RangeFinder *_rng = RangeFinder::get_singleton();
688
#endif
689
690
float roll;
691
float pitch;
692
AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);
693
// roll from [-18000;18000] centidegrees to unsigned .2 degree increments [0;1800] (just in case, limit to 2047 (0x7FF) since the value is stored on 11 bits)
694
uint32_t attiandrng = ((uint16_t)roundf((roll * RAD_TO_DEG * 100 + 18000) * 0.05f) & ATTIANDRNG_ROLL_LIMIT);
695
// pitch from [-9000;9000] centidegrees to unsigned .2 degree increments [0;900] (just in case, limit to 1023 (0x3FF) since the value is stored on 10 bits)
696
attiandrng |= ((uint16_t)roundf((pitch * RAD_TO_DEG * 100 + 9000) * 0.05f) & ATTIANDRNG_PITCH_LIMIT)<<ATTIANDRNG_PITCH_OFFSET;
697
// rangefinder measurement in cm
698
#if AP_RANGEFINDER_ENABLED
699
attiandrng |= prep_number(_rng ? _rng->distance_cm_orient(ROTATION_PITCH_270) : 0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;
700
#else
701
attiandrng |= prep_number(0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;
702
#endif
703
return attiandrng;
704
}
705
706
/*
707
* prepare rpm for sensors 1 and 2
708
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
709
*/
710
uint32_t AP_Frsky_SPort_Passthrough::calc_rpm(void)
711
{
712
#if AP_RPM_ENABLED
713
const AP_RPM *ap_rpm = AP::rpm();
714
if (ap_rpm == nullptr) {
715
return 0;
716
}
717
uint32_t value = 0;
718
// we send: rpm_value*0.1 as 16 bits signed
719
float rpm;
720
// bits 0-15 for rpm 0
721
if (ap_rpm->get_rpm(0,rpm)) {
722
value |= (int16_t)roundf(rpm * 0.1);
723
}
724
// bits 16-31 for rpm 1
725
if (ap_rpm->get_rpm(1,rpm)) {
726
value |= (int16_t)roundf(rpm * 0.1) << 16;
727
}
728
return value;
729
#else
730
return 0;
731
#endif
732
}
733
734
/*
735
* prepare terrain data
736
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
737
*/
738
uint32_t AP_Frsky_SPort_Passthrough::calc_terrain(void)
739
{
740
uint32_t value = 0;
741
#if AP_TERRAIN_AVAILABLE
742
AP_Terrain *terrain = AP::terrain();
743
if (terrain == nullptr || !terrain->enabled()) {
744
return value;
745
}
746
float height_above_terrain;
747
if (terrain->height_above_terrain(height_above_terrain, true)) {
748
// vehicle height above terrain
749
value |= prep_number(roundf(height_above_terrain * 10), 3, 2);
750
}
751
// terrain unhealthy flag
752
value |= (uint8_t)(terrain->status() == AP_Terrain::TerrainStatus::TerrainStatusUnhealthy) << TERRAIN_UNHEALTHY_OFFSET;
753
#endif
754
return value;
755
}
756
757
/*
758
* prepare wind data
759
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
760
* wind direction = 0 means North
761
*/
762
uint32_t AP_Frsky_SPort_Passthrough::calc_wind(void)
763
{
764
#if !APM_BUILD_TYPE(APM_BUILD_Rover)
765
Vector3f v;
766
{
767
AP_AHRS &ahrs = AP::ahrs();
768
WITH_SEMAPHORE(ahrs.get_semaphore());
769
v = ahrs.wind_estimate();
770
}
771
// wind angle in 3 degree increments 0,360 (unsigned)
772
uint32_t value = prep_number(roundf(wrap_360(degrees(atan2f(-v.y, -v.x))) * (1.0f/3.0f)), 2, 0);
773
// wind speed in dm/s
774
value |= prep_number(roundf(v.length() * 10), 2, 1) << WIND_SPEED_OFFSET;
775
#else
776
const AP_WindVane* windvane = AP_WindVane::get_singleton();
777
uint32_t value = 0;
778
if (windvane != nullptr && windvane->enabled()) {
779
// true wind angle in 3 degree increments 0,360 (unsigned)
780
value = prep_number(roundf(wrap_360(degrees(windvane->get_true_wind_direction_rad())) * (1.0f/3.0f)), 2, 0);
781
// true wind speed in dm/s
782
value |= prep_number(roundf(windvane->get_true_wind_speed() * 10), 2, 1) << WIND_SPEED_OFFSET;
783
// apparent wind angle in 3 degree increments -180,180 (signed)
784
value |= prep_number(roundf(degrees(windvane->get_apparent_wind_direction_rad()) * (1.0f/3.0f)), 2, 0) << WIND_APPARENT_ANGLE_OFFSET;
785
// apparent wind speed in dm/s
786
value |= prep_number(roundf(windvane->get_apparent_wind_speed() * 10), 2, 1) << WIND_APPARENT_SPEED_OFFSET;
787
}
788
#endif
789
return value;
790
}
791
/*
792
* prepare waypoint data
793
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
794
*/
795
uint32_t AP_Frsky_SPort_Passthrough::calc_waypoint(void)
796
{
797
const AP_Mission *mission = AP::mission();
798
const AP_Vehicle *vehicle = AP::vehicle();
799
if (mission == nullptr || vehicle == nullptr) {
800
return 0U;
801
}
802
float wp_distance;
803
if (!vehicle->get_wp_distance_m(wp_distance)) {
804
return 0U;
805
}
806
float angle;
807
if (!vehicle->get_wp_bearing_deg(angle)) {
808
return 0U;
809
}
810
// waypoint current nav index
811
uint32_t value = MIN(mission->get_current_nav_index(), WP_NUMBER_LIMIT);
812
// distance to next waypoint
813
value |= prep_number(wp_distance, 3, 2) << WP_DISTANCE_OFFSET;
814
// bearing encoded in 3 degrees increments
815
value |= ((uint8_t)roundf(wrap_360(angle) * 0.333f)) << WP_BEARING_OFFSET;
816
return value;
817
}
818
819
/*
820
fetch Sport data for an external transport, such as FPort or crossfire
821
Note: we need to create a packet array with unique packet types
822
For very big frames we might have to relax the "unique packet type per frame"
823
constraint in order to maximize bandwidth usage
824
*/
825
bool AP_Frsky_SPort_Passthrough::get_telem_data(sport_packet_t* packet_array, uint8_t &packet_count, const uint8_t max_size)
826
{
827
if (!_use_external_data) {
828
return false;
829
}
830
831
uint8_t idx = 0;
832
833
// max_size >= WFQ_LAST_ITEM
834
// get a packet per enabled type
835
if (max_size >= WFQ_LAST_ITEM) {
836
for (uint8_t i=0; i<WFQ_LAST_ITEM; i++) {
837
if (process_scheduler_entry(i)) {
838
if (external_data.pending) {
839
packet_array[idx].frame = external_data.packet.frame;
840
packet_array[idx].appid = external_data.packet.appid;
841
packet_array[idx].data = external_data.packet.data;
842
idx++;
843
external_data.pending = false;
844
}
845
}
846
}
847
} else {
848
// max_size < WFQ_LAST_ITEM
849
// call run_wfq_scheduler(false) enough times to create a packet of up to max_size unique elements
850
uint32_t item_mask = 0;
851
for (uint8_t i=0; i<max_size; i++) {
852
// call the scheduler with the shaper "disabled"
853
const uint8_t item = run_wfq_scheduler(false);
854
if (!BIT_IS_SET(item_mask, item) && external_data.pending) {
855
// ok got some data, flip the bitmask bit to prevent adding the same packet type more than once
856
BIT_SET(item_mask, item);
857
packet_array[idx].frame = external_data.packet.frame;
858
packet_array[idx].appid = external_data.packet.appid;
859
packet_array[idx].data = external_data.packet.data;
860
idx++;
861
external_data.pending = false;
862
}
863
}
864
}
865
packet_count = idx;
866
return idx > 0;
867
}
868
869
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
870
/*
871
allow external transports (e.g. FPort), to supply telemetry data
872
*/
873
bool AP_Frsky_SPort_Passthrough::set_telem_data(const uint8_t frame, const uint16_t appid, const uint32_t data)
874
{
875
// queue only Uplink packets
876
if (frame == SPORT_UPLINK_FRAME || frame == SPORT_UPLINK_FRAME_RW) {
877
const AP_Frsky_SPort::sport_packet_t sp {
878
{ 0x00, // this is ignored by process_sport_rx_queue() so no need for a real sensor ID
879
frame,
880
appid,
881
data }
882
};
883
884
_SPort_bidir.rx_packet_queue.push_force(sp);
885
return true;
886
}
887
return false;
888
}
889
890
/*
891
* Queue uplink packets in the sport rx queue
892
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
893
*/
894
void AP_Frsky_SPort_Passthrough::queue_rx_packet(const AP_Frsky_SPort::sport_packet_t packet)
895
{
896
// queue only Uplink packets
897
if (packet.sensor == _SPort_bidir.uplink_sensor_id && packet.frame == SPORT_UPLINK_FRAME) {
898
_SPort_bidir.rx_packet_queue.push_force(packet);
899
}
900
}
901
902
/*
903
* Extract up to 1 mavlite message from the sport rx packet queue
904
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
905
*/
906
void AP_Frsky_SPort_Passthrough::process_rx_queue()
907
{
908
AP_Frsky_SPort::sport_packet_t packet;
909
uint8_t loop_count = 0; // prevent looping forever
910
while (_SPort_bidir.rx_packet_queue.pop(packet) && loop_count++ < MAVLITE_MSG_SPORT_PACKETS_COUNT(MAVLITE_MAX_PAYLOAD_LEN)) {
911
AP_Frsky_MAVlite_Message rxmsg;
912
913
if (sport_to_mavlite.process(rxmsg, packet)) {
914
mavlite.process_message(rxmsg);
915
break; // process only 1 mavlite message each call
916
}
917
}
918
}
919
920
/*
921
* Process the sport tx queue
922
* pop and send 1 sport packet
923
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
924
*/
925
void AP_Frsky_SPort_Passthrough::process_tx_queue()
926
{
927
AP_Frsky_SPort::sport_packet_t packet;
928
929
if (!_SPort_bidir.tx_packet_queue.peek(packet)) {
930
return;
931
}
932
933
// when using fport repeat each packet to account for
934
// fport packet loss (around 15%)
935
if (!_use_external_data || _SPort_bidir.tx_packet_duplicates++ == SPORT_TX_PACKET_DUPLICATES) {
936
_SPort_bidir.tx_packet_queue.pop();
937
_SPort_bidir.tx_packet_duplicates = 0;
938
}
939
940
send_sport_frame(SPORT_DOWNLINK_FRAME, packet.appid, packet.data);
941
}
942
943
/*
944
* Send a mavlite message
945
* Message is chunked in sport packets pushed in the tx queue
946
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
947
*/
948
bool AP_Frsky_SPort_Passthrough::send_message(const AP_Frsky_MAVlite_Message &txmsg)
949
{
950
return mavlite_to_sport.process(_SPort_bidir.tx_packet_queue, txmsg);
951
}
952
#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
953
/*
954
* Utility method to apply constraints in changing sensor id values
955
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
956
*/
957
void AP_Frsky_SPort_Passthrough::set_sensor_id(AP_Int8 param_idx, uint8_t &sensor)
958
{
959
int8_t idx = param_idx.get();
960
961
if (idx == -1) {
962
// disable this sensor
963
sensor = 0xFF;
964
return;
965
}
966
sensor = calc_sensor_id(idx);
967
}
968
969
namespace AP
970
{
971
AP_Frsky_SPort_Passthrough *frsky_passthrough_telem()
972
{
973
return AP_Frsky_SPort_Passthrough::get_singleton();
974
}
975
};
976
977
#endif // AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
978
979