mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: add static create method
This commit is contained in:
parent
f5c2ffffb9
commit
2e80b2e1d0
@ -30,10 +30,20 @@ class AP_RangeFinder_Backend;
|
||||
|
||||
class RangeFinder
|
||||
{
|
||||
public:
|
||||
friend class AP_RangeFinder_Backend;
|
||||
|
||||
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default);
|
||||
public:
|
||||
static RangeFinder create(AP_SerialManager &_serial_manager,
|
||||
enum Rotation orientation_default)
|
||||
{
|
||||
return RangeFinder(_serial_manager, orientation_default);
|
||||
}
|
||||
|
||||
constexpr RangeFinder(RangeFinder &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
RangeFinder(const RangeFinder &other) = delete;
|
||||
RangeFinder &operator=(const RangeFinder&) = delete;
|
||||
|
||||
// RangeFinder driver types
|
||||
enum RangeFinder_Type {
|
||||
@ -156,6 +166,8 @@ public:
|
||||
|
||||
|
||||
private:
|
||||
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default);
|
||||
|
||||
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES];
|
||||
AP_RangeFinder_Backend *drivers[RANGEFINDER_MAX_INSTANCES];
|
||||
uint8_t num_instances:3;
|
||||
|
Loading…
Reference in New Issue
Block a user