AP_Frsky_Telem.cpp 40 KB

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