OLIMEXINO - Initial support for the OLIMEXINO board.

PWM and ADC configuration is the same as the naze32 for now.  Requires an accelerometer is connected via I2C2.

I2C signals SDA2 and SCL2 are on the UEXT header (Pins 6 and 5 respectively)
USART signals TX and RX are on the CON3/CON4 headers (TX = D7, RX = D8)

Onboard LEDs (LED1/LED2) working.
Buzzer support removed for now as it conflicted with PWM map and LEDs.
mma845x support disabled as it conflicted with an LED.
Relocated some NAZE specific comments.

Disabling PWM2 as an input as it conflicts with the yellow onboard LED2.
This commit is contained in:
Dominic Clifton 2013-04-06 21:35:29 +02:00
parent 98d0581ac2
commit 4da8accfc0
7 changed files with 73 additions and 24 deletions

View File

@ -14,7 +14,7 @@
# Things that the user might override on the commandline # Things that the user might override on the commandline
# #
# The target to build, must be one of NAZE or FY90Q # The target to build, must be one of NAZE, FY90Q OR OLIMEXINO
TARGET ?= NAZE TARGET ?= NAZE
# Compile-time options # Compile-time options
@ -24,7 +24,7 @@ OPTIONS ?=
# Things that need to be maintained as the source changes # Things that need to be maintained as the source changes
# #
VALID_TARGETS = NAZE FY90Q VALID_TARGETS = NAZE FY90Q OLIMEXINO
# Working directories # Working directories
ROOT = $(dir $(lastword $(MAKEFILE_LIST))) ROOT = $(dir $(lastword $(MAKEFILE_LIST)))
@ -76,6 +76,15 @@ FY90Q_SRC = drv_adc_fy90q.c \
drv_pwm_fy90q.c \ drv_pwm_fy90q.c \
$(COMMON_SRC) $(COMMON_SRC)
# Source files for the OLIMEXINO target
OLIMEXINO_SRC = drv_adc.c \
drv_adxl345.c \
drv_mpu3050.c \
drv_mpu6050.c \
drv_l3g4200d.c \
drv_pwm.c \
$(COMMON_SRC)
# Search path for baseflight sources # Search path for baseflight sources
VPATH := $(SRC_DIR):$(SRC_DIR)/baseflight_startups VPATH := $(SRC_DIR):$(SRC_DIR)/baseflight_startups

View File

@ -112,14 +112,34 @@ typedef struct baro_t
#define GYRO #define GYRO
#define ACC #define ACC
#else #define SENSORS_SET (SENSOR_ACC)
#endif
#ifdef OLIMEXINO
// OLIMEXINO
// LED2 is using one of the pwm pins (PWM2), so we must not use PWM2. @See pwmInit()
#define LED0_GPIO GPIOA
#define LED0_PIN GPIO_Pin_1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#define LED1_GPIO GPIOA
#define LED1_PIN GPIO_Pin_5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#define GYRO
#define ACC
#define SENSORS_SET (SENSOR_ACC)
#endif
#ifdef NAZE
// Afroflight32 // Afroflight32
#define LED0_GPIO GPIOB #define LED0_GPIO GPIOB
#define LED0_PIN GPIO_Pin_3 #define LED0_PIN GPIO_Pin_3 // PB3 (LED)
#define LED1_GPIO GPIOB #define LED1_GPIO GPIOB
#define LED1_PIN GPIO_Pin_4 #define LED1_PIN GPIO_Pin_4 // PB4 (LED)
#define BEEP_GPIO GPIOA #define BEEP_GPIO GPIOA
#define BEEP_PIN GPIO_Pin_12 #define BEEP_PIN GPIO_Pin_12 // PA12 (Buzzer)
#define BARO_GPIO GPIOC #define BARO_GPIO GPIOC
#define BARO_PIN GPIO_Pin_13 #define BARO_PIN GPIO_Pin_13
@ -129,6 +149,9 @@ typedef struct baro_t
#define BARO #define BARO
#define LEDRING #define LEDRING
#define SONAR #define SONAR
#define BUZZER
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
#endif #endif
@ -160,8 +183,22 @@ typedef struct baro_t
#include "drv_i2c.h" #include "drv_i2c.h"
#include "drv_pwm.h" #include "drv_pwm.h"
#include "drv_uart.h" #include "drv_uart.h"
#endif
#else #ifdef OLIMEXINO
// OLIMEXINO
#include "drv_system.h" // timers, delays, etc
#include "drv_adc.h"
#include "drv_i2c.h"
#include "drv_adxl345.h"
#include "drv_mpu3050.h"
#include "drv_mpu6050.h"
#include "drv_l3g4200d.h"
#include "drv_pwm.h"
#include "drv_uart.h"
#endif
#ifdef NAZE
// AfroFlight32 // AfroFlight32
#include "drv_system.h" // timers, delays, etc #include "drv_system.h" // timers, delays, etc
#include "drv_adc.h" #include "drv_adc.h"

View File

@ -75,6 +75,7 @@ static void mma8452Init(void)
GPIO_InitTypeDef GPIO_InitStructure; GPIO_InitTypeDef GPIO_InitStructure;
// PA5 - ACC_INT2 output on rev3/4 hardware // PA5 - ACC_INT2 output on rev3/4 hardware
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5; GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;

View File

@ -449,6 +449,12 @@ bool pwmInit(drv_pwm_config_t *init)
if (setup[i] == 0xFF) // terminator if (setup[i] == 0xFF) // terminator
break; break;
#ifdef OLIMEXINO
// PWM2 is connected to LED2 on the board and cannot be connected.
if (port == PWM2)
continue;
#endif
// skip UART ports for GPS // skip UART ports for GPS
if (init->useUART && (port == PWM3 || port == PWM4)) if (init->useUART && (port == PWM3 || port == PWM4))
continue; continue;

View File

@ -48,10 +48,10 @@ void systemInit(void)
uint32_t i; uint32_t i;
gpio_config_t gpio_cfg[] = { gpio_config_t gpio_cfg[] = {
{ LED0_GPIO, LED0_PIN, GPIO_Mode_Out_PP }, // PB3 (LED) { LED0_GPIO, LED0_PIN, GPIO_Mode_Out_PP },
{ LED1_GPIO, LED1_PIN, GPIO_Mode_Out_PP }, // PB4 (LED) { LED1_GPIO, LED1_PIN, GPIO_Mode_Out_PP },
#ifndef FY90Q #ifdef BUZZER
{ BEEP_GPIO, BEEP_PIN, GPIO_Mode_Out_OD }, // PA12 (Buzzer) { BEEP_GPIO, BEEP_PIN, GPIO_Mode_Out_OD },
#endif #endif
}; };
uint8_t gpio_count = sizeof(gpio_cfg) / sizeof(gpio_cfg[0]); uint8_t gpio_count = sizeof(gpio_cfg) / sizeof(gpio_cfg[0]);

View File

@ -58,13 +58,7 @@ int main(void)
adcInit(&adc_params); adcInit(&adc_params);
// We have these sensors // We have these sensors
#ifndef FY90Q sensorsSet(SENSORS_SET);
// AfroFlight32
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
#else
// FY90Q
sensorsSet(SENSOR_ACC);
#endif
mixerInit(); // this will set useServo var depending on mixer type mixerInit(); // this will set useServo var depending on mixer type
// when using airplane/wing mixer, servo/motor outputs are remapped // when using airplane/wing mixer, servo/motor outputs are remapped

View File

@ -67,12 +67,14 @@ retry:
break; break;
} }
; // fallthrough ; // fallthrough
#ifndef OLIMEXINO
case 3: // MMA8452 case 3: // MMA8452
if (mma8452Detect(&acc)) { if (mma8452Detect(&acc)) {
accHardware = ACC_MMA8452; accHardware = ACC_MMA8452;
if (mcfg.acc_hardware == ACC_MMA8452) if (mcfg.acc_hardware == ACC_MMA8452)
break; break;
} }
#endif
} }
// Found anything? Check if user fucked up or ACC is really missing. // Found anything? Check if user fucked up or ACC is really missing.