PX4 Firmware
PX4 Autopilot Software http://px4.io
sPort_data.cpp File Reference
#include "sPort_data.h"
#include "common.h"
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <math.h>
#include <lib/ecl/geo/geo.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_local_position.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <drivers/drv_hrt.h>
Include dependency graph for sPort_data.cpp:

Go to the source code of this file.

Classes

struct  s_port_subscription_data_s
 

Macros

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

Functions

bool sPort_init ()
 Initializes the uORB subscriptions. More...
 
void sPort_deinit ()
 
void sPort_update_topics ()
 
static void update_crc (uint16_t *crc, unsigned char b)
 
static void sPort_send_byte (int uart, uint8_t value)
 Sends one byte, performing byte-stuffing if necessary. More...
 
void sPort_send_data (int uart, uint16_t id, uint32_t data)
 Sends one data id/value pair. More...
 
void sPort_send_BATV (int uart)
 
void sPort_send_CUR (int uart)
 
void sPort_send_ALT (int uart)
 
void sPort_send_SPD (int uart)
 
void sPort_send_VSPD (int uart, float speed)
 
void sPort_send_FUEL (int uart)
 
void sPort_send_GPS_LON (int uart)
 
void sPort_send_GPS_LAT (int uart)
 
void sPort_send_GPS_ALT (int uart)
 
void sPort_send_GPS_CRS (int uart)
 
void sPort_send_GPS_TIME (int uart)
 
void sPort_send_GPS_SPD (int uart)
 
void sPort_send_NAV_STATE (int uart)
 
void sPort_send_GPS_FIX (int uart)
 
void sPort_send_flight_mode (int uart)
 
void sPort_send_GPS_info (int uart)
 

Variables

static struct s_port_subscription_data_ss_port_subscription_data = nullptr
 

Macro Definition Documentation

◆ frac

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

Definition at line 65 of file sPort_data.cpp.

Function Documentation

◆ sPort_deinit()

void sPort_deinit ( void  )

Definition at line 94 of file sPort_data.cpp.

References s_port_subscription_data.

Referenced by frsky_telemetry_thread_main().

Here is the caller graph for this function:

◆ sPort_init()

bool sPort_init ( void  )

Initializes the uORB subscriptions.

Definition at line 83 of file sPort_data.cpp.

Referenced by frsky_telemetry_thread_main().

Here is the caller graph for this function:

◆ sPort_send_ALT()

void sPort_send_ALT ( int  uart)

Definition at line 197 of file sPort_data.cpp.

References vehicle_air_data_s::baro_alt_meter, uORB::SubscriptionData< T >::get(), SMARTPORT_ID_ALT, sPort_send_data(), and s_port_subscription_data_s::vehicle_air_data_sub.

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_send_BATV()

void sPort_send_BATV ( int  uart)

Definition at line 179 of file sPort_data.cpp.

References s_port_subscription_data_s::battery_status_sub, uORB::SubscriptionData< T >::get(), SMARTPORT_ID_VFAS, sPort_send_data(), 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:

◆ sPort_send_byte()

static void sPort_send_byte ( int  uart,
uint8_t  value 
)
static

Sends one byte, performing byte-stuffing if necessary.

Definition at line 123 of file sPort_data.cpp.

References write().

Referenced by sPort_send_data().

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

◆ sPort_send_CUR()

void sPort_send_CUR ( int  uart)

Definition at line 187 of file sPort_data.cpp.

References s_port_subscription_data_s::battery_status_sub, battery_status_s::current_a, uORB::SubscriptionData< T >::get(), SMARTPORT_ID_CURR, and sPort_send_data().

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_send_data()

void sPort_send_data ( int  uart,
uint16_t  id,
uint32_t  data 
)

Sends one data id/value pair.

Definition at line 146 of file sPort_data.cpp.

References data, sPort_send_byte(), update_crc(), and write().

Referenced by sPort_send_ALT(), sPort_send_BATV(), sPort_send_CUR(), sPort_send_flight_mode(), sPort_send_FUEL(), sPort_send_GPS_ALT(), sPort_send_GPS_CRS(), sPort_send_GPS_FIX(), sPort_send_GPS_info(), sPort_send_GPS_LAT(), sPort_send_GPS_LON(), sPort_send_GPS_SPD(), sPort_send_GPS_TIME(), sPort_send_NAV_STATE(), sPort_send_SPD(), and sPort_send_VSPD().

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

◆ sPort_send_flight_mode()

void sPort_send_flight_mode ( int  uart)

Definition at line 330 of file sPort_data.cpp.

References FRSKY_ID_TEMP1, uORB::SubscriptionData< T >::get(), get_telemetry_flight_mode(), vehicle_status_s::nav_state, sPort_send_data(), and s_port_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:

◆ sPort_send_FUEL()

void sPort_send_FUEL ( int  uart)

Definition at line 224 of file sPort_data.cpp.

References s_port_subscription_data_s::battery_status_sub, uORB::SubscriptionData< T >::get(), battery_status_s::remaining, SMARTPORT_ID_FUEL, and sPort_send_data().

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_send_GPS_ALT()

void sPort_send_GPS_ALT ( int  uart)

Definition at line 256 of file sPort_data.cpp.

References vehicle_gps_position_s::alt, uORB::SubscriptionData< T >::get(), SMARTPORT_ID_GPS_ALT, sPort_send_data(), and s_port_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:

◆ sPort_send_GPS_CRS()

void sPort_send_GPS_CRS ( int  uart)

Definition at line 263 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), M_PI_F, SMARTPORT_ID_GPS_CRS, sPort_send_data(), s_port_subscription_data_s::vehicle_local_position_sub, and vehicle_local_position_s::yaw.

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_send_GPS_FIX()

void sPort_send_GPS_FIX ( int  uart)

Definition at line 321 of file sPort_data.cpp.

References vehicle_gps_position_s::fix_type, uORB::SubscriptionData< T >::get(), vehicle_gps_position_s::satellites_used, SMARTPORT_ID_DIY_GPSFIX, sPort_send_data(), t2, and s_port_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:

◆ sPort_send_GPS_info()

void sPort_send_GPS_info ( int  uart)

Definition at line 337 of file sPort_data.cpp.

References vehicle_gps_position_s::fix_type, FRSKY_ID_TEMP2, uORB::SubscriptionData< T >::get(), gps, vehicle_gps_position_s::satellites_used, sPort_send_data(), and s_port_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:

◆ sPort_send_GPS_LAT()

void sPort_send_GPS_LAT ( int  uart)

Definition at line 245 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), vehicle_gps_position_s::lat, SMARTPORT_ID_GPS_LON_LAT, sPort_send_data(), and s_port_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:

◆ sPort_send_GPS_LON()

void sPort_send_GPS_LON ( int  uart)

Definition at line 231 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), vehicle_gps_position_s::lon, SMARTPORT_ID_GPS_LON_LAT, sPort_send_data(), and s_port_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:

◆ sPort_send_GPS_SPD()

void sPort_send_GPS_SPD ( int  uart)

Definition at line 298 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), SMARTPORT_ID_GPS_SPD, sPort_send_data(), s_port_subscription_data_s::vehicle_global_position_sub, vehicle_global_position_s::vel_e, and vehicle_global_position_s::vel_n.

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_send_GPS_TIME()

void sPort_send_GPS_TIME ( int  uart)

Definition at line 275 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), SMARTPORT_ID_GPS_TIME, sPort_send_data(), vehicle_gps_position_s::time_utc_usec, and s_port_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:

◆ sPort_send_NAV_STATE()

void sPort_send_NAV_STATE ( int  uart)

Definition at line 311 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), vehicle_status_s::nav_state, SMARTPORT_ID_DIY_NAVSTATE, sPort_send_data(), and s_port_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:

◆ sPort_send_SPD()

void sPort_send_SPD ( int  uart)

Definition at line 205 of file sPort_data.cpp.

References uORB::SubscriptionData< T >::get(), SMARTPORT_ID_GPS_SPD, sPort_send_data(), s_port_subscription_data_s::vehicle_global_position_sub, vehicle_global_position_s::vel_e, and vehicle_global_position_s::vel_n.

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_send_VSPD()

void sPort_send_VSPD ( int  uart,
float  speed 
)

Definition at line 216 of file sPort_data.cpp.

References SMARTPORT_ID_VARIO, and sPort_send_data().

Referenced by frsky_telemetry_thread_main().

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

◆ sPort_update_topics()

void sPort_update_topics ( void  )

Definition at line 102 of file sPort_data.cpp.

References s_port_subscription_data_s::battery_status_sub, s_port_subscription_data_s::sensor_combined_sub, uORB::SubscriptionData< T >::update(), s_port_subscription_data_s::vehicle_air_data_sub, s_port_subscription_data_s::vehicle_global_position_sub, s_port_subscription_data_s::vehicle_gps_position_sub, s_port_subscription_data_s::vehicle_local_position_sub, and s_port_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:

◆ update_crc()

static void update_crc ( uint16_t *  crc,
unsigned char  b 
)
static

Definition at line 113 of file sPort_data.cpp.

Referenced by sPort_send_data().

Here is the caller graph for this function:

Variable Documentation

◆ s_port_subscription_data

struct s_port_subscription_data_s* s_port_subscription_data = nullptr
static

Definition at line 77 of file sPort_data.cpp.

Referenced by sPort_deinit().