AP_HAL_AVR: SPI: adapt to the new signature of transaction()
A default behaviour was added here.
This commit is contained in:
parent
4af2a9a9cc
commit
93f5abb274
@ -109,7 +109,7 @@ void AVRSPI0DeviceDriver::transfer(const uint8_t *tx, uint16_t len) {
|
||||
}
|
||||
}
|
||||
|
||||
void AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
bool AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
uint16_t len) {
|
||||
_cs_assert();
|
||||
if (rx == NULL) {
|
||||
@ -128,6 +128,7 @@ void AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
}
|
||||
}
|
||||
_cs_release();
|
||||
return true;
|
||||
}
|
||||
|
||||
void AVRSPI0DeviceDriver::cs_assert() {
|
||||
|
@ -97,7 +97,7 @@ void AVRSPI2DeviceDriver::_transfer17(const uint8_t *tx, uint8_t *rx)
|
||||
TRANSFER1(16);
|
||||
}
|
||||
|
||||
void AVRSPI2DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
bool AVRSPI2DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
uint16_t len) {
|
||||
_cs_assert();
|
||||
if (rx == NULL) {
|
||||
@ -116,6 +116,7 @@ void AVRSPI2DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
}
|
||||
}
|
||||
_cs_release();
|
||||
return true;
|
||||
}
|
||||
|
||||
void AVRSPI2DeviceDriver::cs_assert() {
|
||||
|
@ -91,7 +91,7 @@ void AVRSPI3DeviceDriver::_transfer(const uint8_t *data, uint16_t len) {
|
||||
}
|
||||
}
|
||||
|
||||
void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
bool AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
uint16_t len) {
|
||||
_cs_assert();
|
||||
if (rx == NULL) {
|
||||
@ -102,6 +102,7 @@ void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
||||
}
|
||||
}
|
||||
_cs_release();
|
||||
return true;
|
||||
}
|
||||
|
||||
void AVRSPI3DeviceDriver::cs_assert() {
|
||||
|
@ -23,7 +23,7 @@ public:
|
||||
void init();
|
||||
AP_HAL::Semaphore* get_semaphore();
|
||||
|
||||
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
void cs_assert();
|
||||
void cs_release();
|
||||
@ -64,7 +64,7 @@ public:
|
||||
void init();
|
||||
AP_HAL::Semaphore* get_semaphore();
|
||||
|
||||
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
void cs_assert();
|
||||
void cs_release();
|
||||
@ -100,7 +100,7 @@ public:
|
||||
void init();
|
||||
AP_HAL::Semaphore* get_semaphore();
|
||||
|
||||
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
void cs_assert();
|
||||
void cs_release();
|
||||
|
Loading…
Reference in New Issue
Block a user