AP_HAL: move set_retries() up to Device class

we really need set_retries() high during init for nearly all i2c
devices, and as many are written against the generic device class
moving it to the Device class makes this a lot easier. It is a NOP on
SPI.
This commit is contained in:
Andrew Tridgell 2016-12-01 15:00:02 +11:00
parent e735a56c82
commit 28a318145c
2 changed files with 3 additions and 3 deletions

View File

@ -235,6 +235,9 @@ public:
uint32_t get_bus_id_devtype(uint8_t devtype) {
return change_bus_id(get_bus_id(), devtype);
}
/* set number of retries on transfers */
virtual void set_retries(uint8_t retries) {};
protected:
uint8_t _read_flag = 0;

View File

@ -36,9 +36,6 @@ public:
*/
virtual void set_address(uint8_t address) = 0;
/* set number of retries on transfers */
virtual void set_retries(uint8_t retries) = 0;
/* Device implementation */
/* See Device::set_speed() */