Browse Source

MPU6000: minor fixes

the hardware functions should be private, and cs_pin should be uint8_t
master
Andrew Tridgell 13 years ago
parent
commit
18d26dc74e
  1. 4
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
  2. 8
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h

4
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

@ -64,7 +64,7 @@ @@ -64,7 +64,7 @@
#define BIT_I2C_IF_DIS 0x10
#define BIT_INT_STATUS_DATA 0x01
int AP_InertialSensor_MPU6000::_cs_pin;
uint8_t AP_InertialSensor_MPU6000::_cs_pin;
/* pch: by the data sheet, the gyro scale should be 16.4LSB per DPS
* Given the radians conversion factor (0.174532), the gyro scale factor
@ -90,7 +90,7 @@ const uint8_t AP_InertialSensor_MPU6000::_temp_data_index = 3; @@ -90,7 +90,7 @@ const uint8_t AP_InertialSensor_MPU6000::_temp_data_index = 3;
static volatile uint8_t _new_data;
AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000( int cs_pin )
AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000( uint8_t cs_pin )
{
_cs_pin = cs_pin; /* can't use initializer list, is static */
_gyro.x = 0;

8
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h

@ -14,7 +14,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor @@ -14,7 +14,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
{
public:
AP_InertialSensor_MPU6000( int cs_pin );
AP_InertialSensor_MPU6000( uint8_t cs_pin );
void init( AP_PeriodicProcess * scheduler );
@ -33,14 +33,14 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor @@ -33,14 +33,14 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
uint32_t sample_time();
void reset_sample_time();
private:
static void read(uint32_t);
static void data_interrupt(void);
static uint8_t register_read( uint8_t reg );
static void register_write( uint8_t reg, uint8_t val );
static void hardware_init();
private:
Vector3f _gyro;
Vector3f _accel;
float _temp;
@ -63,7 +63,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor @@ -63,7 +63,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
static int16_t _data[7];
/* TODO deprecate _cs_pin */
static int _cs_pin;
static uint8_t _cs_pin;
};
#endif // __AP_INERTIAL_SENSOR_MPU6000_H__

Loading…
Cancel
Save