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:
parent
6aed71b75d
commit
1387ed06bd
@ -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();
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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)
|
||||
{
|
||||
|
@ -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;
|
||||
|
@ -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();
|
||||
|
@ -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;
|
||||
|
@ -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()
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user