mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_HAL_FLYMAPLE: SPI: adapt to the new signature of transaction()
A default behaviour was added here.
This commit is contained in:
parent
4e27d19107
commit
458f587656
@ -48,7 +48,7 @@ AP_HAL::Semaphore* FLYMAPLESPIDeviceDriver::get_semaphore()
|
||||
return &_semaphore;
|
||||
}
|
||||
|
||||
void FLYMAPLESPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
bool FLYMAPLESPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
{
|
||||
cs_assert();
|
||||
if (rx == NULL) {
|
||||
@ -61,6 +61,7 @@ void FLYMAPLESPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16
|
||||
}
|
||||
}
|
||||
cs_release();
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
|
@ -29,7 +29,7 @@ public:
|
||||
FLYMAPLESPIDeviceDriver();
|
||||
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