mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: removed empty constructors
This commit is contained in:
parent
2406877a60
commit
001f6a29ee
|
@ -34,22 +34,13 @@ extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
volatile struct range *rangerpru;
|
volatile struct range *rangerpru;
|
||||||
|
|
||||||
/*
|
|
||||||
The constructor also initialises the rangefinder. Note that this
|
|
||||||
constructor is not called until detect() returns true, so we
|
|
||||||
already know that we should setup the rangefinder
|
|
||||||
*/
|
|
||||||
AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
|
||||||
AP_RangeFinder_Backend(_state, _params)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Stop PRU, load firmware (check if firmware is present), start PRU.
|
Stop PRU, load firmware (check if firmware is present), start PRU.
|
||||||
If we get a result the sensor seems to be there.
|
If we get a result the sensor seems to be there.
|
||||||
*/
|
*/
|
||||||
bool AP_RangeFinder_BBB_PRU::detect()
|
bool AP_RangeFinder_BBB_PRU::detect()
|
||||||
{
|
{
|
||||||
|
//The constructor is called when the detect() method returns true, more on this in the header file
|
||||||
bool result = true;
|
bool result = true;
|
||||||
uint32_t mem_fd;
|
uint32_t mem_fd;
|
||||||
uint32_t *ctrl;
|
uint32_t *ctrl;
|
||||||
|
|
|
@ -20,8 +20,13 @@ struct range {
|
||||||
class AP_RangeFinder_BBB_PRU : public AP_RangeFinder_Backend
|
class AP_RangeFinder_BBB_PRU : public AP_RangeFinder_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// constructor
|
/*
|
||||||
AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
|
Constructor:
|
||||||
|
The constructor also initialises the rangefinder. Note that this
|
||||||
|
constructor is not called until detect() returns true, so we
|
||||||
|
already know that we should setup the rangefinder
|
||||||
|
*/
|
||||||
|
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
|
||||||
|
|
||||||
// static detection function
|
// static detection function
|
||||||
static bool detect();
|
static bool detect();
|
||||||
|
|
|
@ -16,13 +16,6 @@ extern const AP_HAL::HAL& hal;
|
||||||
//UAVCAN Frontend Registry Binder
|
//UAVCAN Frontend Registry Binder
|
||||||
UC_REGISTRY_BINDER(MeasurementCb, uavcan::equipment::range_sensor::Measurement);
|
UC_REGISTRY_BINDER(MeasurementCb, uavcan::equipment::range_sensor::Measurement);
|
||||||
|
|
||||||
/*
|
|
||||||
constructor - registers instance at top RangeFinder driver
|
|
||||||
*/
|
|
||||||
AP_RangeFinder_UAVCAN::AP_RangeFinder_UAVCAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
|
||||||
AP_RangeFinder_Backend(_state, _params)
|
|
||||||
{}
|
|
||||||
|
|
||||||
//links the rangefinder uavcan message to this backend
|
//links the rangefinder uavcan message to this backend
|
||||||
void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
|
void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
|
||||||
{
|
{
|
||||||
|
|
|
@ -9,7 +9,8 @@ class MeasurementCb;
|
||||||
|
|
||||||
class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend {
|
class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend {
|
||||||
public:
|
public:
|
||||||
AP_RangeFinder_UAVCAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
|
//constructor - registers instance at top RangeFinder driver
|
||||||
|
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
|
||||||
|
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue