AP_HAL_Linux: 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 7900359fac
commit 27dafa8f1b
1 changed files with 0 additions and 3 deletions

View File

@ -28,8 +28,6 @@ public:
uint8_t transfer (uint8_t data);
void transfer (const uint8_t *data, uint16_t len);
void set_bus_speed(enum bus_speed speed);
void set_state(State state) override { _state = state; }
State get_state() override { return _state; }
private:
uint16_t _bus;
@ -38,7 +36,6 @@ private:
AP_HAL::DigitalSource *_cs;
uint8_t _mode;
uint8_t _bitsPerWord;
State _state = State::UNKNOWN;
uint32_t _lowspeed;
uint32_t _highspeed;
uint32_t _speed;