mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: AK8963: Rename some SPI/I2C method parameters
On read/write operations the argument is the register that will be read or write not the address, SPI don't even have the concept of device address.
This commit is contained in:
parent
3d7ec3704d
commit
a9d34ac3bd
|
@ -167,7 +167,7 @@ bool AP_Compass_AK8963::init()
|
|||
}
|
||||
|
||||
if (!_bus->start_measurements()) {
|
||||
hal.console->printf("AK8963: Could not start measurments\n");
|
||||
hal.console->printf("AK8963: Could not start measurements\n");
|
||||
goto fail;
|
||||
}
|
||||
|
||||
|
@ -412,41 +412,41 @@ AP_AK8963_SerialBus_MPU9250::AP_AK8963_SerialBus_MPU9250()
|
|||
}
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_MPU9250::register_write(uint8_t address, uint8_t value)
|
||||
void AP_AK8963_SerialBus_MPU9250::register_write(uint8_t reg, uint8_t value)
|
||||
{
|
||||
const uint8_t count = 1;
|
||||
_write(MPUREG_I2C_SLV0_ADDR, AK8963_I2C_ADDR);
|
||||
_write(MPUREG_I2C_SLV0_REG, address);
|
||||
_write(MPUREG_I2C_SLV0_REG, reg);
|
||||
_write(MPUREG_I2C_SLV0_DO, value);
|
||||
_write(MPUREG_I2C_SLV0_CTRL, I2C_SLV0_EN | count);
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_MPU9250::register_read(uint8_t address, uint8_t *value, uint8_t count)
|
||||
void AP_AK8963_SerialBus_MPU9250::register_read(uint8_t reg, uint8_t *value, uint8_t count)
|
||||
{
|
||||
_write(MPUREG_I2C_SLV0_ADDR, AK8963_I2C_ADDR | READ_FLAG);
|
||||
_write(MPUREG_I2C_SLV0_REG, address);
|
||||
_write(MPUREG_I2C_SLV0_REG, reg);
|
||||
_write(MPUREG_I2C_SLV0_CTRL, I2C_SLV0_EN | count);
|
||||
|
||||
hal.scheduler->delay(10);
|
||||
_read(MPUREG_EXT_SENS_DATA_00, value, count);
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_MPU9250::_read(uint8_t address, uint8_t *buf, uint32_t count)
|
||||
void AP_AK8963_SerialBus_MPU9250::_read(uint8_t reg, uint8_t *buf, uint32_t count)
|
||||
{
|
||||
ASSERT(count < 32);
|
||||
|
||||
address |= READ_FLAG;
|
||||
uint8_t tx[32] = { address, };
|
||||
reg |= READ_FLAG;
|
||||
uint8_t tx[32] = { reg, };
|
||||
uint8_t rx[32] = { };
|
||||
|
||||
_spi->transaction(tx, rx, count + 1);
|
||||
memcpy(buf, rx + 1, count);
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_MPU9250::_write(uint8_t address, const uint8_t *buf, uint32_t count)
|
||||
void AP_AK8963_SerialBus_MPU9250::_write(uint8_t reg, const uint8_t *buf, uint32_t count)
|
||||
{
|
||||
ASSERT(count < 2);
|
||||
uint8_t tx[2] = { address, };
|
||||
uint8_t tx[2] = { reg, };
|
||||
|
||||
memcpy(tx+1, buf, count);
|
||||
_spi->transaction(tx, NULL, count + 1);
|
||||
|
@ -506,14 +506,14 @@ AP_AK8963_SerialBus_I2C::AP_AK8963_SerialBus_I2C(AP_HAL::I2CDriver *i2c, uint8_t
|
|||
{
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_I2C::register_write(uint8_t address, uint8_t value)
|
||||
void AP_AK8963_SerialBus_I2C::register_write(uint8_t reg, uint8_t value)
|
||||
{
|
||||
_i2c->writeRegister(_addr, address, value);
|
||||
_i2c->writeRegister(_addr, reg, value);
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_I2C::register_read(uint8_t address, uint8_t *value, uint8_t count)
|
||||
void AP_AK8963_SerialBus_I2C::register_read(uint8_t reg, uint8_t *value, uint8_t count)
|
||||
{
|
||||
_i2c->readRegisters(_addr, address, count, value);
|
||||
_i2c->readRegisters(_addr, reg, count, value);
|
||||
}
|
||||
|
||||
void AP_AK8963_SerialBus_I2C::read_raw(struct raw_value *rv)
|
||||
|
|
|
@ -18,13 +18,13 @@ public:
|
|||
};
|
||||
|
||||
virtual ~AP_AK8963_SerialBus() { }
|
||||
virtual void register_read(uint8_t address, uint8_t *value, uint8_t count) = 0;
|
||||
uint8_t register_read(uint8_t address) {
|
||||
uint8_t reg;
|
||||
register_read(address, ®, 1);
|
||||
return reg;
|
||||
virtual void register_read(uint8_t reg, uint8_t *value, uint8_t count) = 0;
|
||||
uint8_t register_read(uint8_t reg) {
|
||||
uint8_t value;
|
||||
register_read(reg, &value, 1);
|
||||
return value;
|
||||
}
|
||||
virtual void register_write(uint8_t address, uint8_t value) = 0;
|
||||
virtual void register_write(uint8_t reg, uint8_t value) = 0;
|
||||
virtual AP_HAL::Semaphore* get_semaphore() = 0;
|
||||
virtual bool configure() = 0;
|
||||
virtual bool start_measurements() = 0;
|
||||
|
@ -86,18 +86,18 @@ class AP_AK8963_SerialBus_MPU9250: public AP_AK8963_SerialBus
|
|||
{
|
||||
public:
|
||||
AP_AK8963_SerialBus_MPU9250();
|
||||
void register_read(uint8_t address, uint8_t *value, uint8_t count);
|
||||
void register_write(uint8_t address, uint8_t value);
|
||||
void register_read(uint8_t reg, uint8_t *value, uint8_t count);
|
||||
void register_write(uint8_t reg, uint8_t value);
|
||||
AP_HAL::Semaphore* get_semaphore();
|
||||
bool configure();
|
||||
bool start_measurements();
|
||||
void read_raw(struct raw_value *rv);
|
||||
uint32_t get_dev_id();
|
||||
private:
|
||||
void _read(uint8_t address, uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t address, const uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t address, const uint8_t value) {
|
||||
_write(address, &value, 1);
|
||||
void _read(uint8_t reg, uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t reg, const uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t reg, const uint8_t value) {
|
||||
_write(reg, &value, 1);
|
||||
}
|
||||
AP_HAL::SPIDeviceDriver *_spi;
|
||||
AP_HAL::Semaphore *_spi_sem;
|
||||
|
@ -107,18 +107,18 @@ class AP_AK8963_SerialBus_I2C: public AP_AK8963_SerialBus
|
|||
{
|
||||
public:
|
||||
AP_AK8963_SerialBus_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr);
|
||||
void register_read(uint8_t address, uint8_t *value, uint8_t count);
|
||||
void register_write(uint8_t address, uint8_t value);
|
||||
void register_read(uint8_t reg, uint8_t *value, uint8_t count);
|
||||
void register_write(uint8_t reg, uint8_t value);
|
||||
AP_HAL::Semaphore* get_semaphore();
|
||||
bool configure(){ return true; }
|
||||
bool start_measurements() { return true; }
|
||||
void read_raw(struct raw_value *rv);
|
||||
uint32_t get_dev_id();
|
||||
private:
|
||||
void _read(uint8_t address, uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t address, const uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t address, const uint8_t value) {
|
||||
_write(address, &value, 1);
|
||||
void _read(uint8_t reg, uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t reg, const uint8_t *value, uint32_t count);
|
||||
void _write(uint8_t reg, const uint8_t value) {
|
||||
_write(reg, &value, 1);
|
||||
}
|
||||
AP_HAL::I2CDriver *_i2c;
|
||||
AP_HAL::Semaphore *_i2c_sem;
|
||||
|
|
Loading…
Reference in New Issue