AP_RangeFinder: use enum-class for RangeFinder type

This commit is contained in:
Peter Barker 2019-11-01 14:03:14 +11:00 committed by Peter Barker
parent c1acdc4994
commit ea26e94f66
8 changed files with 75 additions and 75 deletions

View File

@ -48,7 +48,7 @@ extern const AP_HAL::HAL& hal;
AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus, AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus,
RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params, AP_RangeFinder_Params &_params,
RangeFinder::RangeFinder_Type _rftype) RangeFinder::Type _rftype)
: AP_RangeFinder_Backend(_state, _params) : AP_RangeFinder_Backend(_state, _params)
, _dev(hal.i2c_mgr->get_device(bus, LL40LS_ADDR)) , _dev(hal.i2c_mgr->get_device(bus, LL40LS_ADDR))
, rftype(_rftype) , rftype(_rftype)
@ -62,7 +62,7 @@ AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus,
AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus, AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params, AP_RangeFinder_Params &_params,
RangeFinder::RangeFinder_Type rftype) RangeFinder::Type rftype)
{ {
AP_RangeFinder_PulsedLightLRF *sensor AP_RangeFinder_PulsedLightLRF *sensor
= new AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype); = new AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype);
@ -167,9 +167,9 @@ bool AP_RangeFinder_PulsedLightLRF::init(void)
// LidarLite needs split transfers // LidarLite needs split transfers
_dev->set_split_transfers(true); _dev->set_split_transfers(true);
if (rftype == RangeFinder::RangeFinder_TYPE_PLI2CV3) { if (rftype == RangeFinder::Type::PLI2CV3) {
v2_hardware = true; v2_hardware = true;
} else if (rftype == RangeFinder::RangeFinder_TYPE_PLI2CV3HP) { } else if (rftype == RangeFinder::Type::PLI2CV3HP) {
v3hp_hardware = true; v3hp_hardware = true;
} else { } else {
// auto-detect v1 vs v2 // auto-detect v1 vs v2

View File

@ -22,7 +22,7 @@ public:
static AP_RangeFinder_Backend *detect(uint8_t bus, static AP_RangeFinder_Backend *detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params, AP_RangeFinder_Params &_params,
RangeFinder::RangeFinder_Type rftype); RangeFinder::Type rftype);
// update state // update state
void update(void) override {} void update(void) override {}
@ -38,7 +38,7 @@ private:
AP_RangeFinder_PulsedLightLRF(uint8_t bus, AP_RangeFinder_PulsedLightLRF(uint8_t bus,
RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params, AP_RangeFinder_Params &_params,
RangeFinder::RangeFinder_Type rftype); RangeFinder::Type rftype);
// start a reading // start a reading
bool init(void); bool init(void);
@ -53,7 +53,7 @@ private:
bool v2_hardware; bool v2_hardware;
bool v3hp_hardware; bool v3hp_hardware;
uint16_t last_distance_cm; uint16_t last_distance_cm;
RangeFinder::RangeFinder_Type rftype; RangeFinder::Type rftype;
enum { PHASE_MEASURE, PHASE_COLLECT } phase; enum { PHASE_MEASURE, PHASE_COLLECT } phase;
}; };

View File

@ -51,12 +51,12 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u
AP_RangeFinder_UAVCAN* driver = nullptr; AP_RangeFinder_UAVCAN* driver = nullptr;
//Scan through the Rangefinder params to find UAVCAN RFND with matching address. //Scan through the Rangefinder params to find UAVCAN RFND with matching address.
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if (AP::rangefinder()->params[i].type == RangeFinder::RangeFinder_TYPE_UAVCAN && if ((RangeFinder::Type)AP::rangefinder()->params[i].type.get() == RangeFinder::Type::UAVCAN &&
AP::rangefinder()->params[i].address == address) { AP::rangefinder()->params[i].address == address) {
driver = (AP_RangeFinder_UAVCAN*)AP::rangefinder()->drivers[i]; driver = (AP_RangeFinder_UAVCAN*)AP::rangefinder()->drivers[i];
} }
//Double check if the driver was initialised as UAVCAN Type //Double check if the driver was initialised as UAVCAN Type
if (driver != nullptr && (driver->_backend_type == RangeFinder::RangeFinder_TYPE_UAVCAN)) { if (driver != nullptr && (driver->_backend_type == RangeFinder::Type::UAVCAN)) {
if (driver->_ap_uavcan == ap_uavcan && if (driver->_ap_uavcan == ap_uavcan &&
driver->_node_id == node_id) { driver->_node_id == node_id) {
return driver; return driver;
@ -70,7 +70,7 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u
if (create_new) { if (create_new) {
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if (AP::rangefinder()->params[i].type == RangeFinder::RangeFinder_TYPE_UAVCAN && if ((RangeFinder::Type)AP::rangefinder()->params[i].type.get() == RangeFinder::Type::UAVCAN &&
AP::rangefinder()->params[i].address == address) { AP::rangefinder()->params[i].address == address) {
if (AP::rangefinder()->drivers[i] != nullptr) { if (AP::rangefinder()->drivers[i] != nullptr) {
//we probably initialised this driver as something else, reboot is required for setting //we probably initialised this driver as something else, reboot is required for setting

View File

@ -329,7 +329,7 @@ void RangeFinder::update(void)
{ {
for (uint8_t i=0; i<num_instances; i++) { for (uint8_t i=0; i<num_instances; i++) {
if (drivers[i] != nullptr) { if (drivers[i] != nullptr) {
if (params[i].type == RangeFinder_TYPE_NONE) { if ((Type)params[i].type.get() == Type::NONE) {
// allow user to disable a rangefinder at runtime // allow user to disable a rangefinder at runtime
state[i].status = RangeFinder_NotConnected; state[i].status = RangeFinder_NotConnected;
state[i].range_valid_count = 0; state[i].range_valid_count = 0;
@ -361,18 +361,18 @@ bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend)
*/ */
void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
{ {
enum RangeFinder_Type _type = (enum RangeFinder_Type)params[instance].type.get(); const RangeFinder::Type _type = (Type)params[instance].type.get();
switch (_type) { switch (_type) {
case RangeFinder_TYPE_PLI2C: case Type::PLI2C:
case RangeFinder_TYPE_PLI2CV3: case Type::PLI2CV3:
case RangeFinder_TYPE_PLI2CV3HP: case Type::PLI2CV3HP:
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type))) { if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type))) {
break; break;
} }
} }
break; break;
case RangeFinder_TYPE_MBI2C: case Type::MBI2C:
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)))) { hal.i2c_mgr->get_device(i, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)))) {
@ -380,7 +380,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
} }
break; break;
case RangeFinder_TYPE_LWI2C: case Type::LWI2C:
if (params[instance].address) { if (params[instance].address) {
// the LW20 needs a long time to boot up, so we delay 1.5s here // the LW20 needs a long time to boot up, so we delay 1.5s here
if (!hal.util->was_watchdog_armed()) { if (!hal.util->was_watchdog_armed()) {
@ -399,7 +399,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
#endif #endif
} }
break; break;
case RangeFinder_TYPE_TRI2C: case Type::TRI2C:
if (params[instance].address) { if (params[instance].address) {
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance],
@ -409,7 +409,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
} }
break; break;
case RangeFinder_TYPE_VL53L0X: case Type::VL53L0X:
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, params[instance].address)))) { hal.i2c_mgr->get_device(i, params[instance].address)))) {
@ -421,7 +421,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
} }
break; break;
case RangeFinder_TYPE_BenewakeTFminiPlus: case Type::BenewakeTFminiPlus:
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_Benewake_TFMiniPlus::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_Benewake_TFMiniPlus::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, params[instance].address)))) { hal.i2c_mgr->get_device(i, params[instance].address)))) {
@ -430,7 +430,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
break; break;
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
case RangeFinder_TYPE_PX4_PWM: case Type::PX4_PWM:
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
// to ease moving from PX4 to ChibiOS we'll lie a little about // to ease moving from PX4 to ChibiOS we'll lie a little about
// the backend driver... // the backend driver...
@ -441,48 +441,48 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
break; break;
#endif #endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
case RangeFinder_TYPE_BBB_PRU: case Type::BBB_PRU:
if (AP_RangeFinder_BBB_PRU::detect()) { if (AP_RangeFinder_BBB_PRU::detect()) {
drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance], params[instance]); drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance], params[instance]);
} }
break; break;
#endif #endif
case RangeFinder_TYPE_LWSER: case Type::LWSER:
if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) { if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], params[instance], serial_instance++);
} }
break; break;
case RangeFinder_TYPE_LEDDARONE: case Type::LEDDARONE:
if (AP_RangeFinder_LeddarOne::detect(serial_instance)) { if (AP_RangeFinder_LeddarOne::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], params[instance], serial_instance++);
} }
break; break;
case RangeFinder_TYPE_ULANDING: case Type::ULANDING:
if (AP_RangeFinder_uLanding::detect(serial_instance)) { if (AP_RangeFinder_uLanding::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_uLanding(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_uLanding(state[instance], params[instance], serial_instance++);
} }
break; break;
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO) CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
case RangeFinder_TYPE_BEBOP: case Type::BEBOP:
if (AP_RangeFinder_Bebop::detect()) { if (AP_RangeFinder_Bebop::detect()) {
drivers[instance] = new AP_RangeFinder_Bebop(state[instance], params[instance]); drivers[instance] = new AP_RangeFinder_Bebop(state[instance], params[instance]);
} }
break; break;
#endif #endif
case RangeFinder_TYPE_MAVLink: case Type::MAVLink:
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
if (AP_RangeFinder_MAVLink::detect()) { if (AP_RangeFinder_MAVLink::detect()) {
drivers[instance] = new AP_RangeFinder_MAVLink(state[instance], params[instance]); drivers[instance] = new AP_RangeFinder_MAVLink(state[instance], params[instance]);
} }
#endif #endif
break; break;
case RangeFinder_TYPE_MBSER: case Type::MBSER:
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) { if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance], serial_instance++);
} }
break; break;
case RangeFinder_TYPE_ANALOG: case Type::ANALOG:
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
// note that analog will always come back as present if the pin is valid // note that analog will always come back as present if the pin is valid
if (AP_RangeFinder_analog::detect(params[instance])) { if (AP_RangeFinder_analog::detect(params[instance])) {
@ -490,44 +490,44 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
#endif #endif
break; break;
case RangeFinder_TYPE_NMEA: case Type::NMEA:
if (AP_RangeFinder_NMEA::detect(serial_instance)) { if (AP_RangeFinder_NMEA::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_NMEA(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_NMEA(state[instance], params[instance], serial_instance++);
} }
break; break;
case RangeFinder_TYPE_WASP: case Type::WASP:
if (AP_RangeFinder_Wasp::detect(serial_instance)) { if (AP_RangeFinder_Wasp::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_Wasp(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_Wasp(state[instance], params[instance], serial_instance++);
} }
break; break;
case RangeFinder_TYPE_BenewakeTF02: case Type::BenewakeTF02:
if (AP_RangeFinder_Benewake::detect(serial_instance)) { if (AP_RangeFinder_Benewake::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02); drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02);
} }
break; break;
case RangeFinder_TYPE_BenewakeTFmini: case Type::BenewakeTFmini:
if (AP_RangeFinder_Benewake::detect(serial_instance)) { if (AP_RangeFinder_Benewake::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini); drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini);
} }
break; break;
case RangeFinder_TYPE_BenewakeTF03: case Type::BenewakeTF03:
if (AP_RangeFinder_Benewake::detect(serial_instance)) { if (AP_RangeFinder_Benewake::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF03); drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF03);
} }
break; break;
case RangeFinder_TYPE_PWM: case Type::PWM:
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
if (AP_RangeFinder_PWM::detect()) { if (AP_RangeFinder_PWM::detect()) {
drivers[instance] = new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height); drivers[instance] = new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height);
} }
#endif #endif
break; break;
case RangeFinder_TYPE_BLPing: case Type::BLPing:
if (AP_RangeFinder_BLPing::detect(serial_instance)) { if (AP_RangeFinder_BLPing::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_BLPing(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_BLPing(state[instance], params[instance], serial_instance++);
} }
break; break;
case RangeFinder_TYPE_Lanbao: case Type::Lanbao:
if (AP_RangeFinder_Lanbao::detect(serial_instance)) { if (AP_RangeFinder_Lanbao::detect(serial_instance)) {
drivers[instance] = new AP_RangeFinder_Lanbao(state[instance], params[instance], serial_instance++); drivers[instance] = new AP_RangeFinder_Lanbao(state[instance], params[instance], serial_instance++);
} }
@ -548,7 +548,7 @@ AP_RangeFinder_Backend *RangeFinder::get_backend(uint8_t id) const {
return nullptr; return nullptr;
} }
if (drivers[id] != nullptr) { if (drivers[id] != nullptr) {
if (drivers[id]->type() == RangeFinder_TYPE_NONE) { if (drivers[id]->type() == Type::NONE) {
// pretend it isn't here; disabled at runtime? // pretend it isn't here; disabled at runtime?
return nullptr; return nullptr;
} }
@ -569,7 +569,7 @@ void RangeFinder::handle_msg(const mavlink_message_t &msg)
{ {
uint8_t i; uint8_t i;
for (i=0; i<num_instances; i++) { for (i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && (params[i].type != RangeFinder_TYPE_NONE)) { if ((drivers[i] != nullptr) && ((Type)params[i].type.get() != Type::NONE)) {
drivers[i]->handle_msg(msg); drivers[i]->handle_msg(msg);
} }
} }
@ -727,7 +727,7 @@ void RangeFinder::Log_RFND()
bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const
{ {
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if ((params[i].type != RangeFinder_TYPE_NONE) && (drivers[i] == nullptr)) { if (((Type)params[i].type.get() != Type::NONE) && (drivers[i] == nullptr)) {
hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %d was not detected", i + 1); hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %d was not detected", i + 1);
return false; return false;
} }

View File

@ -48,35 +48,35 @@ public:
RangeFinder &operator=(const RangeFinder&) = delete; RangeFinder &operator=(const RangeFinder&) = delete;
// RangeFinder driver types // RangeFinder driver types
enum RangeFinder_Type { enum class Type {
RangeFinder_TYPE_NONE = 0, NONE = 0,
RangeFinder_TYPE_ANALOG = 1, ANALOG = 1,
RangeFinder_TYPE_MBI2C = 2, MBI2C = 2,
RangeFinder_TYPE_PLI2C = 3, PLI2C = 3,
RangeFinder_TYPE_PX4 = 4, PX4 = 4,
RangeFinder_TYPE_PX4_PWM= 5, PX4_PWM= 5,
RangeFinder_TYPE_BBB_PRU= 6, BBB_PRU= 6,
RangeFinder_TYPE_LWI2C = 7, LWI2C = 7,
RangeFinder_TYPE_LWSER = 8, LWSER = 8,
RangeFinder_TYPE_BEBOP = 9, BEBOP = 9,
RangeFinder_TYPE_MAVLink = 10, MAVLink = 10,
RangeFinder_TYPE_ULANDING= 11, ULANDING= 11,
RangeFinder_TYPE_LEDDARONE = 12, LEDDARONE = 12,
RangeFinder_TYPE_MBSER = 13, MBSER = 13,
RangeFinder_TYPE_TRI2C = 14, TRI2C = 14,
RangeFinder_TYPE_PLI2CV3= 15, PLI2CV3= 15,
RangeFinder_TYPE_VL53L0X = 16, VL53L0X = 16,
RangeFinder_TYPE_NMEA = 17, NMEA = 17,
RangeFinder_TYPE_WASP = 18, WASP = 18,
RangeFinder_TYPE_BenewakeTF02 = 19, BenewakeTF02 = 19,
RangeFinder_TYPE_BenewakeTFmini = 20, BenewakeTFmini = 20,
RangeFinder_TYPE_PLI2CV3HP = 21, PLI2CV3HP = 21,
RangeFinder_TYPE_PWM = 22, PWM = 22,
RangeFinder_TYPE_BLPing = 23, BLPing = 23,
RangeFinder_TYPE_UAVCAN = 24, UAVCAN = 24,
RangeFinder_TYPE_BenewakeTFminiPlus = 25, BenewakeTFminiPlus = 25,
RangeFinder_TYPE_Lanbao = 26, Lanbao = 26,
RangeFinder_TYPE_BenewakeTF03 = 27, BenewakeTF03 = 27,
}; };
enum RangeFinder_Function { enum RangeFinder_Function {

View File

@ -28,18 +28,18 @@ AP_RangeFinder_Backend::AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_
state(_state), state(_state),
params(_params) params(_params)
{ {
_backend_type = (RangeFinder::RangeFinder_Type)params.type.get(); _backend_type = type();
} }
MAV_DISTANCE_SENSOR AP_RangeFinder_Backend::get_mav_distance_sensor_type() const { MAV_DISTANCE_SENSOR AP_RangeFinder_Backend::get_mav_distance_sensor_type() const {
if (params.type == RangeFinder::RangeFinder_TYPE_NONE) { if (type() == RangeFinder::Type::NONE) {
return MAV_DISTANCE_SENSOR_UNKNOWN; return MAV_DISTANCE_SENSOR_UNKNOWN;
} }
return _get_mav_distance_sensor_type(); return _get_mav_distance_sensor_type();
} }
RangeFinder::RangeFinder_Status AP_RangeFinder_Backend::status() const { RangeFinder::RangeFinder_Status AP_RangeFinder_Backend::status() const {
if (params.type == RangeFinder::RangeFinder_TYPE_NONE) { if (type() == RangeFinder::Type::NONE) {
// turned off at runtime? // turned off at runtime?
return RangeFinder::RangeFinder_NotConnected; return RangeFinder::RangeFinder_NotConnected;
} }

View File

@ -41,7 +41,7 @@ public:
int16_t ground_clearance_cm() const { return params.ground_clearance_cm; } int16_t ground_clearance_cm() const { return params.ground_clearance_cm; }
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const; MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const;
RangeFinder::RangeFinder_Status status() const; RangeFinder::RangeFinder_Status status() const;
RangeFinder::RangeFinder_Type type() const { return (RangeFinder::RangeFinder_Type)params.type.get(); } RangeFinder::Type type() const { return (RangeFinder::Type)params.type.get(); }
// true if sensor is returning data // true if sensor is returning data
bool has_data() const; bool has_data() const;
@ -71,7 +71,7 @@ protected:
HAL_Semaphore _sem; HAL_Semaphore _sem;
//Type Backend initialised with //Type Backend initialised with
RangeFinder::RangeFinder_Type _backend_type; RangeFinder::Type _backend_type;
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0; virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0;
}; };

View File

@ -19,7 +19,7 @@ void setup()
hal.console->printf("Range Finder library test\n"); hal.console->printf("Range Finder library test\n");
// setup for analog pin 13 // setup for analog pin 13
AP_Param::set_object_value(&sonar, sonar.var_info, "_TYPE", RangeFinder::RangeFinder_TYPE_PLI2C); AP_Param::set_object_value(&sonar, sonar.var_info, "_TYPE", (uint8_t)RangeFinder::Type::PLI2C);
AP_Param::set_object_value(&sonar, sonar.var_info, "_PIN", -1.0f); AP_Param::set_object_value(&sonar, sonar.var_info, "_PIN", -1.0f);
AP_Param::set_object_value(&sonar, sonar.var_info, "_SCALING", 1.0f); AP_Param::set_object_value(&sonar, sonar.var_info, "_SCALING", 1.0f);