APM:Libraries
AP_Frsky_Telem.h
Go to the documentation of this file.
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 
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 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14 */
15 #pragma once
16 
17 #include <AP_HAL/AP_HAL.h>
18 #include <AP_AHRS/AP_AHRS.h>
20 #include <AP_Notify/AP_Notify.h>
24 
25 #define FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY 5 // size of the message buffer queue (max number of messages waiting to be sent)
26 
27 /*
28 for FrSky D protocol (D-receivers)
29 */
30 // FrSky sensor hub data IDs
31 #define DATA_ID_GPS_ALT_BP 0x01
32 #define DATA_ID_TEMP1 0x02
33 #define DATA_ID_FUEL 0x04
34 #define DATA_ID_TEMP2 0x05
35 #define DATA_ID_GPS_ALT_AP 0x09
36 #define DATA_ID_BARO_ALT_BP 0x10
37 #define DATA_ID_GPS_SPEED_BP 0x11
38 #define DATA_ID_GPS_LONG_BP 0x12
39 #define DATA_ID_GPS_LAT_BP 0x13
40 #define DATA_ID_GPS_COURS_BP 0x14
41 #define DATA_ID_GPS_SPEED_AP 0x19
42 #define DATA_ID_GPS_LONG_AP 0x1A
43 #define DATA_ID_GPS_LAT_AP 0x1B
44 #define DATA_ID_BARO_ALT_AP 0x21
45 #define DATA_ID_GPS_LONG_EW 0x22
46 #define DATA_ID_GPS_LAT_NS 0x23
47 #define DATA_ID_CURRENT 0x28
48 #define DATA_ID_VFAS 0x39
49 
50 #define START_STOP_D 0x5E
51 #define BYTESTUFF_D 0x5D
52 
53 /*
54 for FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
55 */
56 // FrSky Sensor IDs
57 #define SENSOR_ID_VARIO 0x00 // Sensor ID 0
58 #define SENSOR_ID_FAS 0x22 // Sensor ID 2
59 #define SENSOR_ID_GPS 0x83 // Sensor ID 3
60 #define SENSOR_ID_SP2UR 0xC6 // Sensor ID 6
61 #define SENSOR_ID_28 0x1B // Sensor ID 28
62 
63 // FrSky data IDs
64 #define GPS_LONG_LATI_FIRST_ID 0x0800
65 #define DIY_FIRST_ID 0x5000
66 
67 #define START_STOP_SPORT 0x7E
68 #define BYTESTUFF_SPORT 0x7D
69 
70 /*
71 for FrSky SPort Passthrough
72 */
73 // data bits preparation
74 // for parameter data
75 #define PARAM_ID_OFFSET 24
76 #define PARAM_VALUE_LIMIT 0xFFFFFF
77 // for gps status data
78 #define GPS_SATS_LIMIT 0xF
79 #define GPS_STATUS_LIMIT 0x3
80 #define GPS_STATUS_OFFSET 4
81 #define GPS_HDOP_OFFSET 6
82 #define GPS_ADVSTATUS_OFFSET 14
83 #define GPS_ALTMSL_OFFSET 22
84 // for battery data
85 #define BATT_VOLTAGE_LIMIT 0x1FF
86 #define BATT_CURRENT_OFFSET 9
87 #define BATT_TOTALMAH_LIMIT 0x7FFF
88 #define BATT_TOTALMAH_OFFSET 17
89 // for autopilot status data
90 #define AP_CONTROL_MODE_LIMIT 0x1F
91 #define AP_SSIMPLE_FLAGS 0x6
92 #define AP_SSIMPLE_OFFSET 4
93 #define AP_LANDCOMPLETE_FLAG 0x80
94 #define AP_INITIALIZED_FLAG 0x2000
95 #define AP_ARMED_OFFSET 8
96 #define AP_BATT_FS_OFFSET 9
97 #define AP_EKF_FS_OFFSET 10
98 // for home position related data
99 #define HOME_ALT_OFFSET 12
100 #define HOME_BEARING_LIMIT 0x7F
101 #define HOME_BEARING_OFFSET 25
102 // for velocity and yaw data
103 #define VELANDYAW_XYVEL_OFFSET 9
104 #define VELANDYAW_YAW_LIMIT 0x7FF
105 #define VELANDYAW_YAW_OFFSET 17
106 // for attitude (roll, pitch) and range data
107 #define ATTIANDRNG_ROLL_LIMIT 0x7FF
108 #define ATTIANDRNG_PITCH_LIMIT 0x3FF
109 #define ATTIANDRNG_PITCH_OFFSET 11
110 #define ATTIANDRNG_RNGFND_OFFSET 21
111 
112 
113 
115 public:
117 
118  /* Do not allow copies */
119  AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
120  AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
121 
122  // init - perform required initialisation
123  void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep = nullptr);
124 
125  // add statustext message to FrSky lib message queue
126  void queue_message(MAV_SEVERITY severity, const char *text);
127 
128  // update flight control mode. The control mode is vehicle type specific
129  void update_control_mode(uint8_t mode) { _ap.control_mode = mode; }
130 
131  // update whether we're flying (used for Plane)
132  // set land_complete flag to 0 if is_flying
133  // set land_complete flag to 1 if not flying
134  void set_is_flying(bool is_flying) { (is_flying) ? (_ap.value &= ~AP_LANDCOMPLETE_FLAG) : (_ap.value |= AP_LANDCOMPLETE_FLAG); }
135 
136  // update error mask of sensors and subsystems. The mask uses the
137  // MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
138  // indicates that the sensor or subsystem is present but not
139  // functioning correctly
140  void update_sensor_status_flags(uint32_t error_mask) { _ap.sensor_status_flags = error_mask; }
141 
143 
144 private:
148  AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver
149  AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
151  uint16_t _crc;
152 
153  struct
154  {
155  uint8_t mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
156  } _params;
157 
158  struct
159  {
160  uint8_t control_mode;
161  uint32_t value;
162  const uint32_t *valuep;
164  } _ap;
165 
168  uint8_t _paramID;
169 
170  struct
171  {
172  char lat_ns, lon_ew;
173  uint16_t latdddmm;
174  uint16_t latmmmm;
175  uint16_t londddmm;
176  uint16_t lonmmmm;
177  uint16_t alt_gps_meters;
178  uint16_t alt_gps_cm;
179  uint16_t alt_nav_meters;
180  uint16_t alt_nav_cm;
181  int16_t speed_in_meter;
183  } _gps;
184 
185  struct
186  {
187  uint8_t new_byte;
190  uint32_t params_timer;
191  uint32_t ap_status_timer;
192  uint32_t batt_timer;
193  uint32_t batt_timer2;
195  uint32_t home_timer;
196  uint32_t velandyaw_timer;
198  } _passthrough;
199 
200  struct
201  {
203  uint8_t fas_call;
204  uint8_t gps_call;
205  uint8_t vario_call;
206  uint8_t various_call;
207  } _SPort;
208 
209  struct
210  {
213  } _D;
214 
215  struct
216  {
217  uint32_t chunk; // a "chunk" (four characters/bytes) at a time of the queued message to be sent
218  uint8_t repeats; // send each message "chunk" 3 times to make sure the entire messsage gets through without getting cut
219  uint8_t char_index; // index of which character to get in the message
220  } _msg_chunk;
221 
222  // main transmission function when protocol is FrSky SPort Passthrough (OpenTX)
223  void send_SPort_Passthrough(void);
224  // main transmission function when protocol is FrSky SPort
225  void send_SPort(void);
226  // main transmission function when protocol is FrSky D
227  void send_D(void);
228  // tick - main call to send updates to transmitter (called by scheduler at 1kHz)
229  void tick(void);
230 
231  // methods related to the nuts-and-bolts of sending data
232  void calc_crc(uint8_t byte);
233  void send_crc(void);
234  void send_byte(uint8_t value);
235  void send_uint32(uint16_t id, uint32_t data);
236  void send_uint16(uint16_t id, uint16_t data);
237 
238  // methods to convert flight controller data to FrSky SPort Passthrough (OpenTX) format
239  bool get_next_msg_chunk(void);
240  void check_sensor_status_flags(void);
241  void check_ekf_status(void);
242  uint32_t calc_param(void);
243  uint32_t calc_gps_latlng(bool *send_latitude);
244  uint32_t calc_gps_status(void);
245  uint32_t calc_batt(uint8_t instance);
246  uint32_t calc_ap_status(void);
247  uint32_t calc_home(void);
248  uint32_t calc_velandyaw(void);
249  uint32_t calc_attiandrng(void);
250  uint16_t prep_number(int32_t number, uint8_t digits, uint8_t power);
251 
252  // methods to convert flight controller data to FrSky D or SPort format
253  void calc_nav_alt(void);
254  float format_gps(float dec);
255  void calc_gps_position(void);
256 };
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
uint32_t calc_batt(uint8_t instance)
uint16_t alt_nav_meters
uint32_t check_sensor_status_timer
AP_HAL::UARTDriver * _port
uint32_t gps_status_timer
uint32_t last_1000ms_frame
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
uint32_t batt_timer2
struct AP_Frsky_Telem::@26 _msg_chunk
uint32_t calc_velandyaw(void)
uint32_t calc_attiandrng(void)
uint32_t calc_ap_status(void)
uint32_t ap_status_timer
uint32_t check_ekf_status_timer
void send_uint32(uint16_t id, uint32_t data)
AP_Frsky_Telem(AP_AHRS &ahrs, const AP_BattMonitor &battery, const RangeFinder &rng)
void send_byte(uint8_t value)
uint32_t calc_gps_latlng(bool *send_latitude)
const AP_BattMonitor & _battery
uint8_t various_call
void send_uint16(uint16_t id, uint16_t data)
uint32_t home_timer
struct AP_Frsky_Telem::@24 _SPort
void update_sensor_status_flags(uint32_t error_mask)
AP_SerialManager::SerialProtocol _protocol
const RangeFinder & _rng
uint32_t params_timer
uint32_t calc_gps_status(void)
uint16_t alt_nav_cm
uint32_t velandyaw_timer
void queue_message(MAV_SEVERITY severity, const char *text)
uint32_t batt_timer
bool get_next_msg_chunk(void)
uint32_t calc_param(void)
uint16_t prep_number(int32_t number, uint8_t digits, uint8_t power)
void update_control_mode(uint8_t mode)
struct AP_Frsky_Telem::@20 _params
int16_t speed_in_meter
uint8_t byte
Definition: compat.h:8
uint32_t calc_home(void)
struct AP_Frsky_Telem::@22 _gps
void send_SPort_Passthrough(void)
AP_BattMonitor & battery()
uint32_t gps_latlng_timer
uint8_t control_mode
void send_SPort(void)
AP_Frsky_Telem & operator=(const AP_Frsky_Telem &)=delete
struct AP_Frsky_Telem::@25 _D
uint16_t alt_gps_cm
struct AP_Frsky_Telem::@21 _ap
void set_is_flying(bool is_flying)
uint16_t alt_gps_meters
uint32_t last_200ms_frame
void calc_crc(uint8_t byte)
static ObjectArray< mavlink_statustext_t > _statustext_queue
Catch-all header that defines all supported RangeFinder classes.
void send_crc(void)
void check_ekf_status(void)
void calc_gps_position(void)
uint16_t speed_in_centimeter
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep=nullptr)
const uint32_t * valuep
struct AP_Frsky_Telem::@23 _passthrough
uint32_t sensor_status_flags
float format_gps(float dec)
#define AP_LANDCOMPLETE_FLAG
void check_sensor_status_flags(void)
void calc_nav_alt(void)