AP_Proximity: remove empty constructors
Well, some of them were only essentially empty
This commit is contained in:
parent
7944692de6
commit
39863bf0b4
@ -23,16 +23,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
#define PROXIMITY_MAX_RANGE 100.0f
|
#define PROXIMITY_MAX_RANGE 100.0f
|
||||||
#define PROXIMITY_ACCURACY 0.1f
|
#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
|
// update the state of the sensor
|
||||||
void AP_Proximity_AirSimSITL::update(void)
|
void AP_Proximity_AirSimSITL::update(void)
|
||||||
{
|
{
|
||||||
|
@ -26,7 +26,7 @@ class AP_Proximity_AirSimSITL : public AP_Proximity_Backend
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_Proximity_AirSimSITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
|
using AP_Proximity_Backend::AP_Proximity_Backend;
|
||||||
|
|
||||||
// update state
|
// update state
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
@ -39,6 +39,6 @@ public:
|
|||||||
bool get_upward_distance(float &distance) const override;
|
bool get_upward_distance(float &distance) const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
SITL::SITL *sitl;
|
SITL::SITL *sitl = AP::sitl();
|
||||||
};
|
};
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -23,17 +23,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
#define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds
|
#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
|
// update the state of the sensor
|
||||||
void AP_Proximity_MAV::update(void)
|
void AP_Proximity_MAV::update(void)
|
||||||
{
|
{
|
||||||
|
@ -8,7 +8,7 @@ class AP_Proximity_MAV : public AP_Proximity_Backend
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
|
using AP_Proximity_Backend::AP_Proximity_Backend;
|
||||||
|
|
||||||
// update state
|
// update state
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
|
@ -24,16 +24,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
#define PROXIMITY_MAX_RANGE 200.0f
|
#define PROXIMITY_MAX_RANGE 200.0f
|
||||||
#define PROXIMITY_ACCURACY 0.1f
|
#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
|
// update the state of the sensor
|
||||||
void AP_Proximity_MorseSITL::update(void)
|
void AP_Proximity_MorseSITL::update(void)
|
||||||
{
|
{
|
||||||
|
@ -11,7 +11,7 @@ class AP_Proximity_MorseSITL : public AP_Proximity_Backend
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_Proximity_MorseSITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
|
using AP_Proximity_Backend::AP_Proximity_Backend;
|
||||||
|
|
||||||
// update state
|
// update state
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
@ -24,7 +24,7 @@ public:
|
|||||||
bool get_upward_distance(float &distance) const override;
|
bool get_upward_distance(float &distance) const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
SITL::SITL *sitl;
|
SITL::SITL *sitl = AP::sitl();
|
||||||
float distance_maximum;
|
float distance_maximum;
|
||||||
};
|
};
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -20,15 +20,6 @@
|
|||||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
#include <AP_RangeFinder/RangeFinder_Backend.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
|
// update the state of the sensor
|
||||||
void AP_Proximity_RangeFinder::update(void)
|
void AP_Proximity_RangeFinder::update(void)
|
||||||
{
|
{
|
||||||
|
@ -10,7 +10,7 @@ class AP_Proximity_RangeFinder : public AP_Proximity_Backend
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
|
using AP_Proximity_Backend::AP_Proximity_Backend;
|
||||||
|
|
||||||
// update state
|
// update state
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
@ -31,5 +31,5 @@ private:
|
|||||||
|
|
||||||
// upward distance support
|
// upward distance support
|
||||||
uint32_t _last_upward_update_ms; // system time of last update distance
|
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
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user