mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Proximity: Make singleton and add an interface to check what type is loaded
This commit is contained in:
parent
7d6c3ec683
commit
f8b10aaa53
@ -178,6 +178,12 @@ AP_Proximity::AP_Proximity(AP_SerialManager &_serial_manager) :
|
|||||||
serial_manager(_serial_manager)
|
serial_manager(_serial_manager)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
if (_singleton != nullptr) {
|
||||||
|
AP_HAL::panic("AP_Proximity must be singleton");
|
||||||
|
}
|
||||||
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
_singleton = this;
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise the Proximity class. We do detection of attached sensors here
|
// initialise the Proximity class. We do detection of attached sensors here
|
||||||
@ -422,3 +428,13 @@ bool AP_Proximity::get_upward_distance(float &distance) const
|
|||||||
{
|
{
|
||||||
return get_upward_distance(primary_instance, distance);
|
return get_upward_distance(primary_instance, distance);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
AP_Proximity::Proximity_Type AP_Proximity::get_type(uint8_t instance) const
|
||||||
|
{
|
||||||
|
if (instance < PROXIMITY_MAX_INSTANCES) {
|
||||||
|
return (Proximity_Type)((uint8_t)_type[instance]);
|
||||||
|
}
|
||||||
|
return Proximity_Type_None;
|
||||||
|
}
|
||||||
|
|
||||||
|
AP_Proximity *AP_Proximity::_singleton;
|
||||||
|
@ -36,6 +36,9 @@ public:
|
|||||||
|
|
||||||
AP_Proximity(AP_SerialManager &_serial_manager);
|
AP_Proximity(AP_SerialManager &_serial_manager);
|
||||||
|
|
||||||
|
AP_Proximity(const AP_Proximity &other) = delete;
|
||||||
|
AP_Proximity &operator=(const AP_Proximity) = delete;
|
||||||
|
|
||||||
// Proximity driver types
|
// Proximity driver types
|
||||||
enum Proximity_Type {
|
enum Proximity_Type {
|
||||||
Proximity_Type_None = 0,
|
Proximity_Type_None = 0,
|
||||||
@ -124,10 +127,15 @@ public:
|
|||||||
bool get_upward_distance(uint8_t instance, float &distance) const;
|
bool get_upward_distance(uint8_t instance, float &distance) const;
|
||||||
bool get_upward_distance(float &distance) const;
|
bool get_upward_distance(float &distance) const;
|
||||||
|
|
||||||
|
Proximity_Type get_type(uint8_t instance) const;
|
||||||
|
|
||||||
// parameter list
|
// parameter list
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
static AP_Proximity *get_singleton(void) { return _singleton; };
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
static AP_Proximity *_singleton;
|
||||||
Proximity_State state[PROXIMITY_MAX_INSTANCES];
|
Proximity_State state[PROXIMITY_MAX_INSTANCES];
|
||||||
AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES];
|
AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES];
|
||||||
const RangeFinder *_rangefinder;
|
const RangeFinder *_rangefinder;
|
||||||
|
Loading…
Reference in New Issue
Block a user