AP_Beacon: use enum class for type

This commit is contained in:
Peter Barker 2024-06-24 11:22:18 +10:00 committed by Peter Barker
parent b841f5517e
commit 87d694414b
2 changed files with 25 additions and 17 deletions

View File

@ -97,24 +97,30 @@ void AP_Beacon::init(void)
} }
// create backend // create backend
if (_type == AP_BeaconType_Pozyx) { switch ((Type)_type) {
case Type::Pozyx:
_driver = NEW_NOTHROW AP_Beacon_Pozyx(*this); _driver = NEW_NOTHROW AP_Beacon_Pozyx(*this);
} else if (_type == AP_BeaconType_Marvelmind) { break;
case Type::Marvelmind:
_driver = NEW_NOTHROW AP_Beacon_Marvelmind(*this); _driver = NEW_NOTHROW AP_Beacon_Marvelmind(*this);
} else if (_type == AP_BeaconType_Nooploop) { break;
case Type::Nooploop:
_driver = NEW_NOTHROW AP_Beacon_Nooploop(*this); _driver = NEW_NOTHROW AP_Beacon_Nooploop(*this);
} break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if AP_BEACON_SITL_ENABLED
if (_type == AP_BeaconType_SITL) { case Type::SITL:
_driver = NEW_NOTHROW AP_Beacon_SITL(*this); _driver = NEW_NOTHROW AP_Beacon_SITL(*this);
} break;
#endif #endif
case Type::None:
break;
}
} }
// return true if beacon feature is enabled // return true if beacon feature is enabled
bool AP_Beacon::enabled(void) const bool AP_Beacon::enabled(void) const
{ {
return (_type != AP_BeaconType_None); return (_type != Type::None);
} }
// return true if sensor is basically healthy (we are receiving data) // return true if sensor is basically healthy (we are receiving data)
@ -236,7 +242,7 @@ Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const
// return last update time from beacon in milliseconds // return last update time from beacon in milliseconds
uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const
{ {
if (_type == AP_BeaconType_None || beacon_instance >= num_beacons) { if (_type == Type::None || beacon_instance >= num_beacons) {
return 0; return 0;
} }
return beacon_state[beacon_instance].distance_update_ms; return beacon_state[beacon_instance].distance_update_ms;
@ -388,7 +394,7 @@ const Vector2f* AP_Beacon::get_boundary_points(uint16_t& num_points) const
// check if the device is ready // check if the device is ready
bool AP_Beacon::device_ready(void) const bool AP_Beacon::device_ready(void) const
{ {
return ((_driver != nullptr) && (_type != AP_BeaconType_None)); return ((_driver != nullptr) && (_type != Type::None));
} }
#if HAL_LOGGING_ENABLED #if HAL_LOGGING_ENABLED

View File

@ -40,12 +40,14 @@ public:
static AP_Beacon *get_singleton() { return _singleton; } static AP_Beacon *get_singleton() { return _singleton; }
// external position backend types (used by _TYPE parameter) // external position backend types (used by _TYPE parameter)
enum AP_BeaconType { enum class Type : uint8_t {
AP_BeaconType_None = 0, None = 0,
AP_BeaconType_Pozyx = 1, Pozyx = 1,
AP_BeaconType_Marvelmind = 2, Marvelmind = 2,
AP_BeaconType_Nooploop = 3, Nooploop = 3,
AP_BeaconType_SITL = 10 #if AP_BEACON_SITL_ENABLED
SITL = 10
#endif
}; };
// The AP_BeaconState structure is filled in by the backend driver // The AP_BeaconState structure is filled in by the backend driver
@ -125,7 +127,7 @@ private:
static bool get_next_boundary_point(const Vector2f* boundary, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle); static bool get_next_boundary_point(const Vector2f* boundary, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle);
// parameters // parameters
AP_Int8 _type; AP_Enum<Type> _type;
AP_Float origin_lat; AP_Float origin_lat;
AP_Float origin_lon; AP_Float origin_lon;
AP_Float origin_alt; AP_Float origin_alt;