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