AP_Proximity: remove empty constructors

Well, some of them were only essentially empty
This commit is contained in:
Peter Barker 2019-09-27 19:33:18 +10:00 committed by Randy Mackay
parent 9879821600
commit 922cd629c0
8 changed files with 7 additions and 47 deletions

View File

@ -23,16 +23,6 @@ extern const AP_HAL::HAL& hal;
#define PROXIMITY_MAX_RANGE 100.0f
#define PROXIMITY_ACCURACY 0.1f
/*
The constructor also initialises the proximity sensor.
*/
AP_Proximity_AirSimSITL::AP_Proximity_AirSimSITL(AP_Proximity &_frontend,
AP_Proximity::Proximity_State &_state):
AP_Proximity_Backend(_frontend, _state),
sitl(AP::sitl())
{
}
// update the state of the sensor
void AP_Proximity_AirSimSITL::update(void)
{

View File

@ -26,7 +26,7 @@ class AP_Proximity_AirSimSITL : public AP_Proximity_Backend
public:
// constructor
AP_Proximity_AirSimSITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
using AP_Proximity_Backend::AP_Proximity_Backend;
// update state
void update(void) override;
@ -39,6 +39,6 @@ public:
bool get_upward_distance(float &distance) const override;
private:
SITL::SITL *sitl;
SITL::SITL *sitl = AP::sitl();
};
#endif // CONFIG_HAL_BOARD

View File

@ -23,17 +23,6 @@ extern const AP_HAL::HAL& hal;
#define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds
/*
The constructor also initialises the proximity sensor. Note that this
constructor is not called until detect() returns true, so we
already know that we should setup the proximity sensor
*/
AP_Proximity_MAV::AP_Proximity_MAV(AP_Proximity &_frontend,
AP_Proximity::Proximity_State &_state) :
AP_Proximity_Backend(_frontend, _state)
{
}
// update the state of the sensor
void AP_Proximity_MAV::update(void)
{

View File

@ -8,7 +8,7 @@ class AP_Proximity_MAV : public AP_Proximity_Backend
public:
// constructor
AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
using AP_Proximity_Backend::AP_Proximity_Backend;
// update state
void update(void) override;

View File

@ -24,16 +24,6 @@ extern const AP_HAL::HAL& hal;
#define PROXIMITY_MAX_RANGE 200.0f
#define PROXIMITY_ACCURACY 0.1f
/*
The constructor also initialises the proximity sensor.
*/
AP_Proximity_MorseSITL::AP_Proximity_MorseSITL(AP_Proximity &_frontend,
AP_Proximity::Proximity_State &_state):
AP_Proximity_Backend(_frontend, _state),
sitl(AP::sitl())
{
}
// update the state of the sensor
void AP_Proximity_MorseSITL::update(void)
{

View File

@ -11,7 +11,7 @@ class AP_Proximity_MorseSITL : public AP_Proximity_Backend
public:
// constructor
AP_Proximity_MorseSITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
using AP_Proximity_Backend::AP_Proximity_Backend;
// update state
void update(void) override;
@ -24,7 +24,7 @@ public:
bool get_upward_distance(float &distance) const override;
private:
SITL::SITL *sitl;
SITL::SITL *sitl = AP::sitl();
float distance_maximum;
};
#endif // CONFIG_HAL_BOARD

View File

@ -20,15 +20,6 @@
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_RangeFinder/RangeFinder_Backend.h>
extern const AP_HAL::HAL& hal;
AP_Proximity_RangeFinder::AP_Proximity_RangeFinder(AP_Proximity &_frontend,
AP_Proximity::Proximity_State &_state) :
AP_Proximity_Backend(_frontend, _state),
_distance_upward(-1)
{
}
// update the state of the sensor
void AP_Proximity_RangeFinder::update(void)
{

View File

@ -10,7 +10,7 @@ class AP_Proximity_RangeFinder : public AP_Proximity_Backend
public:
// constructor
AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
using AP_Proximity_Backend::AP_Proximity_Backend;
// update state
void update(void) override;
@ -31,5 +31,5 @@ private:
// upward distance support
uint32_t _last_upward_update_ms; // system time of last update distance
float _distance_upward; // upward distance in meters, negative if the last reading was out of range
float _distance_upward = -1; // upward distance in meters, negative if the last reading was out of range
};