25 #define FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY 5 // size of the message buffer queue (max number of messages waiting to be sent) 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 50 #define START_STOP_D 0x5E 51 #define BYTESTUFF_D 0x5D 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 64 #define GPS_LONG_LATI_FIRST_ID 0x0800 65 #define DIY_FIRST_ID 0x5000 67 #define START_STOP_SPORT 0x7E 68 #define BYTESTUFF_SPORT 0x7D 75 #define PARAM_ID_OFFSET 24 76 #define PARAM_VALUE_LIMIT 0xFFFFFF 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 85 #define BATT_VOLTAGE_LIMIT 0x1FF 86 #define BATT_CURRENT_OFFSET 9 87 #define BATT_TOTALMAH_LIMIT 0x7FFF 88 #define BATT_TOTALMAH_OFFSET 17 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 99 #define HOME_ALT_OFFSET 12 100 #define HOME_BEARING_LIMIT 0x7F 101 #define HOME_BEARING_OFFSET 25 103 #define VELANDYAW_XYVEL_OFFSET 9 104 #define VELANDYAW_YAW_LIMIT 0x7FF 105 #define VELANDYAW_YAW_OFFSET 17 107 #define ATTIANDRNG_ROLL_LIMIT 0x7FF 108 #define ATTIANDRNG_PITCH_LIMIT 0x3FF 109 #define ATTIANDRNG_PITCH_OFFSET 11 110 #define ATTIANDRNG_RNGFND_OFFSET 21 250 uint16_t
prep_number(int32_t number, uint8_t digits, uint8_t power);
static AP_SerialManager serial_manager
uint32_t calc_batt(uint8_t instance)
uint32_t check_sensor_status_timer
AP_HAL::UARTDriver * _port
uint32_t gps_status_timer
uint32_t last_1000ms_frame
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 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
void send_uint16(uint16_t id, uint16_t data)
struct AP_Frsky_Telem::@24 _SPort
void update_sensor_status_flags(uint32_t error_mask)
AP_SerialManager::SerialProtocol _protocol
uint32_t calc_gps_status(void)
void queue_message(MAV_SEVERITY severity, const char *text)
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
struct AP_Frsky_Telem::@22 _gps
void send_SPort_Passthrough(void)
AP_BattMonitor & battery()
uint32_t gps_latlng_timer
AP_Frsky_Telem & operator=(const AP_Frsky_Telem &)=delete
struct AP_Frsky_Telem::@25 _D
struct AP_Frsky_Telem::@21 _ap
void set_is_flying(bool is_flying)
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 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)
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)