54 if (ap_valuep ==
nullptr) {
58 _ap.valuep = ap_valuep;
62 if (
_port !=
nullptr) {
90 uint8_t prev_byte = 0;
91 for (int16_t i = 0; i < numc; i++) {
182 for (int16_t i = 0; i < numc; i++) {
184 if (
_SPort.sport_status ==
false) {
186 _SPort.sport_status =
true;
191 switch (
_SPort.fas_call) {
205 switch (
_SPort.gps_call) {
244 switch (
_SPort.vario_call) {
256 switch (
_SPort.various_call) {
267 _SPort.sport_status =
false;
282 if (now -
_D.last_200ms_frame >= 200) {
283 _D.last_200ms_frame = now;
294 if (now -
_D.last_1000ms_frame >= 1000) {
295 _D.last_1000ms_frame = now;
395 uint8_t *bytes = (uint8_t*)&
id;
398 bytes = (uint8_t*)&data;
412 uint8_t *bytes = (uint8_t*)&
id;
414 bytes = (uint8_t*)&data;
430 uint8_t character = 0;
467 mavlink_statustext_t statustext{};
469 statustext.severity = severity;
470 strncpy(statustext.text, text,
sizeof(statustext.text));
488 if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_GPS) > 0) {
491 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_GYRO) > 0) {
494 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_ACCEL) > 0) {
497 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_MAG) > 0) {
500 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE) > 0) {
503 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_LASER_POSITION) > 0) {
506 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) > 0) {
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) {
515 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_AHRS) > 0) {
518 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_SENSOR_RC_RECEIVER) > 0) {
521 }
else if ((
_ap.sensor_status_flags & MAV_SYS_STATUS_LOGGING) > 0) {
535 float velVar, posVar, hgtVar, tasVar;
543 queue_message(MAV_SEVERITY_CRITICAL,
"Error velocity variance");
547 queue_message(MAV_SEVERITY_CRITICAL,
"Error pos horiz variance");
551 queue_message(MAV_SEVERITY_CRITICAL,
"Error pos vert variance");
554 if (magVar.
length() >= 1) {
555 queue_message(MAV_SEVERITY_CRITICAL,
"Error compass variance");
559 queue_message(MAV_SEVERITY_CRITICAL,
"Error terrain alt variance");
609 if ((*send_latitude) ==
true) {
611 latlng = ((labs(loc.
lat)/100)*6) | 0x40000000;
613 latlng = ((labs(loc.
lat)/100)*6);
615 (*send_latitude) =
false;
618 latlng = ((labs(loc.
lng)/100)*6) | 0xC0000000;
620 latlng = ((labs(loc.
lng)/100)*6) | 0x80000000;
622 (*send_latitude) =
true;
699 float _relative_home_altitude = 0;
703 if (home_loc.
lat != 0 || home_loc.
lng != 0) {
710 _relative_home_altitude = loc.
alt;
733 velandyaw =
prep_number(roundf(-velNED.z * 10), 2, 1);
736 if (aspeed && aspeed->
enabled()) {
770 uint32_t abs_number = abs(number);
772 if ((digits == 2) && (power == 1)) {
773 if (abs_number < 100) {
775 }
else if (abs_number < 1270) {
776 res = ((uint8_t)roundf(abs_number * 0.1
f)<<1)|0x1;
783 }
else if ((digits == 2) && (power == 2)) {
784 if (abs_number < 100) {
786 }
else if (abs_number < 1000) {
787 res = ((uint8_t)roundf(abs_number * 0.1
f)<<2)|0x1;
788 }
else if (abs_number < 10000) {
789 res = ((uint8_t)roundf(abs_number * 0.01
f)<<2)|0x2;
790 }
else if (abs_number < 127000) {
791 res = ((uint8_t)roundf(abs_number * 0.001
f)<<2)|0x3;
798 }
else if ((digits == 3) && (power == 1)) {
799 if (abs_number < 1000) {
801 }
else if (abs_number < 10240) {
802 res = ((uint16_t)roundf(abs_number * 0.1
f)<<1)|0x1;
809 }
else if ((digits == 3) && (power == 2)) {
810 if (abs_number < 1000) {
812 }
else if (abs_number < 10000) {
813 res = ((uint16_t)roundf(abs_number * 0.1
f)<<2)|0x1;
814 }
else if (abs_number < 100000) {
815 res = ((uint16_t)roundf(abs_number * 0.01
f)<<2)|0x2;
816 }
else if (abs_number < 1024000) {
817 res = ((uint16_t)roundf(abs_number * 0.001
f)<<2)|0x3;
835 float current_height = 0;
837 current_height = loc.
alt*0.01f;
844 _gps.alt_nav_meters = (int16_t)current_height;
845 _gps.alt_nav_cm = (current_height -
_gps.alt_nav_meters) * 100;
854 uint8_t dm_deg = (uint8_t) dec;
855 return (dm_deg * 100.0
f) + (dec - dm_deg) * 60;
873 _gps.latmmmm = (lat -
_gps.latdddmm) * 10000;
874 _gps.lat_ns = (loc.
lat < 0) ?
'S' :
'N';
878 _gps.lonmmmm = (lon -
_gps.londddmm) * 10000;
879 _gps.lon_ew = (loc.
lng < 0) ?
'W' :
'E';
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;
886 _gps.speed_in_meter = speed;
887 _gps.speed_in_centimeter = (speed -
_gps.speed_in_meter) * 100;
894 _gps.alt_gps_meters = 0;
896 _gps.speed_in_meter = 0;
897 _gps.speed_in_centimeter = 0;
virtual bool get_velocity_NED(Vector3f &vec) const
static AP_SerialManager serial_manager
uint32_t calc_batt(uint8_t instance)
bool enabled(uint8_t i) const
uint32_t check_sensor_status_timer
#define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX
AP_HAL::UARTDriver * _port
#define DATA_ID_BARO_ALT_AP
bool push_force(const T &object)
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 AP_INITIALIZED_FLAG
const struct Location & get_home(void) const
float get_airspeed(uint8_t i) const
float get_distance(const struct Location &loc1, const struct Location &loc2)
struct AP_Frsky_Telem::@26 _msg_chunk
#define BATT_VOLTAGE_LIMIT
uint32_t calc_velandyaw(void)
#define VELANDYAW_YAW_OFFSET
uint32_t calc_attiandrng(void)
virtual uint32_t txspace()=0
#define AP_SERIALMANAGER_FRSKY_D_BAUD
uint32_t calc_ap_status(void)
#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)
const Location & location(uint8_t instance) const
void register_frsky_telemetry_callback(AP_Frsky_Telem *frsky_telemetry)
int32_t lat
param 3 - Latitude * 10**7
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
void send_byte(uint8_t value)
#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
void send_uint16(uint16_t id, uint16_t data)
struct AP_Frsky_Telem::@24 _SPort
AP_SerialManager::SerialProtocol _protocol
#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
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
virtual size_t write(uint8_t)=0
void queue_message(MAV_SEVERITY severity, const char *text)
bool get_next_msg_chunk(void)
uint16_t distance_cm_orient(enum Rotation orientation) const
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)
#define DATA_ID_GPS_LONG_BP
#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
GPS_Status status(uint8_t instance) const
Query GPS status.
#define PARAM_VALUE_LIMIT
#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)
AP_BattMonitor & battery()
#define ATTIANDRNG_RNGFND_OFFSET
#define BATT_TOTALMAH_LIMIT
#define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX
#define GPS_ALTMSL_OFFSET
virtual uint32_t available()=0
struct AP_Frsky_Telem::@25 _D
#define AP_BATT_FS_OFFSET
int32_t lng
param 4 - Longitude * 10**7
uint8_t num_sats(uint8_t instance) const
virtual void register_io_process(AP_HAL::MemberProc)=0
#define DATA_ID_GPS_LAT_AP
static struct notify_flags_and_values_type flags
#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_CONTROL_MODE_LIMIT
void calc_crc(uint8_t byte)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
static ObjectArray< mavlink_statustext_t > _statustext_queue
#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
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)
#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)
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
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
#define DATA_ID_GPS_SPEED_BP
#define ATTIANDRNG_PITCH_OFFSET
void check_sensor_status_flags(void)
#define DATA_ID_GPS_LAT_BP