APM:Libraries
AP_Frsky_Telem.cpp
Go to the documentation of this file.
1 /*
2 
3  Inspired by work done here https://github.com/PX4/Firmware/tree/master/src/drivers/frsky_telemetry from Stefan Rado <px4@sradonia.net>
4 
5  This program is free software: you can redistribute it and/or modify
6  it under the terms of the GNU General Public License as published by
7  the Free Software Foundation, either version 3 of the License, or
8  (at your option) any later version.
9 
10  This program is distributed in the hope that it will be useful,
11  but WITHOUT ANY WARRANTY; without even the implied warranty of
12  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  GNU General Public License for more details.
14 
15  You should have received a copy of the GNU General Public License
16  along with this program. If not, see <http://www.gnu.org/licenses/>.
17 */
18 
19 /*
20  FRSKY Telemetry library
21 */
22 #include "AP_Frsky_Telem.h"
23 #include <GCS_MAVLink/GCS.h>
24 
25 extern const AP_HAL::HAL& hal;
26 
28 
29 //constructor
31  _ahrs(ahrs),
32  _battery(battery),
33  _rng(rng)
34  {}
35 
36 /*
37  * init - perform required initialisation
38  */
39 void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep)
40 {
41  // check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
42  if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
43  _protocol = AP_SerialManager::SerialProtocol_FrSky_D; // FrSky D protocol (D-receivers)
44  } else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) {
45  _protocol = AP_SerialManager::SerialProtocol_FrSky_SPort; // FrSky SPort protocol (X-receivers)
47  _protocol = AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough; // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
48  // make frsky_telemetry available to GCS_MAVLINK (used to queue statustext messages from GCS_MAVLINK)
50  // add firmware and frame info to message queue
51  queue_message(MAV_SEVERITY_INFO, firmware_str);
52  // save main parameters locally
53  _params.mav_type = mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
54  if (ap_valuep == nullptr) { // ap bit-field
55  _ap.value = 0x2000; // set "initialised" to 1 for rover and plane
56  _ap.valuep = &_ap.value;
57  } else {
58  _ap.valuep = ap_valuep;
59  }
60  }
61 
62  if (_port != nullptr) {
64  // we don't want flow control for either protocol
66  }
67 }
68 
69 
70 /*
71  * send telemetry data
72  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
73  */
75 {
76  int16_t numc;
77  numc = _port->available();
78 
79  // check if available is negative
80  if (numc < 0) {
81  return;
82  }
83 
84  // this is the constant for hub data frame
85  if (_port->txspace() < 19) {
86  return;
87  }
88 
89  // keep only the last two bytes of the data found in the serial buffer, as we shouldn't respond to old poll requests
90  uint8_t prev_byte = 0;
91  for (int16_t i = 0; i < numc; i++) {
92  prev_byte = _passthrough.new_byte;
93  _passthrough.new_byte = _port->read();
94  }
95 
96  if ((prev_byte == START_STOP_SPORT) && (_passthrough.new_byte == SENSOR_ID_28)) { // byte 0x7E is the header of each poll request
97  if (_passthrough.send_attiandrng) { // skip other data, send attitude (roll, pitch) and range only this iteration
98  _passthrough.send_attiandrng = false; // next iteration, check if we should send something other
99  } else { // send other sensor data if it's time for them, and reset the corresponding timer if sent
100  _passthrough.send_attiandrng = true; // next iteration, send attitude b/c it needs frequent updates to remain smooth
101  uint32_t now = AP_HAL::millis();
102  if ((now - _passthrough.params_timer) >= 1000) {
104  _passthrough.params_timer = AP_HAL::millis();
105  return;
106  }
107  // build message queue for sensor_status_flags
109  // build message queue for ekf_status
111  // if there's any message in the queue, start sending them chunk by chunk; three times each chunk
112  if (get_next_msg_chunk()) {
114  return;
115  }
116  if ((now - _passthrough.ap_status_timer) >= 500) {
117  if (((*_ap.valuep) & AP_INITIALIZED_FLAG) > 0) { // send ap status only once vehicle has been initialised
119  _passthrough.ap_status_timer = AP_HAL::millis();
120  }
121  return;
122  }
123  if ((now - _passthrough.batt_timer) >= 1000) {
125  _passthrough.batt_timer = AP_HAL::millis();
126  return;
127  }
128  if (_battery.num_instances() > 1) {
129  if ((now - _passthrough.batt_timer2) >= 1000) {
131  _passthrough.batt_timer2 = AP_HAL::millis();
132  return;
133  }
134  }
135  if ((now - _passthrough.gps_status_timer) >= 1000) {
137  _passthrough.gps_status_timer = AP_HAL::millis();
138  return;
139  }
140  if ((now - _passthrough.home_timer) >= 500) {
142  _passthrough.home_timer = AP_HAL::millis();
143  return;
144  }
145  if ((now - _passthrough.velandyaw_timer) >= 500) {
147  _passthrough.velandyaw_timer = AP_HAL::millis();
148  return;
149  }
150  if ((now - _passthrough.gps_latlng_timer) >= 1000) {
151  send_uint32(GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(&_passthrough.send_latitude)); // gps latitude or longitude
152  if (!_passthrough.send_latitude) { // we've cycled and sent one each of longitude then latitude, so reset the timer
153  _passthrough.gps_latlng_timer = AP_HAL::millis();
154  }
155  return;
156  }
157  }
158  // if nothing else needed to be sent, send attitude (roll, pitch) and range data
160  }
161 }
162 
163 /*
164  * send telemetry data
165  * for FrSky SPort protocol (X-receivers)
166  */
168 {
169  int16_t numc;
170  numc = _port->available();
171 
172  // check if available is negative
173  if (numc < 0) {
174  return;
175  }
176 
177  // this is the constant for hub data frame
178  if (_port->txspace() < 19) {
179  return;
180  }
181 
182  for (int16_t i = 0; i < numc; i++) {
183  int16_t readbyte = _port->read();
184  if (_SPort.sport_status == false) {
185  if (readbyte == START_STOP_SPORT) {
186  _SPort.sport_status = true;
187  }
188  } else {
189  switch(readbyte) {
190  case SENSOR_ID_FAS:
191  switch (_SPort.fas_call) {
192  case 0:
193  send_uint32(DATA_ID_FUEL, (uint16_t)roundf(_battery.capacity_remaining_pct())); // send battery remaining
194  break;
195  case 1:
196  send_uint32(DATA_ID_VFAS, (uint16_t)roundf(_battery.voltage() * 10.0f)); // send battery voltage
197  break;
198  case 2:
199  send_uint32(DATA_ID_CURRENT, (uint16_t)roundf(_battery.current_amps() * 10.0f)); // send current consumption
200  break;
201  }
202  if (_SPort.fas_call++ > 2) _SPort.fas_call = 0;
203  break;
204  case SENSOR_ID_GPS:
205  switch (_SPort.gps_call) {
206  case 0:
207  calc_gps_position(); // gps data is not recalculated until all of it has been sent
208  send_uint32(DATA_ID_GPS_LAT_BP, _gps.latdddmm); // send gps lattitude degree and minute integer part
209  break;
210  case 1:
211  send_uint32(DATA_ID_GPS_LAT_AP, _gps.latmmmm); // send gps lattitude minutes decimal part
212  break;
213  case 2:
214  send_uint32(DATA_ID_GPS_LAT_NS, _gps.lat_ns); // send gps North / South information
215  break;
216  case 3:
217  send_uint32(DATA_ID_GPS_LONG_BP, _gps.londddmm); // send gps longitude degree and minute integer part
218  break;
219  case 4:
220  send_uint32(DATA_ID_GPS_LONG_AP, _gps.lonmmmm); // send gps longitude minutes decimal part
221  break;
222  case 5:
223  send_uint32(DATA_ID_GPS_LONG_EW, _gps.lon_ew); // send gps East / West information
224  break;
225  case 6:
226  send_uint32(DATA_ID_GPS_SPEED_BP, _gps.speed_in_meter); // send gps speed integer part
227  break;
228  case 7:
229  send_uint32(DATA_ID_GPS_SPEED_AP, _gps.speed_in_centimeter); // send gps speed decimal part
230  break;
231  case 8:
232  send_uint32(DATA_ID_GPS_ALT_BP, _gps.alt_gps_meters); // send gps altitude integer part
233  break;
234  case 9:
235  send_uint32(DATA_ID_GPS_ALT_AP, _gps.alt_gps_cm); // send gps altitude decimals
236  break;
237  case 10:
238  send_uint32(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360)); // send heading in degree based on AHRS and not GPS
239  break;
240  }
241  if (_SPort.gps_call++ > 10) _SPort.gps_call = 0;
242  break;
243  case SENSOR_ID_VARIO:
244  switch (_SPort.vario_call) {
245  case 0 :
246  calc_nav_alt(); // nav altitude is not recalculated until all of it has been sent
247  send_uint32(DATA_ID_BARO_ALT_BP, _gps.alt_nav_meters); // send altitude integer part
248  break;
249  case 1:
250  send_uint32(DATA_ID_BARO_ALT_AP, _gps.alt_nav_cm); // send altitude decimal part
251  break;
252  }
253  if (_SPort.vario_call++ > 1) _SPort.vario_call = 0;
254  break;
255  case SENSOR_ID_SP2UR:
256  switch (_SPort.various_call) {
257  case 0 :
258  send_uint32(DATA_ID_TEMP2, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status())); // send GPS status and number of satellites as num_sats*10 + status (to fit into a uint8_t)
259  break;
260  case 1:
261  send_uint32(DATA_ID_TEMP1, _ap.control_mode); // send flight mode
262  break;
263  }
264  if (_SPort.various_call++ > 1) _SPort.various_call = 0;
265  break;
266  }
267  _SPort.sport_status = false;
268  }
269  }
270 }
271 
272 /*
273  * send frame1 and frame2 telemetry data
274  * one frame (frame1) is sent every 200ms with baro alt, nb sats, batt volts and amp, control_mode
275  * a second frame (frame2) is sent every second (1000ms) with gps position data, and ahrs.yaw_sensor heading (instead of GPS heading)
276  * for FrSky D protocol (D-receivers)
277  */
279 {
280  uint32_t now = AP_HAL::millis();
281  // send frame1 every 200ms
282  if (now - _D.last_200ms_frame >= 200) {
283  _D.last_200ms_frame = now;
284  send_uint16(DATA_ID_TEMP2, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status())); // send GPS status and number of satellites as num_sats*10 + status (to fit into a uint8_t)
285  send_uint16(DATA_ID_TEMP1, _ap.control_mode); // send flight mode
286  send_uint16(DATA_ID_FUEL, (uint16_t)roundf(_battery.capacity_remaining_pct())); // send battery remaining
287  send_uint16(DATA_ID_VFAS, (uint16_t)roundf(_battery.voltage() * 10.0f)); // send battery voltage
288  send_uint16(DATA_ID_CURRENT, (uint16_t)roundf(_battery.current_amps() * 10.0f)); // send current consumption
289  calc_nav_alt();
290  send_uint16(DATA_ID_BARO_ALT_BP, _gps.alt_nav_meters); // send nav altitude integer part
291  send_uint16(DATA_ID_BARO_ALT_AP, _gps.alt_nav_cm); // send nav altitude decimal part
292  }
293  // send frame2 every second
294  if (now - _D.last_1000ms_frame >= 1000) {
295  _D.last_1000ms_frame = now;
296  send_uint16(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360)); // send heading in degree based on AHRS and not GPS
298  if (AP::gps().status() >= 3) {
299  send_uint16(DATA_ID_GPS_LAT_BP, _gps.latdddmm); // send gps lattitude degree and minute integer part
300  send_uint16(DATA_ID_GPS_LAT_AP, _gps.latmmmm); // send gps lattitude minutes decimal part
301  send_uint16(DATA_ID_GPS_LAT_NS, _gps.lat_ns); // send gps North / South information
302  send_uint16(DATA_ID_GPS_LONG_BP, _gps.londddmm); // send gps longitude degree and minute integer part
303  send_uint16(DATA_ID_GPS_LONG_AP, _gps.lonmmmm); // send gps longitude minutes decimal part
304  send_uint16(DATA_ID_GPS_LONG_EW, _gps.lon_ew); // send gps East / West information
305  send_uint16(DATA_ID_GPS_SPEED_BP, _gps.speed_in_meter); // send gps speed integer part
306  send_uint16(DATA_ID_GPS_SPEED_AP, _gps.speed_in_centimeter); // send gps speed decimal part
307  send_uint16(DATA_ID_GPS_ALT_BP, _gps.alt_gps_meters); // send gps altitude integer part
308  send_uint16(DATA_ID_GPS_ALT_AP, _gps.alt_gps_cm); // send gps altitude decimal part
309  }
310  }
311 }
312 
313 /*
314  * tick - main call to send data to the receiver (called by scheduler at 1kHz)
315  */
317 {
318  // check UART has been initialised
319  if (!_initialised_uart) {
320  // initialise uart (this must be called from within tick b/c the UART begin must be called from the same thread as it is used from)
321  if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
323  } else { // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
325  }
326  _initialised_uart = true;// true when we have detected the protocol and UART has been initialised
327  }
328 
329  if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
330  send_D();
331  } else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort) { // FrSky SPort protocol (X-receivers)
332  send_SPort();
333  } else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough) { // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
335  }
336 }
337 
338 /*
339  * build up the frame's crc
340  * for FrSky SPort protocol (X-receivers)
341  */
343 {
344  _crc += byte; //0-1FF
345  _crc += _crc >> 8; //0-100
346  _crc &= 0xFF;
347 }
348 
349 /*
350  * send the frame's crc at the end of the frame
351  * for FrSky SPort protocol (X-receivers)
352  */
354 {
355  send_byte(0xFF - _crc);
356  _crc = 0;
357 }
358 
359 
360 /*
361  send 1 byte and do byte stuffing
362 */
364 {
365  if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
366  if (byte == START_STOP_D) {
367  _port->write(0x5D);
368  _port->write(0x3E);
369  } else if (byte == BYTESTUFF_D) {
370  _port->write(0x5D);
371  _port->write(0x3D);
372  } else {
373  _port->write(byte);
374  }
375  } else { // FrSky SPort protocol (X-receivers)
376  if (byte == START_STOP_SPORT) {
377  _port->write(0x7D);
378  _port->write(0x5E);
379  } else if (byte == BYTESTUFF_SPORT) {
380  _port->write(0x7D);
381  _port->write(0x5D);
382  } else {
383  _port->write(byte);
384  }
385  calc_crc(byte);
386  }
387 }
388 
389 /*
390  * send one uint32 frame of FrSky data - for FrSky SPort protocol (X-receivers)
391  */
392 void AP_Frsky_Telem::send_uint32(uint16_t id, uint32_t data)
393 {
394  send_byte(0x10); // DATA_FRAME
395  uint8_t *bytes = (uint8_t*)&id;
396  send_byte(bytes[0]); // LSB
397  send_byte(bytes[1]); // MSB
398  bytes = (uint8_t*)&data;
399  send_byte(bytes[0]); // LSB
400  send_byte(bytes[1]);
401  send_byte(bytes[2]);
402  send_byte(bytes[3]); // MSB
403  send_crc();
404 }
405 
406 /*
407  * send one uint16 frame of FrSky data - for FrSky D protocol (D-receivers)
408  */
409 void AP_Frsky_Telem::send_uint16(uint16_t id, uint16_t data)
410 {
411  _port->write(START_STOP_D); // send a 0x5E start byte
412  uint8_t *bytes = (uint8_t*)&id;
413  send_byte(bytes[0]);
414  bytes = (uint8_t*)&data;
415  send_byte(bytes[0]); // LSB
416  send_byte(bytes[1]); // MSB
417 }
418 
419 /*
420  * grabs one "chunk" (4 bytes) of the queued message to be transmitted
421  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
422  */
424 {
425  if (_statustext_queue.empty()) {
426  return false;
427  }
428 
429  if (_msg_chunk.repeats == 0) { // if it's the first time get_next_msg_chunk is called for a given chunk
430  uint8_t character = 0;
431  _msg_chunk.chunk = 0; // clear the 4 bytes of the chunk buffer
432 
433  for (int i = 3; i > -1 && _msg_chunk.char_index < sizeof(_statustext_queue[0]->text); i--) {
434  character = _statustext_queue[0]->text[_msg_chunk.char_index++];
435 
436  if (!character) {
437  break;
438  }
439 
440  _msg_chunk.chunk |= character << i * 8;
441  }
442 
443  if (!character || (_msg_chunk.char_index == sizeof(_statustext_queue[0]->text))) { // we've reached the end of the message (string terminated by '\0' or last character of the string has been processed)
444  _msg_chunk.char_index = 0; // reset index to get ready to process the next message
445  // 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
446  _msg_chunk.chunk |= (_statustext_queue[0]->severity & 0x4)<<21;
447  _msg_chunk.chunk |= (_statustext_queue[0]->severity & 0x2)<<14;
448  _msg_chunk.chunk |= (_statustext_queue[0]->severity & 0x1)<<7;
449  }
450  }
451 
452  if (_msg_chunk.repeats++ > 2) { // repeat each message chunk 3 times to ensure transmission
453  _msg_chunk.repeats = 0;
454  if (_msg_chunk.char_index == 0) { // if we're ready for the next message
456  }
457  }
458  return true;
459 }
460 
461 /*
462  * add message to message cue for transmission through FrSky link
463  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
464  */
465 void AP_Frsky_Telem::queue_message(MAV_SEVERITY severity, const char *text)
466 {
467  mavlink_statustext_t statustext{};
468 
469  statustext.severity = severity;
470  strncpy(statustext.text, text, sizeof(statustext.text));
471 
472  // The force push will ensure comm links do not block other comm links forever if they fail.
473  // If we push to a full buffer then we overwrite the oldest entry, effectively removing the
474  // block but not until the buffer fills up.
475  _statustext_queue.push_force(statustext);
476 }
477 
478 /*
479  * add sensor_status_flags information to message cue, normally passed as sys_status mavlink messages to the GCS, for transmission through FrSky link
480  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
481  */
483 {
484  uint32_t now = AP_HAL::millis();
485 
486  if ((now - check_sensor_status_timer) >= 5000) { // prevent repeating any system_status messages unless 5 seconds have passed
487  // only one error is reported at a time (in order of preference). Same setup and displayed messages as Mission Planner.
488  if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_GPS) > 0) {
489  queue_message(MAV_SEVERITY_CRITICAL, "Bad GPS Health");
491  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_GYRO) > 0) {
492  queue_message(MAV_SEVERITY_CRITICAL, "Bad Gyro Health");
494  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_ACCEL) > 0) {
495  queue_message(MAV_SEVERITY_CRITICAL, "Bad Accel Health");
497  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_MAG) > 0) {
498  queue_message(MAV_SEVERITY_CRITICAL, "Bad Compass Health");
500  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE) > 0) {
501  queue_message(MAV_SEVERITY_CRITICAL, "Bad Baro Health");
503  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_LASER_POSITION) > 0) {
504  queue_message(MAV_SEVERITY_CRITICAL, "Bad LiDAR Health");
506  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) > 0) {
507  queue_message(MAV_SEVERITY_CRITICAL, "Bad OptFlow Health");
509  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_TERRAIN) > 0) {
510  queue_message(MAV_SEVERITY_CRITICAL, "Bad or No Terrain Data");
512  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_GEOFENCE) > 0) {
513  queue_message(MAV_SEVERITY_CRITICAL, "Geofence Breach");
515  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_AHRS) > 0) {
516  queue_message(MAV_SEVERITY_CRITICAL, "Bad AHRS");
518  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_RC_RECEIVER) > 0) {
519  queue_message(MAV_SEVERITY_CRITICAL, "No RC Receiver");
521  } else if ((_ap.sensor_status_flags & MAV_SYS_STATUS_LOGGING) > 0) {
522  queue_message(MAV_SEVERITY_CRITICAL, "Bad Logging");
524  }
525  }
526 }
527 
528 /*
529  * add innovation variance information to message cue, normally passed as ekf_status_report mavlink messages to the GCS, for transmission through FrSky link
530  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
531  */
533 {
534  // get variances
535  float velVar, posVar, hgtVar, tasVar;
536  Vector3f magVar;
538  if (_ahrs.get_variances(velVar, posVar, hgtVar, magVar, tasVar, offset)) {
539  uint32_t now = AP_HAL::millis();
540  if ((now - check_ekf_status_timer) >= 10000) { // prevent repeating any ekf_status message unless 10 seconds have passed
541  // multiple errors can be reported at a time. Same setup as Mission Planner.
542  if (velVar >= 1) {
543  queue_message(MAV_SEVERITY_CRITICAL, "Error velocity variance");
545  }
546  if (posVar >= 1) {
547  queue_message(MAV_SEVERITY_CRITICAL, "Error pos horiz variance");
549  }
550  if (hgtVar >= 1) {
551  queue_message(MAV_SEVERITY_CRITICAL, "Error pos vert variance");
553  }
554  if (magVar.length() >= 1) {
555  queue_message(MAV_SEVERITY_CRITICAL, "Error compass variance");
557  }
558  if (tasVar >= 1) {
559  queue_message(MAV_SEVERITY_CRITICAL, "Error terrain alt variance");
561  }
562  }
563  }
564 }
565 
566 /*
567  * prepare parameter data
568  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
569  */
571 {
572  uint32_t param = 0;
573 
574  // cycle through paramIDs
575  if (_paramID >= 5) {
576  _paramID = 0;
577  }
578  _paramID++;
579  switch(_paramID) {
580  case 1:
581  param = _params.mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
582  break;
583  case 2: // was used to send the battery failsafe voltage
584  case 3: // was used to send the battery failsafe capacity in mAh
585  break;
586  case 4:
587  param = (uint32_t)roundf(_battery.pack_capacity_mah(0)); // battery pack capacity in mAh
588  break;
589  case 5:
590  param = (uint32_t)roundf(_battery.pack_capacity_mah(1)); // battery pack capacity in mAh
591  break;
592  }
593  //Reserve first 8 bits for param ID, use other 24 bits to store parameter value
594  param = (_paramID << PARAM_ID_OFFSET) | (param & PARAM_VALUE_LIMIT);
595 
596  return param;
597 }
598 
599 /*
600  * prepare gps latitude/longitude data
601  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
602  */
604 {
605  uint32_t latlng;
606  const Location &loc = AP::gps().location(0); // use the first gps instance (same as in send_mavlink_gps_raw)
607 
608  // alternate between latitude and longitude
609  if ((*send_latitude) == true) {
610  if (loc.lat < 0) {
611  latlng = ((labs(loc.lat)/100)*6) | 0x40000000;
612  } else {
613  latlng = ((labs(loc.lat)/100)*6);
614  }
615  (*send_latitude) = false;
616  } else {
617  if (loc.lng < 0) {
618  latlng = ((labs(loc.lng)/100)*6) | 0xC0000000;
619  } else {
620  latlng = ((labs(loc.lng)/100)*6) | 0x80000000;
621  }
622  (*send_latitude) = true;
623  }
624  return latlng;
625 }
626 
627 /*
628  * prepare gps status data
629  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
630  */
632 {
633  const AP_GPS &gps = AP::gps();
634 
635  uint32_t gps_status;
636 
637  // number of GPS satellites visible (limit to 15 (0xF) since the value is stored on 4 bits)
638  gps_status = (gps.num_sats() < GPS_SATS_LIMIT) ? gps.num_sats() : GPS_SATS_LIMIT;
639  // 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)
640  gps_status |= ((gps.status() < GPS_STATUS_LIMIT) ? gps.status() : GPS_STATUS_LIMIT)<<GPS_STATUS_OFFSET;
641  // GPS horizontal dilution of precision in dm
642  gps_status |= prep_number(roundf(gps.get_hdop() * 0.1f),2,1)<<GPS_HDOP_OFFSET;
643  // 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)
644  gps_status |= ((gps.status() > GPS_STATUS_LIMIT) ? gps.status()-GPS_STATUS_LIMIT : 0)<<GPS_ADVSTATUS_OFFSET;
645  // Altitude MSL in dm
646  const Location &loc = gps.location();
647  gps_status |= prep_number(roundf(loc.alt * 0.1f),2,2)<<GPS_ALTMSL_OFFSET;
648  return gps_status;
649 }
650 
651 /*
652  * prepare battery data
653  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
654  */
655 uint32_t AP_Frsky_Telem::calc_batt(uint8_t instance)
656 {
657  uint32_t batt;
658 
659  // battery voltage in decivolts, can have up to a 12S battery (4.25Vx12S = 51.0V)
660  batt = (((uint16_t)roundf(_battery.voltage(instance) * 10.0f)) & BATT_VOLTAGE_LIMIT);
661  // battery current draw in deciamps
662  batt |= prep_number(roundf(_battery.current_amps(instance) * 10.0f), 2, 1)<<BATT_CURRENT_OFFSET;
663  // battery current drawn since power on in mAh (limit to 32767 (0x7FFF) since value is stored on 15 bits)
665  return batt;
666 }
667 
668 /*
669  * prepare various autopilot status data
670  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
671  */
673 {
674  uint32_t ap_status;
675 
676  // control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits)
677  ap_status = (uint8_t)((_ap.control_mode+1) & AP_CONTROL_MODE_LIMIT);
678  // simple/super simple modes flags
679  ap_status |= (uint8_t)((*_ap.valuep) & AP_SSIMPLE_FLAGS)<<AP_SSIMPLE_OFFSET;
680  // is_flying flag
681  ap_status |= (uint8_t)(((*_ap.valuep) & AP_LANDCOMPLETE_FLAG) ^ AP_LANDCOMPLETE_FLAG);
682  // armed flag
683  ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;
684  // battery failsafe flag
685  ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery)<<AP_BATT_FS_OFFSET;
686  // bad ekf flag
687  ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<<AP_EKF_FS_OFFSET;
688  return ap_status;
689 }
690 
691 /*
692  * prepare home position related data
693  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
694  */
696 {
697  uint32_t home = 0;
698  Location loc;
699  float _relative_home_altitude = 0;
700  if (_ahrs.get_position(loc)) {
701  // check home_loc is valid
702  const Location &home_loc = _ahrs.get_home();
703  if (home_loc.lat != 0 || home_loc.lng != 0) {
704  // distance between vehicle and home_loc in meters
705  home = prep_number(roundf(get_distance(home_loc, loc)), 3, 2);
706  // 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)
707  home |= (((uint8_t)roundf(get_bearing_cd(loc,home_loc) * 0.00333f)) & HOME_BEARING_LIMIT)<<HOME_BEARING_OFFSET;
708  }
709  // altitude between vehicle and home_loc
710  _relative_home_altitude = loc.alt;
711  if (!loc.flags.relative_alt) {
712  // loc.alt has home altitude added, remove it
713  _relative_home_altitude -= _ahrs.get_home().alt;
714  }
715  }
716  // altitude above home in decimeters
717  home |= prep_number(roundf(_relative_home_altitude * 0.1f), 3, 2)<<HOME_ALT_OFFSET;
718  return home;
719 }
720 
721 /*
722  * prepare velocity and yaw data
723  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
724  */
726 {
727  uint32_t velandyaw;
728  Vector3f velNED {};
729 
730  // if we can't get velocity then we use zero for vertical velocity
731  _ahrs.get_velocity_NED(velNED);
732  // vertical velocity in dm/s
733  velandyaw = prep_number(roundf(-velNED.z * 10), 2, 1);
734  // horizontal velocity in dm/s (use airspeed if available and enabled - even if not used - otherwise use groundspeed)
735  const AP_Airspeed *aspeed = _ahrs.get_airspeed();
736  if (aspeed && aspeed->enabled()) {
737  velandyaw |= prep_number(roundf(aspeed->get_airspeed() * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;
738  } else { // otherwise send groundspeed estimate from ahrs
739  velandyaw |= prep_number(roundf(_ahrs.groundspeed() * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;
740  }
741  // 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)
742  velandyaw |= ((uint16_t)roundf(_ahrs.yaw_sensor * 0.05f) & VELANDYAW_YAW_LIMIT)<<VELANDYAW_YAW_OFFSET;
743  return velandyaw;
744 }
745 
746 /*
747  * prepare attitude (roll, pitch) and range data
748  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
749  */
751 {
752  uint32_t attiandrng;
753 
754  // 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)
755  attiandrng = ((uint16_t)roundf((_ahrs.roll_sensor + 18000) * 0.05f) & ATTIANDRNG_ROLL_LIMIT);
756  // 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)
757  attiandrng |= ((uint16_t)roundf((_ahrs.pitch_sensor + 9000) * 0.05f) & ATTIANDRNG_PITCH_LIMIT)<<ATTIANDRNG_PITCH_OFFSET;
758  // rangefinder measurement in cm
760  return attiandrng;
761 }
762 
763 /*
764  * prepare value for transmission through FrSky link
765  * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
766  */
767 uint16_t AP_Frsky_Telem::prep_number(int32_t number, uint8_t digits, uint8_t power)
768 {
769  uint16_t res = 0;
770  uint32_t abs_number = abs(number);
771 
772  if ((digits == 2) && (power == 1)) { // number encoded on 8 bits: 7 bits for digits + 1 for 10^power
773  if (abs_number < 100) {
774  res = abs_number<<1;
775  } else if (abs_number < 1270) {
776  res = ((uint8_t)roundf(abs_number * 0.1f)<<1)|0x1;
777  } else { // transmit max possible value (0x7F x 10^1 = 1270)
778  res = 0xFF;
779  }
780  if (number < 0) { // if number is negative, add sign bit in front
781  res |= 0x1<<8;
782  }
783  } else if ((digits == 2) && (power == 2)) { // number encoded on 9 bits: 7 bits for digits + 2 for 10^power
784  if (abs_number < 100) {
785  res = abs_number<<2;
786  } else if (abs_number < 1000) {
787  res = ((uint8_t)roundf(abs_number * 0.1f)<<2)|0x1;
788  } else if (abs_number < 10000) {
789  res = ((uint8_t)roundf(abs_number * 0.01f)<<2)|0x2;
790  } else if (abs_number < 127000) {
791  res = ((uint8_t)roundf(abs_number * 0.001f)<<2)|0x3;
792  } else { // transmit max possible value (0x7F x 10^3 = 127000)
793  res = 0x1FF;
794  }
795  if (number < 0) { // if number is negative, add sign bit in front
796  res |= 0x1<<9;
797  }
798  } else if ((digits == 3) && (power == 1)) { // number encoded on 11 bits: 10 bits for digits + 1 for 10^power
799  if (abs_number < 1000) {
800  res = abs_number<<1;
801  } else if (abs_number < 10240) {
802  res = ((uint16_t)roundf(abs_number * 0.1f)<<1)|0x1;
803  } else { // transmit max possible value (0x3FF x 10^1 = 10240)
804  res = 0x7FF;
805  }
806  if (number < 0) { // if number is negative, add sign bit in front
807  res |= 0x1<<11;
808  }
809  } else if ((digits == 3) && (power == 2)) { // number encoded on 12 bits: 10 bits for digits + 2 for 10^power
810  if (abs_number < 1000) {
811  res = abs_number<<2;
812  } else if (abs_number < 10000) {
813  res = ((uint16_t)roundf(abs_number * 0.1f)<<2)|0x1;
814  } else if (abs_number < 100000) {
815  res = ((uint16_t)roundf(abs_number * 0.01f)<<2)|0x2;
816  } else if (abs_number < 1024000) {
817  res = ((uint16_t)roundf(abs_number * 0.001f)<<2)|0x3;
818  } else { // transmit max possible value (0x3FF x 10^3 = 127000)
819  res = 0xFFF;
820  }
821  if (number < 0) { // if number is negative, add sign bit in front
822  res |= 0x1<<12;
823  }
824  }
825  return res;
826 }
827 
828 /*
829  * prepare altitude between vehicle and home location data
830  * for FrSky D and SPort protocols
831  */
833 {
834  Location loc;
835  float current_height = 0; // in centimeters above home
836  if (_ahrs.get_position(loc)) {
837  current_height = loc.alt*0.01f;
838  if (!loc.flags.relative_alt) {
839  // loc.alt has home altitude added, remove it
840  current_height -= _ahrs.get_home().alt*0.01f;
841  }
842  }
843 
844  _gps.alt_nav_meters = (int16_t)current_height;
845  _gps.alt_nav_cm = (current_height - _gps.alt_nav_meters) * 100;
846 }
847 
848 /*
849  * format the decimal latitude/longitude to the required degrees/minutes
850  * for FrSky D and SPort protocols
851  */
853 {
854  uint8_t dm_deg = (uint8_t) dec;
855  return (dm_deg * 100.0f) + (dec - dm_deg) * 60;
856 }
857 
858 /*
859  * prepare gps data
860  * for FrSky D and SPort protocols
861  */
863 {
864  float lat;
865  float lon;
866  float alt;
867  float speed;
868 
869  if (AP::gps().status() >= 3) {
870  const Location &loc = AP::gps().location(); //get gps instance 0
871  lat = format_gps(fabsf(loc.lat/10000000.0f));
872  _gps.latdddmm = lat;
873  _gps.latmmmm = (lat - _gps.latdddmm) * 10000;
874  _gps.lat_ns = (loc.lat < 0) ? 'S' : 'N';
875 
876  lon = format_gps(fabsf(loc.lng/10000000.0f));
877  _gps.londddmm = lon;
878  _gps.lonmmmm = (lon - _gps.londddmm) * 10000;
879  _gps.lon_ew = (loc.lng < 0) ? 'W' : 'E';
880 
881  alt = loc.alt * 0.01f;
882  _gps.alt_gps_meters = (int16_t)alt;
883  _gps.alt_gps_cm = (alt - _gps.alt_gps_meters) * 100;
884 
885  speed = AP::gps().ground_speed();
886  _gps.speed_in_meter = speed;
887  _gps.speed_in_centimeter = (speed - _gps.speed_in_meter) * 100;
888  } else {
889  _gps.latdddmm = 0;
890  _gps.latmmmm = 0;
891  _gps.lat_ns = 0;
892  _gps.londddmm = 0;
893  _gps.lonmmmm = 0;
894  _gps.alt_gps_meters = 0;
895  _gps.alt_gps_cm = 0;
896  _gps.speed_in_meter = 0;
897  _gps.speed_in_centimeter = 0;
898  }
899 }
Definition: AP_GPS.h:48
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
uint32_t calc_batt(uint8_t instance)
bool enabled(uint8_t i) const
Definition: AP_Airspeed.h:85
uint32_t check_sensor_status_timer
#define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX
#define SENSOR_ID_SP2UR
#define GPS_STATUS_LIMIT
#define DATA_ID_FUEL
AP_HAL::UARTDriver * _port
#define HOME_ALT_OFFSET
bool remove(uint16_t n)
Definition: RingBuffer.h:294
#define DATA_ID_BARO_ALT_AP
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
bool push_force(const T &object)
Definition: RingBuffer.h:284
virtual void begin(uint32_t baud)=0
#define DATA_ID_GPS_ALT_AP
virtual bool get_position(struct Location &loc) const =0
virtual uint8_t capacity_remaining_pct(uint8_t instance) const
capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
Interface definition for the various Ground Control System.
#define SENSOR_ID_FAS
#define AP_INITIALIZED_FLAG
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
#define DATA_ID_TEMP1
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
struct AP_Frsky_Telem::@26 _msg_chunk
#define BATT_VOLTAGE_LIMIT
uint32_t calc_velandyaw(void)
#define AP_SSIMPLE_FLAGS
#define VELANDYAW_YAW_OFFSET
uint32_t calc_attiandrng(void)
virtual uint32_t txspace()=0
#define AP_SERIALMANAGER_FRSKY_D_BAUD
#define GPS_HDOP_OFFSET
uint32_t calc_ap_status(void)
GCS & gcs()
#define AP_SERIALMANAGER_FRSKY_SPORT_BAUD
#define HOME_BEARING_LIMIT
uint32_t check_ekf_status_timer
void send_uint32(uint16_t id, uint32_t data)
#define DATA_ID_GPS_LONG_AP
#define DATA_ID_GPS_COURS_BP
AP_Frsky_Telem(AP_AHRS &ahrs, const AP_BattMonitor &battery, const RangeFinder &rng)
ptrdiff_t offset
Definition: AP_Param.h:149
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
void register_frsky_telemetry_callback(AP_Frsky_Telem *frsky_telemetry)
Definition: GCS.h:626
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
void send_byte(uint8_t value)
int32_t roll_sensor
Definition: AP_AHRS.h:229
#define DATA_ID_GPS_ALT_BP
uint32_t calc_gps_latlng(bool *send_latitude)
const AP_BattMonitor & _battery
const AP_Airspeed * get_airspeed(void) const
Definition: AP_AHRS.h:174
void send_uint16(uint16_t id, uint16_t data)
struct AP_Frsky_Telem::@24 _SPort
AP_SerialManager::SerialProtocol _protocol
const RangeFinder & _rng
#define GPS_STATUS_OFFSET
#define DATA_ID_GPS_LAT_NS
uint32_t calc_gps_status(void)
#define ATTIANDRNG_ROLL_LIMIT
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
int32_t pitch_sensor
Definition: AP_AHRS.h:230
#define f(i)
virtual size_t write(uint8_t)=0
void queue_message(MAV_SEVERITY severity, const char *text)
uint32_t millis()
Definition: system.cpp:157
bool get_next_msg_chunk(void)
#define PARAM_ID_OFFSET
uint16_t distance_cm_orient(enum Rotation orientation) const
#define DATA_ID_VFAS
uint32_t calc_param(void)
uint16_t prep_number(int32_t number, uint8_t digits, uint8_t power)
struct AP_Frsky_Telem::@20 _params
virtual void set_flow_control(enum flow_control flow_control_setting)
Definition: UARTDriver.h:50
#define DATA_ID_GPS_LONG_BP
#define START_STOP_D
#define DATA_ID_GPS_LONG_EW
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
uint16_t get_hdop(uint8_t instance) const
Definition: AP_GPS.h:284
uint8_t byte
Definition: compat.h:8
uint32_t calc_home(void)
#define BYTESTUFF_D
virtual int16_t read()=0
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
#define PARAM_VALUE_LIMIT
#define SENSOR_ID_GPS
#define VELANDYAW_XYVEL_OFFSET
struct AP_Frsky_Telem::@22 _gps
void send_SPort_Passthrough(void)
#define ATTIANDRNG_PITCH_LIMIT
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
AP_BattMonitor & battery()
#define ATTIANDRNG_RNGFND_OFFSET
float length(void) const
Definition: vector3.cpp:288
#define BATT_TOTALMAH_LIMIT
#define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX
#define GPS_ALTMSL_OFFSET
bool empty(void) const
Definition: RingBuffer.h:236
void send_SPort(void)
virtual uint32_t available()=0
struct AP_Frsky_Telem::@25 _D
#define AP_BATT_FS_OFFSET
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
#define DATA_ID_CURRENT
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
virtual void register_io_process(AP_HAL::MemberProc)=0
#define DATA_ID_GPS_LAT_AP
#define AP_ARMED_OFFSET
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
#define AP_SSIMPLE_OFFSET
struct AP_Frsky_Telem::@21 _ap
int32_t pack_capacity_mah(uint8_t instance) const
pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full ...
#define AP_EKF_FS_OFFSET
#define AP_CONTROL_MODE_LIMIT
#define GPS_SATS_LIMIT
#define SENSOR_ID_VARIO
void calc_crc(uint8_t byte)
float groundspeed(void)
Definition: AP_AHRS.h:359
#define BYTESTUFF_SPORT
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
static ObjectArray< mavlink_statustext_t > _statustext_queue
#define DIY_FIRST_ID
#define DATA_ID_BARO_ALT_BP
#define BATT_CURRENT_OFFSET
#define FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY
virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
Definition: AP_AHRS.h:524
static AP_GPS gps
Definition: AHRS_Test.cpp:22
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void send_crc(void)
void check_ekf_status(void)
#define GPS_ADVSTATUS_OFFSET
#define BATT_TOTALMAH_OFFSET
uint8_t num_instances(void) const
float voltage(uint8_t instance) const
voltage - returns battery voltage in millivolts
#define HOME_BEARING_OFFSET
float consumed_mah(uint8_t instance) const
consumed_mah - returns total current drawn since start-up in milliampere.hours
void calc_gps_position(void)
int32_t yaw_sensor
Definition: AP_AHRS.h:231
#define VELANDYAW_YAW_LIMIT
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep=nullptr)
#define DATA_ID_TEMP2
struct AP_Frsky_Telem::@23 _passthrough
#define GPS_LONG_LATI_FIRST_ID
#define DATA_ID_GPS_SPEED_AP
float format_gps(float dec)
#define AP_LANDCOMPLETE_FLAG
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
#define DATA_ID_GPS_SPEED_BP
#define ATTIANDRNG_PITCH_OFFSET
#define START_STOP_SPORT
void check_sensor_status_flags(void)
void calc_nav_alt(void)
#define DATA_ID_GPS_LAT_BP
#define SENSOR_ID_28