Move FY90q acc/gyro code to accgyro_fy90q.c. Update ADC drivers so they

do not include "board.h". It is now clear what all ADC drivers need to
compile and what was unnecessarily included before.

Note: FY90Q make target now compiles successfully, it was broken for
various reasons before.
This commit is contained in:
Dominic Clifton 2014-04-16 18:19:56 +01:00
parent 5442f8ea41
commit 001de4cdf3
10 changed files with 139 additions and 83 deletions

View File

@ -61,7 +61,6 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
drivers/bus_i2c_soft.c \ drivers/bus_i2c_soft.c \
drivers/gpio_common.c \ drivers/gpio_common.c \
drivers/serial_common.c \ drivers/serial_common.c \
drivers/serial_softserial.c \
drivers/serial_uart.c \ drivers/serial_uart.c \
drivers/system_common.c \ drivers/system_common.c \
flight_imu.c \ flight_imu.c \
@ -94,12 +93,15 @@ NAZE_SRC = drivers/accgyro_adxl345.c \
drivers/light_ledring.c \ drivers/light_ledring.c \
drivers/sonar_hcsr04.c \ drivers/sonar_hcsr04.c \
drivers/pwm_common.c \ drivers/pwm_common.c \
drivers/serial_softserial.c \
drivers/timer_common.c \ drivers/timer_common.c \
$(COMMON_SRC) $(COMMON_SRC)
# Source files for the FY90Q target # Source files for the FY90Q target
FY90Q_SRC = drivers/adc_fy90q.c \ FY90Q_SRC = drivers/accgyro_fy90q.c \
drivers/adc_fy90q.c \
drivers/pwm_fy90q.c \ drivers/pwm_fy90q.c \
drivers/bus_spi.c \
$(COMMON_SRC) $(COMMON_SRC)
# Source files for the OLIMEXINO target # Source files for the OLIMEXINO target
@ -110,6 +112,7 @@ OLIMEXINO_SRC = drivers/accgyro_adxl345.c \
drivers/adc_common.c \ drivers/adc_common.c \
drivers/bus_spi.c \ drivers/bus_spi.c \
drivers/pwm_common.c \ drivers/pwm_common.c \
drivers/serial_softserial.c \
drivers/timer_common.c \ drivers/timer_common.c \
$(COMMON_SRC) $(COMMON_SRC)

View File

@ -233,10 +233,14 @@ typedef struct baro_t
#ifdef FY90Q #ifdef FY90Q
// FY90Q // FY90Q
#include "drivers/adc/drv_adc.h" #include "drivers/adc_common.h"
#include "drv_i2c.h" #include "drivers/adc_fy90q.h"
#include "drv_pwm.h" #include "drivers/bus_i2c.h"
#include "drivers/serial/drv_uart.h" #include "drivers/bus_spi.h"
#include "drivers/pwm_common.h"
#include "drivers/timer_common.h"
#include "drivers/serial_common.h"
#include "drivers/serial_uart.h"
#else #else
#ifdef OLIMEXINO #ifdef OLIMEXINO

View File

@ -0,0 +1,72 @@
#ifdef FY90Q
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "accgyro_common.h"
#include "sensors_common.h"
#include "system_common.h"
#include "adc_fy90q.h"
//#include "boardalignment.h"
extern uint16_t acc_1G;
static void adcAccRead(int16_t *accelData);
static void adcGyroRead(int16_t *gyroData);
static void adcDummyInit(sensor_align_e align);
void adcSensorInit(sensor_t *acc, sensor_t *gyro)
{
acc->init = adcDummyInit;
acc->read = adcAccRead;
gyro->init = adcDummyInit;
gyro->read = adcGyroRead;
gyro->scale = 1.0f;
acc_1G = 376;
}
static void adcAccRead(int16_t *accelData)
{
// ADXL335
// 300mV/g
// Vcc 3.0V
accelData[0] = adcData[3];
accelData[1] = adcData[4];
accelData[2] = adcData[5];
}
static void adcGyroRead(int16_t *gyroData)
{
// Vcc: 3.0V
// Pitch/Roll: LPR550AL, 2000dps mode.
// 0.5mV/dps
// Zero-rate: 1.23V
// Yaw: LPY550AL, 2000dps mode.
// 0.5mV/dps
// Zero-rate: 1.23V
// Need to match with: 14.375lsb per dps
// 12-bit ADC
gyroData[0] = adcData[0] * 2;
gyroData[1] = adcData[1] * 2;
gyroData[2] = adcData[2] * 2;
}
static void adcDummyInit(sensor_align_e align)
{
// nothing to init here
}
uint16_t adcGetBattery(void)
{
return 0;
}
#endif

View File

@ -5,10 +5,7 @@
#include "accgyro_common.h" #include "accgyro_common.h"
#include "board.h" #include "adc_common.h"
#define ADC_BATTERY 0
#define ADC_CURRENT 1
// static volatile uint16_t adc1Ch4Value = 0; // static volatile uint16_t adc1Ch4Value = 0;
static volatile uint16_t adcValues[2]; static volatile uint16_t adcValues[2];

View File

@ -1,30 +1,20 @@
#ifdef FY90Q #ifdef FY90Q
#include "board.h"
#define ADC_CHANNELS 9 #include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "accgyro_common.h"
#include "sensors_common.h"
#include "system_common.h"
#include "adc_fy90q.h"
//#include "boardalignment.h"
volatile uint16_t adcData[ADC_CHANNELS] = { 0, }; volatile uint16_t adcData[ADC_CHANNELS] = { 0, };
extern uint16_t acc_1G;
static void adcAccRead(int16_t *accelData);
static void adcAccAlign(int16_t *accelData);
static void adcGyroRead(int16_t *gyroData);
static void adcGyroAlign(int16_t *gyroData);
static void adcDummyInit(void);
void adcSensorInit(sensor_t *acc, sensor_t *gyro)
{
acc->init = adcDummyInit;
acc->read = adcAccRead;
acc->align = adcAccAlign;
gyro->init = adcDummyInit;
gyro->read = adcGyroRead;
gyro->align = adcGyroAlign;
gyro->scale = 1.0f;
acc_1G = 376;
}
void adcCalibrateADC(ADC_TypeDef *ADCx, int n) void adcCalibrateADC(ADC_TypeDef *ADCx, int n)
{ {
@ -95,51 +85,9 @@ void adcInit(void)
ADC_SoftwareStartConvCmd(ADC1, ENABLE); ADC_SoftwareStartConvCmd(ADC1, ENABLE);
} }
static void adcAccRead(int16_t *accelData) uint16_t adcGetChannel(uint8_t channel)
{ {
// ADXL335 return 0; // Not Supported
// 300mV/g
// Vcc 3.0V
accelData[0] = adcData[3];
accelData[1] = adcData[4];
accelData[2] = adcData[5];
} }
static void adcAccAlign(int16_t *accelData)
{
// align OK
}
static void adcGyroRead(int16_t *gyroData)
{
// Vcc: 3.0V
// Pitch/Roll: LPR550AL, 2000dps mode.
// 0.5mV/dps
// Zero-rate: 1.23V
// Yaw: LPY550AL, 2000dps mode.
// 0.5mV/dps
// Zero-rate: 1.23V
// Need to match with: 14.375lsb per dps
// 12-bit ADC
gyroData[0] = adcData[0] * 2;
gyroData[1] = adcData[1] * 2;
gyroData[2] = adcData[2] * 2;
}
static void adcGyroAlign(int16_t *gyroData)
{
// align OK
}
static void adcDummyInit(void)
{
// nothing to init here
}
uint16_t adcGetBattery(void)
{
return 0;
}
#endif #endif

5
src/drivers/adc_fy90q.h Normal file
View File

@ -0,0 +1,5 @@
#pragma once
#define ADC_CHANNELS 9
extern volatile uint16_t adcData[ADC_CHANNELS];

View File

@ -1,5 +1,14 @@
#ifdef FY90Q #ifdef FY90Q
#include "board.h"
#include "stdbool.h"
#include "stdint.h"
#include "platform.h"
#include "serial_common.h"
#include "pwm_common.h"
static uint16_t failsafeThreshold = 985;
#define PULSE_1MS (1000) // 1ms pulse width #define PULSE_1MS (1000) // 1ms pulse width
// #define PULSE_PERIOD (2500) // pulse period (400Hz) // #define PULSE_PERIOD (2500) // pulse period (400Hz)
@ -71,7 +80,6 @@ static void ppmIRQHandler(TIM_TypeDef *tim)
if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) { if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) {
last = now; last = now;
now = TIM_GetCapture1(tim); now = TIM_GetCapture1(tim);
rcActive = true;
} }
TIM_ClearITPendingBit(tim, TIM_IT_CC1); TIM_ClearITPendingBit(tim, TIM_IT_CC1);
@ -87,7 +95,7 @@ static void ppmIRQHandler(TIM_TypeDef *tim)
} else { } else {
if (diff > 750 && diff < 2250 && chan < 8) { // 750 to 2250 ms is our 'valid' channel range if (diff > 750 && diff < 2250 && chan < 8) { // 750 to 2250 ms is our 'valid' channel range
Inputs[chan].capture = diff; Inputs[chan].capture = diff;
if (chan < 4 && diff > FAILSAFE_DETECT_TRESHOLD) if (chan < 4 && diff > failsafeThreshold)
GoodPulses |= (1 << chan); // if signal is valid - mark channel as OK GoodPulses |= (1 << chan); // if signal is valid - mark channel as OK
if (GoodPulses == 0x0F) { // If first four chanells have good pulses, clear FailSafe counter if (GoodPulses == 0x0F) { // If first four chanells have good pulses, clear FailSafe counter
GoodPulses = 0; GoodPulses = 0;
@ -203,7 +211,7 @@ static void pwmInitializeInput(bool usePPM)
TIM_ITConfig(TIM2, TIM_IT_CC1, ENABLE); TIM_ITConfig(TIM2, TIM_IT_CC1, ENABLE);
TIM_Cmd(TIM2, ENABLE); TIM_Cmd(TIM2, ENABLE);
// configure number of PWM outputs, in PPM mode, we use bottom 4 channels more more motors // configure number of PWM outputs, in PPM mode, we use bottom 4 channels for more motors
numOutputChannels = 10; numOutputChannels = 10;
} else { } else {
// Configure TIM2 all 4 channels // Configure TIM2 all 4 channels
@ -331,12 +339,17 @@ bool pwmInit(drv_pwm_config_t *init)
return false; return false;
} }
void pwmWrite(uint8_t channel, uint16_t value) void pwmWriteMotor(uint8_t channel, uint16_t value)
{ {
if (channel < numOutputChannels) if (channel < numOutputChannels)
*OutputChannels[channel] = value; *OutputChannels[channel] = value;
} }
void pwmWriteServo(uint8_t channel, uint16_t value)
{
// Not supported
}
uint16_t pwmRead(uint8_t channel) uint16_t pwmRead(uint8_t channel)
{ {
return Inputs[channel].capture; return Inputs[channel].capture;

View File

@ -148,6 +148,7 @@ int main(void)
serialInit(mcfg.serial_baudrate); serialInit(mcfg.serial_baudrate);
#ifndef FY90Q
if (feature(FEATURE_SOFTSERIAL)) { if (feature(FEATURE_SOFTSERIAL)) {
//mcfg.softserial_baudrate = 19200; // Uncomment to override config value //mcfg.softserial_baudrate = 19200; // Uncomment to override config value
@ -163,6 +164,7 @@ int main(void)
#endif #endif
//core.mainport = (serialPort_t*)&(softSerialPorts[0]); // Uncomment to switch the main port to use softserial. //core.mainport = (serialPort_t*)&(softSerialPorts[0]); // Uncomment to switch the main port to use softserial.
} }
#endif
if (feature(FEATURE_TELEMETRY)) if (feature(FEATURE_TELEMETRY))
initTelemetry(); initTelemetry();

View File

@ -58,7 +58,11 @@ static const char * const mixerNames[] = {
// sync this with AvailableFeatures enum from board.h // sync this with AvailableFeatures enum from board.h
static const char * const featureNames[] = { static const char * const featureNames[] = {
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP", "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS", "SERVO_TILT",
#ifndef FY90Q
"SOFTSERIAL",
#endif
"LED_RING", "GPS",
"FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D",
NULL NULL
}; };

View File

@ -46,14 +46,22 @@ void initTelemetry(void)
if (!feature(FEATURE_SOFTSERIAL)) if (!feature(FEATURE_SOFTSERIAL))
mcfg.telemetry_port = TELEMETRY_PORT_UART; mcfg.telemetry_port = TELEMETRY_PORT_UART;
#ifdef FY90Q
// FY90Q does not support softserial
mcfg.telemetry_port = TELEMETRY_PORT_UART;
core.telemport = core.mainport;
#endif
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration(); isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
#ifndef FY90Q
if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1) if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1)
core.telemport = &(softSerialPorts[0].port); core.telemport = &(softSerialPorts[0].port);
else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2) else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2)
core.telemport = &(softSerialPorts[1].port); core.telemport = &(softSerialPorts[1].port);
else else
core.telemport = core.mainport; core.telemport = core.mainport;
#endif
checkTelemetryState(); checkTelemetryState();
} }