AP_Frsky_Telem.h 7.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_HAL/AP_HAL.h>
  15. #include <AP_Notify/AP_Notify.h>
  16. #include <AP_SerialManager/AP_SerialManager.h>
  17. #include <AP_HAL/utility/RingBuffer.h>
  18. #define FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY 5 // size of the message buffer queue (max number of messages waiting to be sent)
  19. /*
  20. for FrSky D protocol (D-receivers)
  21. */
  22. // FrSky sensor hub data IDs
  23. #define DATA_ID_GPS_ALT_BP 0x01
  24. #define DATA_ID_TEMP1 0x02
  25. #define DATA_ID_FUEL 0x04
  26. #define DATA_ID_TEMP2 0x05
  27. #define DATA_ID_GPS_ALT_AP 0x09
  28. #define DATA_ID_BARO_ALT_BP 0x10
  29. #define DATA_ID_GPS_SPEED_BP 0x11
  30. #define DATA_ID_GPS_LONG_BP 0x12
  31. #define DATA_ID_GPS_LAT_BP 0x13
  32. #define DATA_ID_GPS_COURS_BP 0x14
  33. #define DATA_ID_GPS_SPEED_AP 0x19
  34. #define DATA_ID_GPS_LONG_AP 0x1A
  35. #define DATA_ID_GPS_LAT_AP 0x1B
  36. #define DATA_ID_BARO_ALT_AP 0x21
  37. #define DATA_ID_GPS_LONG_EW 0x22
  38. #define DATA_ID_GPS_LAT_NS 0x23
  39. #define DATA_ID_CURRENT 0x28
  40. #define DATA_ID_VFAS 0x39
  41. #define START_STOP_D 0x5E
  42. #define BYTESTUFF_D 0x5D
  43. /*
  44. for FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
  45. */
  46. // FrSky Sensor IDs
  47. #define SENSOR_ID_VARIO 0x00 // Sensor ID 0
  48. #define SENSOR_ID_FAS 0x22 // Sensor ID 2
  49. #define SENSOR_ID_GPS 0x83 // Sensor ID 3
  50. #define SENSOR_ID_SP2UR 0xC6 // Sensor ID 6
  51. #define SENSOR_ID_28 0x1B // Sensor ID 28
  52. // FrSky data IDs
  53. #define GPS_LONG_LATI_FIRST_ID 0x0800
  54. #define DIY_FIRST_ID 0x5000
  55. #define START_STOP_SPORT 0x7E
  56. #define BYTESTUFF_SPORT 0x7D
  57. /*
  58. for FrSky SPort Passthrough
  59. */
  60. // data bits preparation
  61. // for parameter data
  62. #define PARAM_ID_OFFSET 24
  63. #define PARAM_VALUE_LIMIT 0xFFFFFF
  64. // for gps status data
  65. #define GPS_SATS_LIMIT 0xF
  66. #define GPS_STATUS_LIMIT 0x3
  67. #define GPS_STATUS_OFFSET 4
  68. #define GPS_HDOP_OFFSET 6
  69. #define GPS_ADVSTATUS_OFFSET 14
  70. #define GPS_ALTMSL_OFFSET 22
  71. // for battery data
  72. #define BATT_VOLTAGE_LIMIT 0x1FF
  73. #define BATT_CURRENT_OFFSET 9
  74. #define BATT_TOTALMAH_LIMIT 0x7FFF
  75. #define BATT_TOTALMAH_OFFSET 17
  76. // for autopilot status data
  77. #define AP_CONTROL_MODE_LIMIT 0x1F
  78. #define AP_SIMPLE_OFFSET 5
  79. #define AP_SSIMPLE_OFFSET 6
  80. #define AP_FLYING_OFFSET 7
  81. #define AP_ARMED_OFFSET 8
  82. #define AP_BATT_FS_OFFSET 9
  83. #define AP_EKF_FS_OFFSET 10
  84. #define AP_IMU_TEMP_MIN 19.0f
  85. #define AP_IMU_TEMP_MAX 82.0f
  86. #define AP_IMU_TEMP_OFFSET 26
  87. // for home position related data
  88. #define HOME_ALT_OFFSET 12
  89. #define HOME_BEARING_LIMIT 0x7F
  90. #define HOME_BEARING_OFFSET 25
  91. // for velocity and yaw data
  92. #define VELANDYAW_XYVEL_OFFSET 9
  93. #define VELANDYAW_YAW_LIMIT 0x7FF
  94. #define VELANDYAW_YAW_OFFSET 17
  95. // for attitude (roll, pitch) and range data
  96. #define ATTIANDRNG_ROLL_LIMIT 0x7FF
  97. #define ATTIANDRNG_PITCH_LIMIT 0x3FF
  98. #define ATTIANDRNG_PITCH_OFFSET 11
  99. #define ATTIANDRNG_RNGFND_OFFSET 21
  100. class AP_Frsky_Telem {
  101. public:
  102. AP_Frsky_Telem();
  103. /* Do not allow copies */
  104. AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
  105. AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
  106. // init - perform required initialisation
  107. bool init();
  108. // add statustext message to FrSky lib message queue
  109. void queue_message(MAV_SEVERITY severity, const char *text);
  110. // update error mask of sensors and subsystems. The mask uses the
  111. // MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
  112. // indicates that the sensor or subsystem is present but not
  113. // functioning correctly
  114. uint32_t sensor_status_flags() const;
  115. private:
  116. AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver
  117. AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
  118. uint16_t _crc;
  119. uint32_t check_sensor_status_timer;
  120. uint32_t check_ekf_status_timer;
  121. uint8_t _paramID;
  122. ObjectArray<mavlink_statustext_t> _statustext_queue;
  123. struct
  124. {
  125. char lat_ns, lon_ew;
  126. uint16_t latdddmm;
  127. uint16_t latmmmm;
  128. uint16_t londddmm;
  129. uint16_t lonmmmm;
  130. uint16_t alt_gps_meters;
  131. uint16_t alt_gps_cm;
  132. uint16_t alt_nav_meters;
  133. uint16_t alt_nav_cm;
  134. int16_t speed_in_meter;
  135. uint16_t speed_in_centimeter;
  136. } _gps;
  137. struct
  138. {
  139. uint8_t new_byte;
  140. bool send_attiandrng;
  141. bool send_latitude;
  142. bool send_chunk;
  143. uint32_t params_timer;
  144. uint32_t ap_status_timer;
  145. uint32_t batt_timer;
  146. uint32_t batt_timer2;
  147. uint32_t gps_status_timer;
  148. uint32_t home_timer;
  149. uint32_t velandyaw_timer;
  150. uint32_t gps_latlng_timer;
  151. } _passthrough;
  152. struct
  153. {
  154. bool sport_status;
  155. uint8_t fas_call;
  156. uint8_t gps_call;
  157. uint8_t vario_call;
  158. uint8_t various_call;
  159. } _SPort;
  160. struct
  161. {
  162. uint32_t last_200ms_frame;
  163. uint32_t last_1000ms_frame;
  164. } _D;
  165. struct
  166. {
  167. uint32_t chunk; // a "chunk" (four characters/bytes) at a time of the queued message to be sent
  168. uint8_t repeats; // send each message "chunk" 3 times to make sure the entire messsage gets through without getting cut
  169. uint8_t char_index; // index of which character to get in the message
  170. } _msg_chunk;
  171. // main transmission function when protocol is FrSky SPort Passthrough (OpenTX)
  172. void send_SPort_Passthrough(void);
  173. // main transmission function when protocol is FrSky SPort
  174. void send_SPort(void);
  175. // main transmission function when protocol is FrSky D
  176. void send_D(void);
  177. // tick - main call to send updates to transmitter (called by scheduler at 1kHz)
  178. void loop(void);
  179. // methods related to the nuts-and-bolts of sending data
  180. void calc_crc(uint8_t byte);
  181. void send_crc(void);
  182. void send_byte(uint8_t value);
  183. void send_uint32(uint16_t id, uint32_t data);
  184. void send_uint16(uint16_t id, uint16_t data);
  185. // methods to convert flight controller data to FrSky SPort Passthrough (OpenTX) format
  186. bool get_next_msg_chunk(void);
  187. void check_sensor_status_flags(void);
  188. void check_ekf_status(void);
  189. uint32_t calc_param(void);
  190. uint32_t calc_gps_latlng(bool *send_latitude);
  191. uint32_t calc_gps_status(void);
  192. uint32_t calc_batt(uint8_t instance);
  193. uint32_t calc_ap_status(void);
  194. uint32_t calc_home(void);
  195. uint32_t calc_velandyaw(void);
  196. uint32_t calc_attiandrng(void);
  197. uint16_t prep_number(int32_t number, uint8_t digits, uint8_t power);
  198. // methods to convert flight controller data to FrSky D or SPort format
  199. void calc_nav_alt(void);
  200. float format_gps(float dec);
  201. void calc_gps_position(void);
  202. };