rename sensor_t to acc_t and gyro_t and remove unused variables from
each. relocated acc_t/gyro_t from sensors_common.h into drivers/accgyro_common.h since they define an interface and the dependency was pointing the wrong way from the drivers. baro_t/acc_t/gyro_t dependences are all now pointing the right way.
This commit is contained in:
parent
b3430ae1be
commit
8875aad776
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h"
|
||||||
#include "drivers/accgyro_common.h"
|
#include "drivers/accgyro_common.h"
|
||||||
#include "drivers/gpio_common.h"
|
#include "drivers/gpio_common.h"
|
||||||
#include "drivers/system_common.h"
|
#include "drivers/system_common.h"
|
||||||
|
|
|
@ -7,10 +7,12 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "flight_common.h"
|
#include "flight_common.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h"
|
||||||
|
|
||||||
|
#include "drivers/accgyro_common.h"
|
||||||
#include "drivers/system_common.h"
|
#include "drivers/system_common.h"
|
||||||
|
|
||||||
#include "statusindicator.h"
|
#include "statusindicator.h"
|
||||||
#include "sensors_common.h"
|
|
||||||
#include "sensors_acceleration.h"
|
#include "sensors_acceleration.h"
|
||||||
#include "telemetry_common.h"
|
#include "telemetry_common.h"
|
||||||
#include "gps_common.h"
|
#include "gps_common.h"
|
||||||
|
|
|
@ -3,9 +3,10 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
|
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
|
|
||||||
#include "sensors_common.h"
|
|
||||||
#include "system_common.h"
|
#include "system_common.h"
|
||||||
#include "bus_i2c.h"
|
#include "bus_i2c.h"
|
||||||
|
|
||||||
|
@ -48,7 +49,7 @@ static void adxl345Read(int16_t *accelData);
|
||||||
static bool useFifo = false;
|
static bool useFifo = false;
|
||||||
static sensor_align_e accAlign = CW270_DEG;
|
static sensor_align_e accAlign = CW270_DEG;
|
||||||
|
|
||||||
bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc)
|
bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc)
|
||||||
{
|
{
|
||||||
bool ack = false;
|
bool ack = false;
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
|
|
|
@ -5,4 +5,4 @@ typedef struct drv_adxl345_config_t {
|
||||||
uint16_t dataRate;
|
uint16_t dataRate;
|
||||||
} drv_adxl345_config_t;
|
} drv_adxl345_config_t;
|
||||||
|
|
||||||
bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc);
|
bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc);
|
||||||
|
|
|
@ -3,8 +3,8 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
#include <sensors_common.h>
|
|
||||||
|
|
||||||
#include "accgyro_bma280.h"
|
#include "accgyro_bma280.h"
|
||||||
|
|
||||||
|
@ -24,7 +24,7 @@ static void bma280Read(int16_t *accelData);
|
||||||
|
|
||||||
static sensor_align_e accAlign = CW0_DEG;
|
static sensor_align_e accAlign = CW0_DEG;
|
||||||
|
|
||||||
bool bma280Detect(sensor_t *acc)
|
bool bma280Detect(acc_t *acc)
|
||||||
{
|
{
|
||||||
bool ack = false;
|
bool ack = false;
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
|
|
|
@ -1,3 +1,3 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool bma280Detect(sensor_t *acc);
|
bool bma280Detect(acc_t *acc);
|
||||||
|
|
|
@ -1,3 +1,22 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
extern uint16_t acc_1G;
|
extern uint16_t acc_1G;
|
||||||
|
|
||||||
|
typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype
|
||||||
|
typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
||||||
|
|
||||||
|
typedef struct gyro_s
|
||||||
|
{
|
||||||
|
sensorInitFuncPtr init; // initialize function
|
||||||
|
sensorReadFuncPtr read; // read 3 axis data function
|
||||||
|
sensorReadFuncPtr temperature; // read temperature if available
|
||||||
|
float scale; // scalefactor
|
||||||
|
} gyro_t;
|
||||||
|
|
||||||
|
typedef struct acc_s
|
||||||
|
{
|
||||||
|
sensorInitFuncPtr init; // initialize function
|
||||||
|
sensorReadFuncPtr read; // read 3 axis data function
|
||||||
|
sensorReadFuncPtr temperature; // read temperature if available
|
||||||
|
char revisionCode; // a revision code for the sensor, if known
|
||||||
|
} acc_t;
|
||||||
|
|
|
@ -5,8 +5,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
#include "sensors_common.h"
|
|
||||||
|
|
||||||
#include "system_common.h"
|
#include "system_common.h"
|
||||||
|
|
||||||
|
|
|
@ -5,8 +5,8 @@
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
#include "sensors_common.h"
|
|
||||||
|
|
||||||
#include "accgyro_l3g4200d.h"
|
#include "accgyro_l3g4200d.h"
|
||||||
|
|
||||||
|
@ -47,7 +47,7 @@ static sensor_align_e gyroAlign = CW0_DEG;
|
||||||
static void l3g4200dInit(sensor_align_e align);
|
static void l3g4200dInit(sensor_align_e align);
|
||||||
static void l3g4200dRead(int16_t *gyroData);
|
static void l3g4200dRead(int16_t *gyroData);
|
||||||
|
|
||||||
bool l3g4200dDetect(sensor_t *gyro, uint16_t lpf)
|
bool l3g4200dDetect(gyro_t *gyro, uint16_t lpf)
|
||||||
{
|
{
|
||||||
uint8_t deviceid;
|
uint8_t deviceid;
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,3 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool l3g4200dDetect(sensor_t *gyro, uint16_t lpf);
|
bool l3g4200dDetect(gyro_t *gyro, uint16_t lpf);
|
||||||
|
|
|
@ -3,10 +3,11 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
|
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
#include "system_common.h"
|
#include "system_common.h"
|
||||||
#include "gpio_common.h"
|
#include "gpio_common.h"
|
||||||
#include "sensors_common.h"
|
|
||||||
|
|
||||||
#include "accgyro_mma845x.h"
|
#include "accgyro_mma845x.h"
|
||||||
|
|
||||||
|
@ -67,7 +68,7 @@ static sensor_align_e accAlign = CW90_DEG;
|
||||||
static void mma8452Init(sensor_align_e align);
|
static void mma8452Init(sensor_align_e align);
|
||||||
static void mma8452Read(int16_t *accelData);
|
static void mma8452Read(int16_t *accelData);
|
||||||
|
|
||||||
bool mma8452Detect(sensor_t *acc)
|
bool mma8452Detect(acc_t *acc)
|
||||||
{
|
{
|
||||||
bool ack = false;
|
bool ack = false;
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
|
|
|
@ -1,3 +1,3 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool mma8452Detect(sensor_t *acc);
|
bool mma8452Detect(acc_t *acc);
|
||||||
|
|
|
@ -5,11 +5,11 @@
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
|
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
#include "system_common.h"
|
#include "system_common.h"
|
||||||
|
|
||||||
#include "sensors_common.h"
|
|
||||||
|
|
||||||
#include "accgyro_mpu3050.h"
|
#include "accgyro_mpu3050.h"
|
||||||
|
|
||||||
#include "bus_i2c.h"
|
#include "bus_i2c.h"
|
||||||
|
@ -48,7 +48,7 @@ static void mpu3050Init(sensor_align_e align);
|
||||||
static void mpu3050Read(int16_t *gyroData);
|
static void mpu3050Read(int16_t *gyroData);
|
||||||
static void mpu3050ReadTemp(int16_t *tempData);
|
static void mpu3050ReadTemp(int16_t *tempData);
|
||||||
|
|
||||||
bool mpu3050Detect(sensor_t *gyro, uint16_t lpf)
|
bool mpu3050Detect(gyro_t *gyro, uint16_t lpf)
|
||||||
{
|
{
|
||||||
bool ack;
|
bool ack;
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,3 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool mpu3050Detect(sensor_t *gyro, uint16_t lpf);
|
bool mpu3050Detect(gyro_t *gyro, uint16_t lpf);
|
||||||
|
|
|
@ -5,11 +5,12 @@
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
|
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
#include "system_common.h"
|
#include "system_common.h"
|
||||||
#include "gpio_common.h"
|
#include "gpio_common.h"
|
||||||
|
|
||||||
#include "sensors_common.h"
|
|
||||||
|
|
||||||
#include "accgyro_mpu6050.h"
|
#include "accgyro_mpu6050.h"
|
||||||
|
|
||||||
|
@ -139,7 +140,7 @@ typedef enum {
|
||||||
|
|
||||||
static mpu6050Resolution_e mpuAccelTrim;
|
static mpu6050Resolution_e mpuAccelTrim;
|
||||||
|
|
||||||
bool mpu6050Detect(sensor_t *acc, sensor_t *gyro, uint16_t lpf)
|
bool mpu6050Detect(acc_t *acc, gyro_t *gyro, uint16_t lpf)
|
||||||
{
|
{
|
||||||
bool ack;
|
bool ack;
|
||||||
uint8_t sig, rev;
|
uint8_t sig, rev;
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint16_t lpf);
|
bool mpu6050Detect(acc_t * acc, gyro_t * gyro, uint16_t lpf);
|
||||||
void mpu6050DmpLoop(void);
|
void mpu6050DmpLoop(void);
|
||||||
void mpu6050DmpResetFifo(void);
|
void mpu6050DmpResetFifo(void);
|
||||||
|
|
|
@ -3,6 +3,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "sensors_common.h" // FIXME dependency into the main code
|
||||||
|
|
||||||
#include "accgyro_common.h"
|
#include "accgyro_common.h"
|
||||||
|
|
||||||
#include "adc_common.h"
|
#include "adc_common.h"
|
||||||
|
|
|
@ -5,13 +5,14 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
//
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "flight_common.h"
|
#include "flight_common.h"
|
||||||
//
|
|
||||||
#include "drivers/system_common.h"
|
#include "drivers/system_common.h"
|
||||||
//
|
|
||||||
#include "sensors_common.h"
|
#include "sensors_common.h"
|
||||||
|
#include "drivers/accgyro_common.h"
|
||||||
#include "sensors_gyro.h"
|
#include "sensors_gyro.h"
|
||||||
#include "sensors_compass.h"
|
#include "sensors_compass.h"
|
||||||
#include "sensors_acceleration.h"
|
#include "sensors_acceleration.h"
|
||||||
|
|
|
@ -7,6 +7,8 @@
|
||||||
|
|
||||||
#include "gps_common.h"
|
#include "gps_common.h"
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
|
#include "sensors_common.h"
|
||||||
|
#include "drivers/accgyro_common.h"
|
||||||
#include "drivers/serial_common.h"
|
#include "drivers/serial_common.h"
|
||||||
#include "telemetry_common.h"
|
#include "telemetry_common.h"
|
||||||
#include "boardalignment.h"
|
#include "boardalignment.h"
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
|
|
||||||
#include "sensors_acceleration.h"
|
#include "sensors_acceleration.h"
|
||||||
|
|
||||||
sensor_t acc; // acc access functions
|
acc_t acc; // acc access functions
|
||||||
uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
||||||
|
|
||||||
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
||||||
|
|
|
@ -11,7 +11,7 @@ typedef enum AccelSensors {
|
||||||
} AccelSensors;
|
} AccelSensors;
|
||||||
|
|
||||||
extern uint8_t accHardware;
|
extern uint8_t accHardware;
|
||||||
extern sensor_t acc;
|
extern acc_t acc;
|
||||||
|
|
||||||
void ACC_Common(void);
|
void ACC_Common(void);
|
||||||
void ACC_getADC(void);
|
void ACC_getADC(void);
|
||||||
|
|
|
@ -22,16 +22,4 @@ typedef enum {
|
||||||
CW270_DEG_FLIP = 8
|
CW270_DEG_FLIP = 8
|
||||||
} sensor_align_e;
|
} sensor_align_e;
|
||||||
|
|
||||||
typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype
|
|
||||||
typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
|
||||||
|
|
||||||
typedef struct sensor_t
|
|
||||||
{
|
|
||||||
sensorInitFuncPtr init; // initialize function
|
|
||||||
sensorReadFuncPtr read; // read 3 axis data function
|
|
||||||
sensorReadFuncPtr temperature; // read temperature if available
|
|
||||||
float scale; // scalefactor (currently used for gyro only, todo for accel)
|
|
||||||
char revisionCode; // a revision code for the sensor, if known
|
|
||||||
} sensor_t;
|
|
||||||
|
|
||||||
extern int16_t heading;
|
extern int16_t heading;
|
||||||
|
|
|
@ -8,7 +8,7 @@
|
||||||
|
|
||||||
uint16_t calibratingG = 0;
|
uint16_t calibratingG = 0;
|
||||||
uint16_t acc_1G = 256; // this is the 1G measured acceleration.
|
uint16_t acc_1G = 256; // this is the 1G measured acceleration.
|
||||||
sensor_t gyro; // gyro access functions
|
gyro_t gyro; // gyro access functions
|
||||||
|
|
||||||
void GYRO_Common(void)
|
void GYRO_Common(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
extern uint16_t acc_1G;
|
extern uint16_t acc_1G;
|
||||||
extern sensor_t gyro;
|
extern gyro_t gyro;
|
||||||
|
|
||||||
void GYRO_Common(void);
|
void GYRO_Common(void);
|
||||||
void Gyro_getADC(void);
|
void Gyro_getADC(void);
|
||||||
|
|
|
@ -13,9 +13,9 @@ extern uint16_t batteryWarningVoltage;
|
||||||
extern uint8_t batteryCellCount;
|
extern uint8_t batteryCellCount;
|
||||||
extern float magneticDeclination;
|
extern float magneticDeclination;
|
||||||
|
|
||||||
extern sensor_t gyro;
|
extern gyro_t gyro;
|
||||||
extern baro_t baro;
|
extern baro_t baro;
|
||||||
extern sensor_t acc;
|
extern acc_t acc;
|
||||||
|
|
||||||
#ifdef FY90Q
|
#ifdef FY90Q
|
||||||
// FY90Q analog gyro/acc
|
// FY90Q analog gyro/acc
|
||||||
|
|
Loading…
Reference in New Issue