Updating accgyro files so they do not include "board.h". It is now

clear what all accgyro drivers need to compile and what was
unnecessarily included before.
This commit is contained in:
Dominic Clifton 2014-04-16 17:33:47 +01:00
parent c493a1579c
commit f75f7a7e17
21 changed files with 208 additions and 83 deletions

View File

@ -1,45 +1,25 @@
#pragma once /*
* This file is deprecated. All this code belongs elsewhere - create appropriate headers and include them.
*/
// for roundf() #pragma once
#define __USE_C99_MATH
#include <stdbool.h> #include <stdbool.h>
#include <stdlib.h> #include <stdlib.h>
#include <stdint.h> #include <stdint.h>
#define __USE_C99_MATH // for roundf()
#include <math.h> #include <math.h>
#include <ctype.h> #include <ctype.h>
#include <string.h> #include <string.h>
#include <stdio.h> #include <stdio.h>
#include "stm32f10x_conf.h" #include "platform.h"
#include "core_cm3.h" #include "drivers/accgyro_common.h"
#ifndef __CC_ARM
// only need this garbage on gcc
#define USE_LAME_PRINTF
#define PRINTF_LONG_SUPPORT
#include "printf.h"
#endif
#include "drivers/system_common.h" // timers, delays, etc
#include "drivers/gpio_common.h" #include "drivers/gpio_common.h"
#include "drivers/system_common.h"
#ifndef M_PI #include "sensors_common.h"
#define M_PI 3.14159265358979323846f
#endif /* M_PI */
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f
#define RAD (M_PI / 180.0f)
#define min(a, b) ((a) < (b) ? (a) : (b))
#define max(a, b) ((a) > (b) ? (a) : (b))
#define abs(x) ((x) > 0 ? (x) : -(x))
// Chip Unique ID on F103
#define U_ID_0 (*(uint32_t*)0x1FFFF7E8)
#define U_ID_1 (*(uint32_t*)0x1FFFF7EC)
#define U_ID_2 (*(uint32_t*)0x1FFFF7F0)
typedef enum { typedef enum {
SENSOR_GYRO = 1 << 0, // always present SENSOR_GYRO = 1 << 0, // always present
@ -117,24 +97,6 @@ typedef enum {
TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2 TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2
} TelemetryPort; } TelemetryPort;
typedef enum {
X = 0,
Y,
Z
} sensor_axis_e;
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;
enum { enum {
GYRO_UPDATED = 1 << 0, GYRO_UPDATED = 1 << 0,
ACC_UPDATED = 1 << 1, ACC_UPDATED = 1 << 1,
@ -151,22 +113,11 @@ typedef struct sensor_data_t
int updated; int updated;
} sensor_data_t; } sensor_data_t;
typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype
typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
typedef void (* baroOpFuncPtr)(void); // baro start operation typedef void (* baroOpFuncPtr)(void); // baro start operation
typedef void (* baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature) typedef void (* baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
typedef void (* serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data
typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype typedef void (* pidControllerFuncPtr)(void); // pid controller function 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)
} sensor_t;
typedef struct baro_t typedef struct baro_t
{ {
uint16_t ut_delay; uint16_t ut_delay;

View File

@ -1,4 +1,17 @@
#include "board.h" #include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "accgyro_common.h"
#include <sensors_common.h>
#include "accgyro_adxl345.h"
#include "system_common.h"
#include "bus_i2c.h"
#include "boardalignment.h"
// ADXL345, Alternative address mode 0x53 // ADXL345, Alternative address mode 0x53
#define ADXL345_ADDRESS 0x53 #define ADXL345_ADDRESS 0x53

View File

@ -1,4 +1,17 @@
#include "board.h" #include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "accgyro_common.h"
#include <sensors_common.h>
#include "accgyro_bma280.h"
#include "bus_i2c.h"
#include "boardalignment.h"
// BMA280, default I2C address mode 0x18 // BMA280, default I2C address mode 0x18
#define BMA280_ADDRESS 0x18 #define BMA280_ADDRESS 0x18

View File

@ -0,0 +1,13 @@
#pragma once
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;

View File

@ -1,4 +1,19 @@
#include "board.h" #include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "accgyro_common.h"
#include <sensors_common.h>
#include "accgyro_l3g4200d.h"
#include "system_common.h"
#include "bus_i2c.h"
#include "boardalignment.h"
#include "maths.h"
// L3G4200D, Standard address 0x68 // L3G4200D, Standard address 0x68
#define L3G4200D_ADDRESS 0x68 #define L3G4200D_ADDRESS 0x68

View File

@ -1,4 +1,18 @@
#include "board.h" #include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "accgyro_common.h"
#include "system_common.h"
#include "gpio_common.h"
#include "sensors_common.h"
#include "accgyro_mma845x.h"
#include "bus_i2c.h"
#include "boardalignment.h"
// MMA8452QT, Standard address 0x1C // MMA8452QT, Standard address 0x1C
// ACC_INT2 routed to PA5 // ACC_INT2 routed to PA5

View File

@ -1,4 +1,20 @@
#include "board.h" #include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "accgyro_common.h"
#include "system_common.h"
#include "sensors_common.h"
#include "accgyro_mpu3050.h"
#include "bus_i2c.h"
#include "boardalignment.h"
#include "maths.h"
// MPU3050, Standard address 0x68 // MPU3050, Standard address 0x68
#define MPU3050_ADDRESS 0x68 #define MPU3050_ADDRESS 0x68

View File

@ -1,4 +1,21 @@
#include "board.h" #include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "accgyro_common.h"
#include "system_common.h"
#include "gpio_common.h"
#include "sensors_common.h"
#include "accgyro_mpu6050.h"
#include "bus_i2c.h"
#include "boardalignment.h"
#include "maths.h"
// MPU6050, Standard address 0x68 // MPU6050, Standard address 0x68
// MPU_INT on PB13 on rev4 hardware // MPU_INT on PB13 on rev4 hardware

View File

@ -1,3 +1,10 @@
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "accgyro_common.h"
#include "board.h" #include "board.h"
#define ADC_BATTERY 0 #define ADC_BATTERY 0

View File

@ -1,5 +1,7 @@
#include "board.h" #include "board.h"
#include "maths.h"
// HMC5883L, default address 0x1E // HMC5883L, default address 0x1E
// PB12 connected to MAG_DRDY on rev4 hardware // PB12 connected to MAG_DRDY on rev4 hardware
// PC14 connected to MAG_DRDY on rev5 hardware // PC14 connected to MAG_DRDY on rev5 hardware

View File

@ -7,6 +7,8 @@ typedef enum portMode_t {
MODE_SBUS = 1 << 2, MODE_SBUS = 1 << 2,
} portMode_t; } portMode_t;
typedef void (* serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
typedef struct serialPort { typedef struct serialPort {
const struct serialPortVTable *vTable; const struct serialPortVTable *vTable;

View File

@ -5,6 +5,17 @@
#define sq(x) ((x)*(x)) #define sq(x) ((x)*(x))
#endif #endif
#ifndef M_PI
#define M_PI 3.14159265358979323846f
#endif /* M_PI */
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f
#define RAD (M_PI / 180.0f)
#define min(a, b) ((a) < (b) ? (a) : (b))
#define max(a, b) ((a) > (b) ? (a) : (b))
#define abs(x) ((x) > 0 ? (x) : -(x))
typedef struct stdev_t typedef struct stdev_t
{ {
float m_oldM, m_newM, m_oldS, m_newS; float m_oldM, m_newM, m_oldS, m_newS;

View File

@ -1,5 +1,7 @@
#pragma once #pragma once
#include "runtime_config.h"
/* for VBAT monitoring frequency */ /* for VBAT monitoring frequency */
#define VBATFREQ 6 // to read battery voltage - nth number of loop iterations #define VBATFREQ 6 // to read battery voltage - nth number of loop iterations
#define BARO_TAB_SIZE_MAX 48 #define BARO_TAB_SIZE_MAX 48
@ -293,17 +295,6 @@ typedef struct master_t {
uint8_t chk; // XOR checksum uint8_t chk; // XOR checksum
} master_t; } master_t;
// Core runtime settings
typedef struct core_t {
serialPort_t *mainport;
serialPort_t *gpsport;
serialPort_t *telemport;
serialPort_t *rcvrport;
uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver.
uint8_t numRCChannels; // number of rc channels as reported by current input driver
bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this
} core_t;
typedef struct flags_t { typedef struct flags_t {
uint8_t OK_TO_ARM; uint8_t OK_TO_ARM;
uint8_t ARMED; uint8_t ARMED;
@ -391,7 +382,6 @@ extern uint8_t GPS_svinfo_svid[16]; // Satellite ID
extern uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity extern uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength) extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
extern core_t core;
extern master_t mcfg; extern master_t mcfg;
extern config_t cfg; extern config_t cfg;
extern flags_t f; extern flags_t f;

10
src/platform.h Normal file
View File

@ -0,0 +1,10 @@
#pragma once
#include "stm32f10x_conf.h"
#include "core_cm3.h"
// Chip Unique ID on F103
#define U_ID_0 (*(uint32_t*)0x1FFFF7E8)
#define U_ID_1 (*(uint32_t*)0x1FFFF7EC)
#define U_ID_2 (*(uint32_t*)0x1FFFF7F0)

View File

@ -29,10 +29,22 @@
* OF SUCH DAMAGE. * OF SUCH DAMAGE.
*/ */
#include "board.h" #include <stdbool.h>
#include "mw.h" #include <stdint.h>
#include <stdarg.h>
#include "drivers/serial_common.h"
#include "runtime_config.h"
#include "printf_config.h"
#include "printf.h"
#ifdef PRINTF_LONG_SUPPORT
#include "typeconversion.h" #include "typeconversion.h"
#endif
#ifdef USE_LAME_PRINTF #ifdef USE_LAME_PRINTF

View File

@ -102,12 +102,9 @@ For further details see source code.
regs Kusti, 23.10.2004 regs Kusti, 23.10.2004
*/ */
#ifndef __TFP_PRINTF__ #ifndef __TFP_PRINTF__
#define __TFP_PRINTF__ #define __TFP_PRINTF__
#include <stdarg.h>
void init_printf(void *putp, void (*putf) (void *, char)); void init_printf(void *putp, void (*putf) (void *, char));
void tfp_printf(char *fmt, ...); void tfp_printf(char *fmt, ...);

6
src/printf_config.h Normal file
View File

@ -0,0 +1,6 @@
#pragma once
#ifndef __CC_ARM
#define USE_LAME_PRINTF
#define PRINTF_LONG_SUPPORT
#endif

12
src/runtime_config.h Normal file
View File

@ -0,0 +1,12 @@
// Core runtime settings
typedef struct core_t {
serialPort_t *mainport;
serialPort_t *gpsport;
serialPort_t *telemport;
serialPort_t *rcvrport;
uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver.
uint8_t numRCChannels; // number of rc channels as reported by current input driver
bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this
} core_t;
extern core_t core;

18
src/sensors_common.h Normal file
View File

@ -0,0 +1,18 @@
#pragma once
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)
} sensor_t;
typedef enum {
X = 0,
Y,
Z
} sensor_axis_e;

View File

@ -1,6 +1,11 @@
#include <stdarg.h>
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "printf.h"
// we unset this on 'exit' // we unset this on 'exit'
extern uint8_t cliMode; extern uint8_t cliMode;
static void cliAux(char *cmdline); static void cliAux(char *cmdline);

View File

@ -1,6 +1,7 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "printf_config.h"
#ifdef PRINTF_LONG_SUPPORT #ifdef PRINTF_LONG_SUPPORT
void uli2a(unsigned long int num, unsigned int base, int uc, char *bf) void uli2a(unsigned long int num, unsigned int base, int uc, char *bf)