Merge pull request #3353 from martinbudden/bf_bus_device

Moved busDevice_t out of sensor.h into bus.h
This commit is contained in:
Martin Budden 2017-06-25 13:30:43 +01:00 committed by GitHub
commit c96973ea49
11 changed files with 17 additions and 13 deletions

View File

@ -20,6 +20,7 @@
#include "platform.h" #include "platform.h"
#include "common/axis.h" #include "common/axis.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro/accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD) #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)

View File

@ -17,6 +17,7 @@
#pragma once #pragma once
#include "drivers/bus.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"

View File

@ -34,7 +34,7 @@
#pragma once #pragma once
#include "drivers/sensor.h" #include "drivers/bus.h"
enum pios_bmi160_orientation { // clockwise rotation from board forward enum pios_bmi160_orientation { // clockwise rotation from board forward
PIOS_BMI160_TOP_0DEG, PIOS_BMI160_TOP_0DEG,

View File

@ -16,7 +16,7 @@
*/ */
#pragma once #pragma once
#include "drivers/sensor.h" #include "drivers/bus.h"
#define ICM20689_WHO_AM_I_CONST (0x98) #define ICM20689_WHO_AM_I_CONST (0x98)
#define ICM20689_BIT_RESET (0x80) #define ICM20689_BIT_RESET (0x80)

View File

@ -1,7 +1,7 @@
#pragma once #pragma once
#include "drivers/sensor.h" #include "drivers/bus.h"
#define MPU6000_CONFIG 0x1A #define MPU6000_CONFIG 0x1A

View File

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "drivers/sensor.h" #include "drivers/bus.h"
uint8_t mpu6500SpiDetect(const busDevice_t *bus); uint8_t mpu6500SpiDetect(const busDevice_t *bus);

View File

@ -1,7 +1,7 @@
#pragma once #pragma once
#include "drivers/sensor.h" #include "drivers/bus.h"
#define mpu9250_CONFIG 0x1A #define mpu9250_CONFIG 0x1A

View File

@ -19,6 +19,14 @@
#include "platform.h" #include "platform.h"
#include "drivers/io_types.h"
typedef union busDevice_u {
struct deviceSpi_s {
IO_t csnPin;
} spi;
} busDevice_t;
#ifdef TARGET_BUS_INIT #ifdef TARGET_BUS_INIT
void targetBusInit(void); void targetBusInit(void);
#endif #endif

View File

@ -17,6 +17,7 @@
#pragma once #pragma once
#include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
typedef struct magDev_s { typedef struct magDev_s {

View File

@ -20,8 +20,6 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include "drivers/io_types.h"
typedef enum { typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1, CW0_DEG = 1,
@ -34,12 +32,6 @@ typedef enum {
CW270_DEG_FLIP = 8 CW270_DEG_FLIP = 8
} sensor_align_e; } sensor_align_e;
typedef union busDevice_t {
struct deviceSpi_s {
IO_t csnPin;
} spi;
} busDevice_t;
typedef bool (*sensorInitFuncPtr)(void); // sensor init prototype typedef bool (*sensorInitFuncPtr)(void); // sensor init prototype
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
typedef bool (*sensorInterruptFuncPtr)(void); typedef bool (*sensorInterruptFuncPtr)(void);

View File

@ -19,6 +19,7 @@
#include "common/axis.h" #include "common/axis.h"
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "drivers/bus.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
typedef enum { typedef enum {