diff --git a/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp b/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp index 3134446bb2..f563ecb9a1 100644 --- a/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp +++ b/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp @@ -25,6 +25,8 @@ #define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32 #include "AP_Devo_Telem.h" + +#include #include #include @@ -32,8 +34,7 @@ extern const AP_HAL::HAL& hal; //constructor -AP_DEVO_Telem::AP_DEVO_Telem(const AP_AHRS &ahrs) : - _ahrs(ahrs) +AP_DEVO_Telem::AP_DEVO_Telem() { devoPacket.header = DEVOM_SYNC_BYTE; } @@ -81,6 +82,7 @@ void AP_DEVO_Telem::send_frames(uint8_t control_mode) return; } + const AP_AHRS &_ahrs = AP::ahrs(); const AP_GPS &gps = AP::gps(); Location loc; diff --git a/libraries/AP_Devo_Telem/AP_Devo_Telem.h b/libraries/AP_Devo_Telem/AP_Devo_Telem.h index 437d339fd8..9ad61a68dc 100644 --- a/libraries/AP_Devo_Telem/AP_Devo_Telem.h +++ b/libraries/AP_Devo_Telem/AP_Devo_Telem.h @@ -16,13 +16,12 @@ #pragma once #include -#include #include class AP_DEVO_Telem { public: //constructor - AP_DEVO_Telem(const AP_AHRS &ahrs); + AP_DEVO_Telem(); /* Do not allow copies */ AP_DEVO_Telem(const AP_DEVO_Telem &other) = delete; @@ -62,7 +61,6 @@ private: uint8_t _control_mode; - const AP_AHRS &_ahrs; // reference to attitude estimate AP_HAL::UARTDriver *_port; // UART used to send data to receiver uint32_t _last_frame_ms;