mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: reuse airspeed backend contructor in more backends
... and clean out some unused includes
This commit is contained in:
parent
4f355f7c8b
commit
89a1330801
|
@ -13,11 +13,6 @@ extern const AP_HAL::HAL& hal;
|
||||||
AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[];
|
AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[];
|
||||||
HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry;
|
HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry;
|
||||||
|
|
||||||
// constructor
|
|
||||||
AP_Airspeed_DroneCAN::AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance) :
|
|
||||||
AP_Airspeed_Backend(_frontend, _instance)
|
|
||||||
{}
|
|
||||||
|
|
||||||
void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||||
{
|
{
|
||||||
if (ap_dronecan == nullptr) {
|
if (ap_dronecan == nullptr) {
|
||||||
|
|
|
@ -14,7 +14,8 @@
|
||||||
|
|
||||||
class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend {
|
class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend {
|
||||||
public:
|
public:
|
||||||
AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance);
|
|
||||||
|
using AP_Airspeed_Backend::AP_Airspeed_Backend;
|
||||||
|
|
||||||
bool init(void) override;
|
bool init(void) override;
|
||||||
|
|
||||||
|
|
|
@ -27,7 +27,6 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
#include <AP_HAL/I2CDevice.h>
|
#include <AP_HAL/I2CDevice.h>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
|
|
@ -27,7 +27,6 @@
|
||||||
#if AP_AIRSPEED_MS5525_ENABLED
|
#if AP_AIRSPEED_MS5525_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
#include <AP_HAL/I2CDevice.h>
|
#include <AP_HAL/I2CDevice.h>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
|
|
@ -30,13 +30,6 @@
|
||||||
|
|
||||||
#define TIMEOUT_MS 2000
|
#define TIMEOUT_MS 2000
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
|
||||||
|
|
||||||
AP_Airspeed_NMEA::AP_Airspeed_NMEA(AP_Airspeed &_frontend, uint8_t _instance) :
|
|
||||||
AP_Airspeed_Backend(_frontend, _instance)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
bool AP_Airspeed_NMEA::init()
|
bool AP_Airspeed_NMEA::init()
|
||||||
{
|
{
|
||||||
const AP_SerialManager& serial_manager = AP::serialmanager();
|
const AP_SerialManager& serial_manager = AP::serialmanager();
|
||||||
|
|
|
@ -15,7 +15,8 @@
|
||||||
class AP_Airspeed_NMEA : public AP_Airspeed_Backend
|
class AP_Airspeed_NMEA : public AP_Airspeed_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
AP_Airspeed_NMEA(AP_Airspeed &frontend, uint8_t _instance);
|
|
||||||
|
using AP_Airspeed_Backend::AP_Airspeed_Backend;
|
||||||
|
|
||||||
// probe and initialise the sensor
|
// probe and initialise the sensor
|
||||||
bool init(void) override;
|
bool init(void) override;
|
||||||
|
|
|
@ -42,11 +42,6 @@
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
AP_Airspeed_SDP3X::AP_Airspeed_SDP3X(AP_Airspeed &_frontend, uint8_t _instance) :
|
|
||||||
AP_Airspeed_Backend(_frontend, _instance)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
send a 16 bit command code
|
send a 16 bit command code
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -27,7 +27,6 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
#include <AP_HAL/I2CDevice.h>
|
#include <AP_HAL/I2CDevice.h>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
@ -42,8 +41,8 @@
|
||||||
class AP_Airspeed_SDP3X : public AP_Airspeed_Backend
|
class AP_Airspeed_SDP3X : public AP_Airspeed_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
AP_Airspeed_SDP3X(AP_Airspeed &frontend, uint8_t _instance);
|
|
||||||
~AP_Airspeed_SDP3X(void) {}
|
using AP_Airspeed_Backend::AP_Airspeed_Backend;
|
||||||
|
|
||||||
// probe and initialise the sensor
|
// probe and initialise the sensor
|
||||||
bool init() override;
|
bool init() override;
|
||||||
|
|
|
@ -9,7 +9,6 @@
|
||||||
#if AP_AIRSPEED_ANALOG_ENABLED
|
#if AP_AIRSPEED_ANALOG_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
|
||||||
|
|
||||||
#include "AP_Airspeed_Backend.h"
|
#include "AP_Airspeed_Backend.h"
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue