mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: add AP::rpm() call for singleton
This commit is contained in:
parent
b1c789f73d
commit
7498972b8d
|
@ -182,3 +182,11 @@ bool AP_RPM::enabled(uint8_t instance) const
|
|||
// singleton instance
|
||||
AP_RPM *AP_RPM::_singleton;
|
||||
|
||||
namespace AP {
|
||||
|
||||
AP_RPM *rpm()
|
||||
{
|
||||
return AP_RPM::get_singleton();
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -104,3 +104,7 @@ private:
|
|||
void detect_instance(uint8_t instance);
|
||||
void update_instance(uint8_t instance);
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
AP_RPM *rpm();
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue