AP_WheelEncoder: add singleton

This commit is contained in:
Randy Mackay 2020-11-27 17:17:01 +09:00
parent 38dd3b9209
commit 3984cdd823
2 changed files with 27 additions and 0 deletions

View File

@ -151,6 +151,8 @@ const AP_Param::GroupInfo AP_WheelEncoder::var_info[] = {
AP_WheelEncoder::AP_WheelEncoder(void)
{
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
}
@ -347,3 +349,15 @@ uint32_t AP_WheelEncoder::get_last_reading_ms(uint8_t instance) const
}
return state[instance].last_reading_ms;
}
// singleton instance
AP_WheelEncoder *AP_WheelEncoder::_singleton;
namespace AP {
AP_WheelEncoder *wheelencoder()
{
return AP_WheelEncoder::get_singleton();
}
}

View File

@ -39,6 +39,11 @@ public:
AP_WheelEncoder(const AP_WheelEncoder &other) = delete;
AP_WheelEncoder &operator=(const AP_WheelEncoder&) = delete;
// get singleton instance
static AP_WheelEncoder *get_singleton() {
return _singleton;
}
// WheelEncoder driver types
enum WheelEncoder_Type : uint8_t {
WheelEncoder_TYPE_NONE = 0,
@ -121,4 +126,12 @@ protected:
AP_WheelEncoder_Backend *drivers[WHEELENCODER_MAX_INSTANCES];
uint8_t num_instances;
Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
private:
static AP_WheelEncoder *_singleton;
};
namespace AP {
AP_WheelEncoder *wheelencoder();
}