From 32d576ac4b7f5095a46ea3e602ad985b919bc188 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Feb 2019 10:12:14 +1100 Subject: [PATCH] AP_Devo_Telem: move devo telemetry handling to GCS --- libraries/AP_Devo_Telem/AP_Devo_Telem.cpp | 7 ++++--- libraries/AP_Devo_Telem/AP_Devo_Telem.h | 11 +---------- 2 files changed, 5 insertions(+), 13 deletions(-) diff --git a/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp b/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp index ed1b31d717..94668dcbe4 100644 --- a/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp +++ b/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp @@ -29,6 +29,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -76,7 +77,7 @@ uint32_t AP_DEVO_Telem::gpsDdToDmsFormat(float ddm) #define DEVO_SPEED_FACTOR 0.0194384f -void AP_DEVO_Telem::send_frames(uint8_t control_mode) +void AP_DEVO_Telem::send_frames() { // return immediately if not initialised if (_port == nullptr) { @@ -109,7 +110,7 @@ void AP_DEVO_Telem::send_frames(uint8_t control_mode) devoPacket.volt = roundf(AP::battery().voltage() * 10.0f); - devoPacket.temp = control_mode; // Send mode as temperature + devoPacket.temp = gcs().custom_mode(); // Send mode as temperature devoPacket.checksum8 = 0; // Init Checksum with zero Byte @@ -127,6 +128,6 @@ void AP_DEVO_Telem::tick(void) if (now - _last_frame_ms > 1000) { _last_frame_ms = now; - send_frames(_control_mode); + send_frames(); } } diff --git a/libraries/AP_Devo_Telem/AP_Devo_Telem.h b/libraries/AP_Devo_Telem/AP_Devo_Telem.h index 53b378a9bd..1e34c7c39e 100644 --- a/libraries/AP_Devo_Telem/AP_Devo_Telem.h +++ b/libraries/AP_Devo_Telem/AP_Devo_Telem.h @@ -29,13 +29,6 @@ public: void init(); - // update flight control mode. The control mode is vehicle type specific - void update_control_mode(uint8_t mode) - { - _control_mode = mode; - } - - private: typedef struct PACKED { uint8_t header; ///< 0xAA for a valid packet @@ -54,12 +47,10 @@ private: void tick(void); // send_frames - sends updates down telemetry link - void send_frames(uint8_t control_mode); + void send_frames(); DevoMPacket devoPacket; - uint8_t _control_mode; - AP_HAL::UARTDriver *_port; // UART used to send data to receiver uint32_t _last_frame_ms;