AP_HAL: remove state leftover from SPIDeviceDriver

This was previously used to allow to save a state in a SPIDriver so we
could synchronize the initialization of AP_Compass and
AP_InertialSensor.

It was only used by MPU9250 and is not used anymore since the move to
AuxiliaryBus initialization and it's not used anymore since c3dae6f
("AP_InertialSensor: MPU9250: Remove methods not used anymore")
This commit is contained in:
Lucas De Marchi 2015-12-07 12:39:38 -02:00 committed by Andrew Tridgell
parent 27dafa8f1b
commit f69208d47d

View File

@ -38,15 +38,7 @@ public:
SPI_SPEED_LOW, SPI_SPEED_HIGH
};
enum class State : uint8_t {
UNKNOWN,
RUNNING,
FAILED,
};
virtual void set_bus_speed(enum bus_speed speed) {}
virtual void set_state(State state) { };
virtual State get_state() { return State::UNKNOWN; }
};
#endif // __AP_HAL_SPI_DRIVER_H__