Browse Source

AP_Baro: make AP_SerialBus::write() return success or failure for MS56XX

master
Gustavo Jose de Sousa 10 years ago committed by Andrew Tridgell
parent
commit
1f29e18375
  1. 7
      libraries/AP_Baro/AP_Baro_MS5611.cpp
  2. 6
      libraries/AP_Baro/AP_Baro_MS5611.h

7
libraries/AP_Baro/AP_Baro_MS5611.cpp

@ -76,10 +76,11 @@ uint32_t AP_SerialBus_SPI::read_24bits(uint8_t reg) @@ -76,10 +76,11 @@ uint32_t AP_SerialBus_SPI::read_24bits(uint8_t reg)
return (((uint32_t)rx[1])<<16) | (((uint32_t)rx[2])<<8) | ((uint32_t)rx[3]);
}
void AP_SerialBus_SPI::write(uint8_t reg)
bool AP_SerialBus_SPI::write(uint8_t reg)
{
uint8_t tx[1] = { reg };
_spi->transaction(tx, NULL, 1);
return true;
}
bool AP_SerialBus_SPI::sem_take_blocking()
@ -132,9 +133,9 @@ uint32_t AP_SerialBus_I2C::read_24bits(uint8_t reg) @@ -132,9 +133,9 @@ uint32_t AP_SerialBus_I2C::read_24bits(uint8_t reg)
return 0;
}
void AP_SerialBus_I2C::write(uint8_t reg)
bool AP_SerialBus_I2C::write(uint8_t reg)
{
_i2c->write(_addr, 1, &reg);
return _i2c->write(_addr, 1, &reg) == 0;
}
bool AP_SerialBus_I2C::sem_take_blocking()

6
libraries/AP_Baro/AP_Baro_MS5611.h

@ -20,7 +20,7 @@ public: @@ -20,7 +20,7 @@ public:
virtual uint32_t read_24bits(uint8_t reg) = 0;
/** Write to a register with no data. */
virtual void write(uint8_t reg) = 0;
virtual bool write(uint8_t reg) = 0;
/** Acquire the internal semaphore for this device.
* take_nonblocking should be used from the timer process,
@ -41,7 +41,7 @@ public: @@ -41,7 +41,7 @@ public:
uint16_t read_16bits(uint8_t reg);
uint32_t read_24bits(uint8_t reg);
uint32_t read_adc(uint8_t reg);
void write(uint8_t reg);
bool write(uint8_t reg);
bool sem_take_nonblocking();
bool sem_take_blocking();
void sem_give();
@ -61,7 +61,7 @@ public: @@ -61,7 +61,7 @@ public:
void init();
uint16_t read_16bits(uint8_t reg);
uint32_t read_24bits(uint8_t reg);
void write(uint8_t reg);
bool write(uint8_t reg);
bool sem_take_nonblocking();
bool sem_take_blocking();
void sem_give();

Loading…
Cancel
Save