mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_ICEngine: add singleton and remove unnecessary variable init
This commit is contained in:
parent
d27cd19daa
commit
4f41aa19bf
@ -108,10 +108,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
||||
|
||||
// constructor
|
||||
AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) :
|
||||
rpm(_rpm),
|
||||
state(ICE_OFF)
|
||||
rpm(_rpm)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("AP_ICEngine must be singleton");
|
||||
}
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -289,3 +293,11 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he
|
||||
state = ICE_STARTING;
|
||||
return true;
|
||||
}
|
||||
|
||||
// singleton instance. Should only ever be set in the constructor.
|
||||
AP_ICEngine *AP_ICEngine::_singleton;
|
||||
namespace AP {
|
||||
AP_ICEngine *ice() {
|
||||
return AP_ICEngine::get_singleton();
|
||||
}
|
||||
}
|
||||
|
@ -47,7 +47,11 @@ public:
|
||||
// handle DO_ENGINE_CONTROL messages via MAVLink or mission
|
||||
bool engine_control(float start_control, float cold_start, float height_delay);
|
||||
|
||||
static AP_ICEngine *get_singleton() { return _singleton; }
|
||||
|
||||
private:
|
||||
static AP_ICEngine *_singleton;
|
||||
|
||||
const AP_RPM &rpm;
|
||||
|
||||
enum ICE_State state;
|
||||
@ -95,3 +99,7 @@ private:
|
||||
bool height_pending:1;
|
||||
};
|
||||
|
||||
|
||||
namespace AP {
|
||||
AP_ICEngine *ice();
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user