mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
MPU6k: update driver for new ap_proceduce prototype
This commit is contained in:
parent
8cc2b7669b
commit
cef1c4c558
@ -200,7 +200,7 @@ static int16_t spi_transfer_16(void)
|
|||||||
return (((int16_t)byte_H)<<8) | byte_L;
|
return (((int16_t)byte_H)<<8) | byte_L;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_InertialSensor_MPU6000::read()
|
void AP_InertialSensor_MPU6000::read(uint32_t )
|
||||||
{
|
{
|
||||||
// We start a multibyte SPI read of sensors
|
// We start a multibyte SPI read of sensors
|
||||||
byte addr = MPUREG_ACCEL_XOUT_H | 0x80; // Set most significant bit
|
byte addr = MPUREG_ACCEL_XOUT_H | 0x80; // Set most significant bit
|
||||||
|
@ -33,7 +33,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
|
|||||||
uint32_t sample_time();
|
uint32_t sample_time();
|
||||||
void reset_sample_time();
|
void reset_sample_time();
|
||||||
|
|
||||||
static void read();
|
static void read(uint32_t);
|
||||||
static uint8_t register_read( uint8_t reg );
|
static uint8_t register_read( uint8_t reg );
|
||||||
static void register_write( uint8_t reg, uint8_t val );
|
static void register_write( uint8_t reg, uint8_t val );
|
||||||
static void hardware_init();
|
static void hardware_init();
|
||||||
|
Loading…
Reference in New Issue
Block a user