AP_RangeFinder: Remove unneeded state member

This commit is contained in:
Michael du Breuil 2018-05-08 23:47:13 -07:00 committed by Francisco Ferreira
parent 03fc653e62
commit 9e551350a4
3 changed files with 0 additions and 11 deletions

View File

@ -659,7 +659,6 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
case RangeFinder_TYPE_PX4_PWM:
if (AP_RangeFinder_PX4_PWM::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_PX4_PWM(state[instance], _powersave_range, estimated_terrain_height);
}
break;
@ -667,26 +666,22 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
case RangeFinder_TYPE_BBB_PRU:
if (AP_RangeFinder_BBB_PRU::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance]);
}
break;
#endif
case RangeFinder_TYPE_LWSER:
if (AP_RangeFinder_LightWareSerial::detect(serial_manager, serial_instance)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], serial_manager, serial_instance++);
}
break;
case RangeFinder_TYPE_LEDDARONE:
if (AP_RangeFinder_LeddarOne::detect(serial_manager, serial_instance)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], serial_manager, serial_instance++);
}
break;
case RangeFinder_TYPE_ULANDING:
if (AP_RangeFinder_uLanding::detect(serial_manager, serial_instance)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_uLanding(state[instance], serial_manager, serial_instance++);
}
break;
@ -694,27 +689,23 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
case RangeFinder_TYPE_BEBOP:
if (AP_RangeFinder_Bebop::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_Bebop(state[instance]);
}
break;
#endif
case RangeFinder_TYPE_MAVLink:
if (AP_RangeFinder_MAVLink::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_MAVLink(state[instance]);
}
break;
case RangeFinder_TYPE_MBSER:
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_manager, serial_instance)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], serial_manager, serial_instance++);
}
break;
case RangeFinder_TYPE_ANALOG:
// note that analog will always come back as present if the pin is valid
if (AP_RangeFinder_analog::detect(state[instance])) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_analog(state[instance]);
}
break;

View File

@ -76,7 +76,6 @@ public:
// The RangeFinder_State structure is filled in by the backend driver
struct RangeFinder_State {
uint8_t instance; // the instance number of this RangeFinder
uint16_t distance_cm; // distance: in cm
uint16_t voltage_mv; // voltage in millivolts,
// if applicable, otherwise 0

View File

@ -35,7 +35,6 @@ public:
void update_pre_arm_check();
uint8_t instance() const { return state.instance; }
enum Rotation orientation() const { return (Rotation)state.orientation.get(); }
uint16_t distance_cm() const { return state.distance_cm; }
uint16_t voltage_mv() const { return state.voltage_mv; }