mirror of https://github.com/ArduPilot/ardupilot
AP_Rally: Create singleton
This commit is contained in:
parent
c1e3e3f8c4
commit
0d369929cb
|
@ -52,6 +52,12 @@ AP_Rally::AP_Rally(AP_AHRS &ahrs)
|
||||||
: _ahrs(ahrs)
|
: _ahrs(ahrs)
|
||||||
, _last_change_time_ms(0xFFFFFFFF)
|
, _last_change_time_ms(0xFFFFFFFF)
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
if (_singleton != nullptr) {
|
||||||
|
AP_HAL::panic("Rally must be singleton");
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
_singleton = this;
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -161,3 +167,15 @@ Location AP_Rally::calc_best_rally_or_home_location(const Location ¤t_loc,
|
||||||
|
|
||||||
return return_loc;
|
return return_loc;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// singleton instance
|
||||||
|
AP_Rally *AP_Rally::_singleton;
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
|
||||||
|
AP_Rally *rally()
|
||||||
|
{
|
||||||
|
return AP_Rally::get_singleton();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
|
@ -62,7 +62,13 @@ public:
|
||||||
// parameter block
|
// parameter block
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
// get singleton instance
|
||||||
|
static AP_Rally *get_singleton() { return _singleton; }
|
||||||
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
static AP_Rally *_singleton;
|
||||||
|
|
||||||
virtual bool is_valid(const Location &rally_point) const { return true; }
|
virtual bool is_valid(const Location &rally_point) const { return true; }
|
||||||
|
|
||||||
static StorageAccess _storage;
|
static StorageAccess _storage;
|
||||||
|
@ -77,3 +83,7 @@ private:
|
||||||
|
|
||||||
uint32_t _last_change_time_ms;
|
uint32_t _last_change_time_ms;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
AP_Rally *rally();
|
||||||
|
};
|
||||||
|
|
Loading…
Reference in New Issue