mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_RangeFinder: disable some incompatible drivers for AP_Periph
This commit is contained in:
parent
2059c7bf20
commit
1bdac4811d
@ -391,11 +391,13 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
case RangeFinder_TYPE_PX4_PWM:
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
// to ease moving from PX4 to ChibiOS we'll lie a little about
|
||||
// the backend driver...
|
||||
if (AP_RangeFinder_PWM::detect()) {
|
||||
drivers[instance] = new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||
@ -429,9 +431,11 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
break;
|
||||
#endif
|
||||
case RangeFinder_TYPE_MAVLink:
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
if (AP_RangeFinder_MAVLink::detect()) {
|
||||
drivers[instance] = new AP_RangeFinder_MAVLink(state[instance], params[instance]);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case RangeFinder_TYPE_MBSER:
|
||||
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) {
|
||||
@ -439,10 +443,12 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_ANALOG:
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
// note that analog will always come back as present if the pin is valid
|
||||
if (AP_RangeFinder_analog::detect(params[instance])) {
|
||||
drivers[instance] = new AP_RangeFinder_analog(state[instance], params[instance]);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case RangeFinder_TYPE_NMEA:
|
||||
if (AP_RangeFinder_NMEA::detect(serial_instance)) {
|
||||
@ -470,9 +476,11 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_PWM:
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
if (AP_RangeFinder_PWM::detect()) {
|
||||
drivers[instance] = new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case RangeFinder_TYPE_BLPing:
|
||||
if (AP_RangeFinder_BLPing::detect(serial_instance)) {
|
||||
|
Loading…
Reference in New Issue
Block a user