mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Devo_Telem: use AHRS singleton
This commit is contained in:
parent
2ba6aa7e8a
commit
97a6ead690
@ -25,6 +25,8 @@
|
|||||||
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
|
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
|
||||||
|
|
||||||
#include "AP_Devo_Telem.h"
|
#include "AP_Devo_Telem.h"
|
||||||
|
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
|
|
||||||
@ -32,8 +34,7 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
|
|
||||||
//constructor
|
//constructor
|
||||||
AP_DEVO_Telem::AP_DEVO_Telem(const AP_AHRS &ahrs) :
|
AP_DEVO_Telem::AP_DEVO_Telem()
|
||||||
_ahrs(ahrs)
|
|
||||||
{
|
{
|
||||||
devoPacket.header = DEVOM_SYNC_BYTE;
|
devoPacket.header = DEVOM_SYNC_BYTE;
|
||||||
}
|
}
|
||||||
@ -81,6 +82,7 @@ void AP_DEVO_Telem::send_frames(uint8_t control_mode)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const AP_AHRS &_ahrs = AP::ahrs();
|
||||||
const AP_GPS &gps = AP::gps();
|
const AP_GPS &gps = AP::gps();
|
||||||
Location loc;
|
Location loc;
|
||||||
|
|
||||||
|
@ -16,13 +16,12 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
|
||||||
class AP_DEVO_Telem {
|
class AP_DEVO_Telem {
|
||||||
public:
|
public:
|
||||||
//constructor
|
//constructor
|
||||||
AP_DEVO_Telem(const AP_AHRS &ahrs);
|
AP_DEVO_Telem();
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AP_DEVO_Telem(const AP_DEVO_Telem &other) = delete;
|
AP_DEVO_Telem(const AP_DEVO_Telem &other) = delete;
|
||||||
@ -62,7 +61,6 @@ private:
|
|||||||
|
|
||||||
uint8_t _control_mode;
|
uint8_t _control_mode;
|
||||||
|
|
||||||
const AP_AHRS &_ahrs; // reference to attitude estimate
|
|
||||||
AP_HAL::UARTDriver *_port; // UART used to send data to receiver
|
AP_HAL::UARTDriver *_port; // UART used to send data to receiver
|
||||||
uint32_t _last_frame_ms;
|
uint32_t _last_frame_ms;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user