5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-03 14:38:30 -04:00

AP_WindVane: remove empty contructors

This commit is contained in:
Peter Barker 2021-08-25 13:22:19 +10:00 committed by Peter Barker
parent 6aed71b75d
commit 1387ed06bd
10 changed files with 6 additions and 35 deletions

View File

@ -15,12 +15,6 @@
#include "AP_WindVane_Airspeed.h"
// constructor
AP_WindVane_Airspeed::AP_WindVane_Airspeed(AP_WindVane &frontend) :
AP_WindVane_Backend(frontend)
{
}
void AP_WindVane_Airspeed::update_speed()
{
const AP_Airspeed* airspeed = AP_Airspeed::get_singleton();

View File

@ -22,7 +22,7 @@ class AP_WindVane_Airspeed : public AP_WindVane_Backend
{
public:
// constructor
AP_WindVane_Airspeed(AP_WindVane &frontend);
using AP_WindVane_Backend::AP_WindVane_Backend;
// update state
void update_speed() override;

View File

@ -15,12 +15,6 @@
#include "AP_WindVane_Home.h"
// constructor
AP_WindVane_Home::AP_WindVane_Home(AP_WindVane &frontend) :
AP_WindVane_Backend(frontend)
{
}
void AP_WindVane_Home::update_direction()
{
float direction_apparent_ef = _frontend._home_heading;

View File

@ -21,7 +21,7 @@ class AP_WindVane_Home : public AP_WindVane_Backend
{
public:
// constructor
AP_WindVane_Home(AP_WindVane &frontend);
using AP_WindVane_Backend::AP_WindVane_Backend;
// update state
void update_direction() override;

View File

@ -23,12 +23,6 @@
heavily based on RangeFinder NMEA library
*/
// constructor
AP_WindVane_NMEA::AP_WindVane_NMEA(AP_WindVane &frontend) :
AP_WindVane_Backend(frontend)
{
}
// init - performs any required initialization for this instance
void AP_WindVane_NMEA::init(const AP_SerialManager& serial_manager)
{

View File

@ -20,7 +20,7 @@ class AP_WindVane_NMEA : public AP_WindVane_Backend
{
public:
// constructor
AP_WindVane_NMEA(AP_WindVane &frontend);
using AP_WindVane_Backend::AP_WindVane_Backend;
// initialization
void init(const AP_SerialManager& serial_manager) override;

View File

@ -15,12 +15,6 @@
#include "AP_WindVane_RPM.h"
// constructor
AP_WindVane_RPM::AP_WindVane_RPM(AP_WindVane &frontend) :
AP_WindVane_Backend(frontend)
{
}
void AP_WindVane_RPM::update_speed()
{
const AP_RPM* rpm = AP_RPM::get_singleton();

View File

@ -22,7 +22,7 @@ class AP_WindVane_RPM : public AP_WindVane_Backend
{
public:
// constructor
AP_WindVane_RPM(AP_WindVane &frontend);
using AP_WindVane_Backend::AP_WindVane_Backend;
// update state
void update_speed() override;

View File

@ -15,12 +15,6 @@
#include "AP_WindVane_SITL.h"
// constructor
AP_WindVane_SITL::AP_WindVane_SITL(AP_WindVane &frontend) :
AP_WindVane_Backend(frontend)
{
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
void AP_WindVane_SITL::update_direction()

View File

@ -19,8 +19,9 @@
class AP_WindVane_SITL : public AP_WindVane_Backend
{
public:
// constructor
AP_WindVane_SITL(AP_WindVane &frontend);
using AP_WindVane_Backend::AP_WindVane_Backend;
// update state
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL