Browse Source

AP_Devo_Telem: use AHRS singleton

master
Peter Barker 6 years ago committed by Francisco Ferreira
parent
commit
97a6ead690
  1. 6
      libraries/AP_Devo_Telem/AP_Devo_Telem.cpp
  2. 4
      libraries/AP_Devo_Telem/AP_Devo_Telem.h

6
libraries/AP_Devo_Telem/AP_Devo_Telem.cpp

@ -25,6 +25,8 @@ @@ -25,6 +25,8 @@
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
#include "AP_Devo_Telem.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
@ -32,8 +34,7 @@ extern const AP_HAL::HAL& hal; @@ -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) @@ -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;

4
libraries/AP_Devo_Telem/AP_Devo_Telem.h

@ -16,13 +16,12 @@ @@ -16,13 +16,12 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_SerialManager/AP_SerialManager.h>
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: @@ -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;

Loading…
Cancel
Save