mirror of https://github.com/ArduPilot/ardupilot
AP_RCMapper: add singleton
This commit is contained in:
parent
a09c18386e
commit
e166e90c1d
|
@ -61,8 +61,19 @@ const AP_Param::GroupInfo RCMapper::var_info[] = {
|
|||
AP_GROUPEND
|
||||
};
|
||||
|
||||
// singleton instance
|
||||
RCMapper *RCMapper::_singleton;
|
||||
|
||||
// object constructor.
|
||||
RCMapper::RCMapper(void)
|
||||
{
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("RCMapper must be singleton");
|
||||
}
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
RCMapper *AP::rcmap() {
|
||||
return RCMapper::get_singleton();
|
||||
}
|
||||
|
|
|
@ -12,6 +12,12 @@ public:
|
|||
RCMapper(const RCMapper &other) = delete;
|
||||
RCMapper &operator=(const RCMapper&) = delete;
|
||||
|
||||
// get singleton instance
|
||||
static RCMapper *get_singleton()
|
||||
{
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
/// roll - return input channel number for roll / aileron input
|
||||
uint8_t roll() const { return _ch_roll; }
|
||||
|
||||
|
@ -40,4 +46,10 @@ private:
|
|||
AP_Int8 _ch_throttle;
|
||||
AP_Int8 _ch_forward;
|
||||
AP_Int8 _ch_lateral;
|
||||
static RCMapper *_singleton;
|
||||
};
|
||||
|
||||
namespace AP
|
||||
{
|
||||
RCMapper *rcmap();
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue