mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: add static create method
This commit is contained in:
parent
40fd1b346c
commit
aefae9381e
|
@ -22,14 +22,20 @@
|
|||
// Maximum number of RPM measurement instances available on this platform
|
||||
#define RPM_MAX_INSTANCES 2
|
||||
|
||||
class AP_RPM_Backend;
|
||||
|
||||
class AP_RPM_Backend;
|
||||
|
||||
class AP_RPM
|
||||
{
|
||||
public:
|
||||
friend class AP_RPM_Backend;
|
||||
|
||||
AP_RPM(void);
|
||||
public:
|
||||
static AP_RPM create() { return AP_RPM{}; }
|
||||
|
||||
constexpr AP_RPM(AP_RPM &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_RPM(const AP_RPM &other) = delete;
|
||||
AP_RPM &operator=(const AP_RPM&) = delete;
|
||||
|
||||
// RPM driver types
|
||||
enum RPM_Type {
|
||||
|
@ -55,7 +61,7 @@ public:
|
|||
AP_Float _quality_min[RPM_MAX_INSTANCES];
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
||||
// Return the number of rpm sensor instances
|
||||
uint8_t num_sensors(void) const {
|
||||
return num_instances;
|
||||
|
@ -89,10 +95,12 @@ public:
|
|||
bool enabled(uint8_t instance) const;
|
||||
|
||||
private:
|
||||
AP_RPM();
|
||||
|
||||
RPM_State state[RPM_MAX_INSTANCES];
|
||||
AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];
|
||||
uint8_t num_instances:2;
|
||||
|
||||
void detect_instance(uint8_t instance);
|
||||
void update_instance(uint8_t instance);
|
||||
void update_instance(uint8_t instance);
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue