AP_Frsky_Telem: reformat new filed using astyle.sh; no history to lose
This commit is contained in:
parent
9c211d9847
commit
6cbb553adc
@ -49,7 +49,8 @@ void AP_Frsky_Backend::loop(void)
|
||||
float AP_Frsky_Backend::get_vspeed_ms(void)
|
||||
{
|
||||
|
||||
{// release semaphore as soon as possible
|
||||
{
|
||||
// release semaphore as soon as possible
|
||||
AP_AHRS &_ahrs = AP::ahrs();
|
||||
Vector3f v;
|
||||
WITH_SEMAPHORE(_ahrs.get_semaphore());
|
||||
|
@ -3,7 +3,8 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
class AP_Frsky_Backend {
|
||||
class AP_Frsky_Backend
|
||||
{
|
||||
public:
|
||||
|
||||
AP_Frsky_Backend(AP_HAL::UARTDriver *port) :
|
||||
@ -15,10 +16,14 @@ public:
|
||||
virtual void send() = 0;
|
||||
|
||||
// SPort is at 57600, D overrides this
|
||||
virtual uint32_t initial_baud() const { return 57600; }
|
||||
virtual uint32_t initial_baud() const
|
||||
{
|
||||
return 57600;
|
||||
}
|
||||
|
||||
// get next telemetry data for external consumers of SPort data
|
||||
virtual bool get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data) {
|
||||
virtual bool get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -38,8 +43,7 @@ protected:
|
||||
// methods to convert flight controller data to FrSky D or SPort format
|
||||
float format_gps(float dec);
|
||||
|
||||
struct
|
||||
{
|
||||
struct {
|
||||
int32_t vario_vspd;
|
||||
char lat_ns, lon_ew;
|
||||
uint16_t latdddmm;
|
||||
|
@ -2,7 +2,8 @@
|
||||
|
||||
#include "AP_Frsky_Backend.h"
|
||||
|
||||
class AP_Frsky_D : public AP_Frsky_Backend {
|
||||
class AP_Frsky_D : public AP_Frsky_Backend
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
@ -11,7 +12,10 @@ public:
|
||||
protected:
|
||||
|
||||
void send() override;
|
||||
uint32_t initial_baud() const override { return 9600; }
|
||||
uint32_t initial_baud() const override
|
||||
{
|
||||
return 9600;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
|
@ -2,7 +2,8 @@
|
||||
|
||||
#include "AP_Frsky_Backend.h"
|
||||
|
||||
class AP_Frsky_SPort : public AP_Frsky_Backend {
|
||||
class AP_Frsky_SPort : public AP_Frsky_Backend
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
@ -14,8 +15,7 @@ protected:
|
||||
|
||||
void send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data);
|
||||
|
||||
struct PACKED
|
||||
{
|
||||
struct PACKED {
|
||||
bool send_latitude; // sizeof(bool) = 4 ?
|
||||
uint32_t gps_lng_sample;
|
||||
uint8_t new_byte;
|
||||
@ -25,8 +25,7 @@ protected:
|
||||
|
||||
private:
|
||||
|
||||
struct
|
||||
{
|
||||
struct {
|
||||
bool sport_status;
|
||||
bool gps_refresh;
|
||||
bool vario_refresh;
|
||||
|
@ -6,7 +6,8 @@
|
||||
// for fair scheduler
|
||||
#define TIME_SLOT_MAX 11
|
||||
|
||||
class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry {
|
||||
class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry
|
||||
{
|
||||
public:
|
||||
|
||||
AP_Frsky_SPort_Passthrough(AP_HAL::UARTDriver *port, bool use_external_data) :
|
||||
@ -29,7 +30,8 @@ public:
|
||||
|
||||
bool get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data) override;
|
||||
|
||||
void queue_text_message(MAV_SEVERITY severity, const char *text) override {
|
||||
void queue_text_message(MAV_SEVERITY severity, const char *text) override
|
||||
{
|
||||
AP_RCTelemetry::queue_message(severity, text);
|
||||
}
|
||||
|
||||
@ -80,8 +82,7 @@ private:
|
||||
bool pending;
|
||||
} external_data;
|
||||
|
||||
struct
|
||||
{
|
||||
struct {
|
||||
uint32_t chunk; // a "chunk" (four characters/bytes) at a time of the queued message to be sent
|
||||
uint8_t repeats; // send each message "chunk" 3 times to make sure the entire messsage gets through without getting cut
|
||||
uint8_t char_index; // index of which character to get in the message
|
||||
|
Loading…
Reference in New Issue
Block a user