PX4 Firmware
PX4 Autopilot Software http://px4.io
frsky_data.cpp File Reference
#include "frsky_data.h"
#include "common.h"
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <stdbool.h>
#include <lib/ecl/geo/geo.h>
#include <math.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_air_data.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_status.h>
#include <drivers/drv_hrt.h>
Include dependency graph for frsky_data.cpp:

Go to the source code of this file.

Classes

struct  frsky_subscription_data_s
 

Macros

#define frac(f)   (f - (int)f)
 

Functions

bool frsky_init ()
 Initializes the uORB subscriptions. More...
 
void frsky_deinit ()
 
static void frsky_send_startstop (int uart)
 Sends a 0x5E start/stop byte. More...
 
static void frsky_send_byte (int uart, uint8_t value)
 Sends one byte, performing byte-stuffing if necessary. More...
 
static void frsky_send_data (int uart, uint8_t id, int16_t data)
 Sends one data id/value pair. More...
 
void frsky_update_topics ()
 
void frsky_send_frame1 (int uart)
 Sends frame 1 (every 200ms): acceleration values, barometer altitude, temperature, battery voltage & current. More...
 
static float frsky_format_gps (float dec)
 Formats the decimal latitude/longitude to the required degrees/minutes. More...
 
void frsky_send_frame2 (int uart)
 Sends frame 2 (every 1000ms): GPS course, latitude, longitude, ground speed, GPS altitude, remaining battery level. More...
 
void frsky_send_frame3 (int uart)
 Sends frame 3 (every 5000ms): GPS date & time. More...
 
bool frsky_parse_host (uint8_t *sbuf, int nbytes, struct adc_linkquality *v)
 

Variables

static struct frsky_subscription_data_ssubscription_data = nullptr
 

Macro Definition Documentation

◆ frac

#define frac (   f)    (f - (int)f)

Definition at line 64 of file frsky_data.cpp.

Referenced by frsky_send_frame1(), and frsky_send_frame2().

Function Documentation

◆ frsky_deinit()

void frsky_deinit ( void  )

Definition at line 92 of file frsky_data.cpp.

References subscription_data.

Referenced by frsky_telemetry_thread_main().

Here is the caller graph for this function:

◆ frsky_format_gps()

static float frsky_format_gps ( float  dec)
static

Formats the decimal latitude/longitude to the required degrees/minutes.

Definition at line 189 of file frsky_data.cpp.

References f().

Referenced by frsky_send_frame2().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ frsky_init()

bool frsky_init ( void  )

Initializes the uORB subscriptions.

Definition at line 81 of file frsky_data.cpp.

Referenced by frsky_telemetry_thread_main().

Here is the caller graph for this function:

◆ frsky_parse_host()

bool frsky_parse_host ( uint8_t *  sbuf,
int  nbytes,
struct adc_linkquality v 
)

Definition at line 277 of file frsky_data.cpp.

References adc_linkquality::ad1, adc_linkquality::ad2, DATA, data, adc_linkquality::linkq, and state.

Referenced by frsky_telemetry_thread_main().

Here is the caller graph for this function:

◆ frsky_send_byte()

static void frsky_send_byte ( int  uart,
uint8_t  value 
)
static

Sends one byte, performing byte-stuffing if necessary.

Definition at line 112 of file frsky_data.cpp.

References write().

Referenced by frsky_send_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ frsky_send_data()

static void frsky_send_data ( int  uart,
uint8_t  id,
int16_t  data 
)
static

Sends one data id/value pair.

Definition at line 135 of file frsky_data.cpp.

References data, frsky_send_byte(), and frsky_send_startstop().

Referenced by frsky_send_frame1(), frsky_send_frame2(), and frsky_send_frame3().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ frsky_send_frame1()

void frsky_send_frame1 ( int  uart)

Sends frame 1 (every 200ms): acceleration values, barometer altitude, temperature, battery voltage & current.

Definition at line 161 of file frsky_data.cpp.

References sensor_combined_s::accelerometer_m_s2, vehicle_air_data_s::baro_alt_meter, frsky_subscription_data_s::battery_status_sub, battery_status_s::current_a, vehicle_gps_position_s::fix_type, frac, FRSKY_ID_ACCEL_X, FRSKY_ID_ACCEL_Y, FRSKY_ID_ACCEL_Z, FRSKY_ID_BARO_ALT_AP, FRSKY_ID_BARO_ALT_BP, FRSKY_ID_CURRENT, FRSKY_ID_TEMP1, FRSKY_ID_TEMP2, FRSKY_ID_VFAS, frsky_send_data(), frsky_send_startstop(), uORB::SubscriptionData< T >::get(), get_telemetry_flight_mode(), gps, vehicle_status_s::nav_state, vehicle_gps_position_s::satellites_used, frsky_subscription_data_s::sensor_combined_sub, frsky_subscription_data_s::vehicle_air_data_sub, frsky_subscription_data_s::vehicle_gps_position_sub, frsky_subscription_data_s::vehicle_status_sub, and battery_status_s::voltage_v.

Referenced by frsky_telemetry_thread_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ frsky_send_frame2()

◆ frsky_send_frame3()

void frsky_send_frame3 ( int  uart)

Sends frame 3 (every 5000ms): GPS date & time.

Definition at line 261 of file frsky_data.cpp.

References FRSKY_ID_GPS_DAY_MONTH, FRSKY_ID_GPS_HOUR_MIN, FRSKY_ID_GPS_SEC, FRSKY_ID_GPS_YEAR, frsky_send_data(), frsky_send_startstop(), uORB::SubscriptionData< T >::get(), vehicle_gps_position_s::time_utc_usec, and frsky_subscription_data_s::vehicle_gps_position_sub.

Referenced by frsky_telemetry_thread_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ frsky_send_startstop()

static void frsky_send_startstop ( int  uart)
static

Sends a 0x5E start/stop byte.

Definition at line 103 of file frsky_data.cpp.

References write().

Referenced by frsky_send_data(), frsky_send_frame1(), frsky_send_frame2(), and frsky_send_frame3().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ frsky_update_topics()

void frsky_update_topics ( void  )

Definition at line 147 of file frsky_data.cpp.

References frsky_subscription_data_s::battery_status_sub, frsky_subscription_data_s::sensor_combined_sub, uORB::SubscriptionData< T >::update(), frsky_subscription_data_s::vehicle_air_data_sub, frsky_subscription_data_s::vehicle_global_position_sub, frsky_subscription_data_s::vehicle_gps_position_sub, and frsky_subscription_data_s::vehicle_status_sub.

Referenced by frsky_telemetry_thread_main().

Here is the call graph for this function:
Here is the caller graph for this function:

Variable Documentation

◆ subscription_data

struct frsky_subscription_data_s* subscription_data = nullptr
static

Definition at line 76 of file frsky_data.cpp.

Referenced by frsky_deinit().