Browse Source

AP_HAL_FLYMAPLE: SPI: adapt to the new signature of transaction()

A default behaviour was added here.
mission-4.1.18
Gustavo Jose de Sousa 10 years ago committed by Andrew Tridgell
parent
commit
458f587656
  1. 3
      libraries/AP_HAL_FLYMAPLE/SPIDriver.cpp
  2. 2
      libraries/AP_HAL_FLYMAPLE/SPIDriver.h

3
libraries/AP_HAL_FLYMAPLE/SPIDriver.cpp

@ -48,7 +48,7 @@ AP_HAL::Semaphore* FLYMAPLESPIDeviceDriver::get_semaphore() @@ -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 @@ -61,6 +61,7 @@ void FLYMAPLESPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16
}
}
cs_release();
return true;
}

2
libraries/AP_HAL_FLYMAPLE/SPIDriver.h

@ -29,7 +29,7 @@ public: @@ -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…
Cancel
Save