AP_GPS: change empty constructors out for 'use AP_GPS_Backend::AP_GPS_Backend'
This commit is contained in:
parent
72b821d9da
commit
2dbe15911f
@ -21,11 +21,6 @@
|
||||
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
|
||||
AP_GPS_ExternalAHRS::AP_GPS_ExternalAHRS(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
||||
AP_GPS_Backend(_gps, _state, _port)
|
||||
{
|
||||
}
|
||||
|
||||
// Reading does nothing in this class; we simply return whether or not
|
||||
// the latest reading has been consumed. By calling this function we assume
|
||||
// the caller is consuming the new data;
|
||||
|
@ -29,7 +29,8 @@
|
||||
class AP_GPS_ExternalAHRS : public AP_GPS_Backend
|
||||
{
|
||||
public:
|
||||
AP_GPS_ExternalAHRS(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
||||
|
||||
using AP_GPS_Backend::AP_GPS_Backend;
|
||||
|
||||
bool read() override;
|
||||
void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt) override;
|
||||
|
@ -19,11 +19,6 @@
|
||||
#include "AP_GPS_MAV.h"
|
||||
#include <stdint.h>
|
||||
|
||||
AP_GPS_MAV::AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
||||
AP_GPS_Backend(_gps, _state, _port)
|
||||
{
|
||||
}
|
||||
|
||||
// Reading does nothing in this class; we simply return whether or not
|
||||
// the latest reading has been consumed. By calling this function we assume
|
||||
// the caller is consuming the new data;
|
||||
|
@ -27,7 +27,8 @@
|
||||
|
||||
class AP_GPS_MAV : public AP_GPS_Backend {
|
||||
public:
|
||||
AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
||||
|
||||
using AP_GPS_Backend::AP_GPS_Backend;
|
||||
|
||||
bool read() override;
|
||||
|
||||
|
@ -21,11 +21,6 @@
|
||||
|
||||
#if HAL_MSP_GPS_ENABLED
|
||||
|
||||
AP_GPS_MSP::AP_GPS_MSP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
||||
AP_GPS_Backend(_gps, _state, _port)
|
||||
{
|
||||
}
|
||||
|
||||
// Reading does nothing in this class; we simply return whether or not
|
||||
// the latest reading has been consumed. By calling this function we assume
|
||||
// the caller is consuming the new data;
|
||||
|
@ -29,7 +29,8 @@
|
||||
class AP_GPS_MSP : public AP_GPS_Backend
|
||||
{
|
||||
public:
|
||||
AP_GPS_MSP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
||||
|
||||
using AP_GPS_Backend::AP_GPS_Backend;
|
||||
|
||||
bool read() override;
|
||||
void handle_msp(const MSP::msp_gps_data_message_t &pkt) override;
|
||||
|
Loading…
Reference in New Issue
Block a user