mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_HAL: make SPIDeviceDriver::transaction() return success or failure
This commit is contained in:
parent
a6bdee076e
commit
e05928a7e8
@ -20,7 +20,7 @@ class AP_HAL::SPIDeviceDriver {
|
|||||||
public:
|
public:
|
||||||
virtual void init() = 0;
|
virtual void init() = 0;
|
||||||
virtual AP_HAL::Semaphore* get_semaphore() = 0;
|
virtual AP_HAL::Semaphore* get_semaphore() = 0;
|
||||||
virtual void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len) = 0;
|
virtual bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len) = 0;
|
||||||
|
|
||||||
virtual void cs_assert() = 0;
|
virtual void cs_assert() = 0;
|
||||||
virtual void cs_release() = 0;
|
virtual void cs_release() = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user