1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-12 19:10:27 +03:00

Olimexino removed

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-04-24 08:45:17 +02:00
parent dad24ac7f5
commit a9902a37cd
11 changed files with 4 additions and 351 deletions

View file

@ -29,12 +29,10 @@ doc_files=(
'Migrating from baseflight.md'
'Boards.md'
'Board - AlienFlight.md'
'Board - CC3D.md'
'Board - ChebuzzF3.md'
'Board - CJMCU.md'
'Board - ColibriRace.md'
'Board - Motolab.md'
'Board - Olimexino.md'
'Board - Paris Air Hero 32.md'
'Board - Sparky.md'
'Board - RMDO.md'

View file

@ -1,168 +0,0 @@
# Board - Olimexino
The Olimexino is a cheap and widely available development board
This board is not recommended for cleanflight development because many of the pins needed are not broken out to header pins. A better choice for development is the Port103R, EUSTM32F103RB (F1) or the STM32F3Discovery (F3).
## Connections
### RC Input
INPUT
PA0 CH1 - D2 - PWM1 / PPM
PA1 CH2 - D3 - PWM2 / PWM RSSI
PA2 CH3 - D1 - PWM3 / UART2 TX
PA3 CH4 - D0 - PWM4 / UART2 RX
PA6 CH5 - D12 - PWM5 / SOFTSERIAL1 RX
PA7 CH6 - D11 - PWM6 / SOFTSERIAL1 TX
PB0 CH7 - D27 - PWM7 / SOFTSERIAL2 RX
PB1 CH8 - D28 - PWM8 / SOFTSERIAL2 TX
### PWM Output
OUTPUT
PA8 CH1 - PWM9 - D6
PA11 CH2 - PWM10 - USBDM
PB6 CH3 - PWM11 - D5
PB7 CH4 - PWM12 - D9
PB8 CH5 - PWM13 - D14
PB9 CH6 - PWM14 - D24
## Olimexino Shield V1
Headers for a CP2102 for UART1
Top left
6 way header pinouts (left to right)
1 - N/C
2 - N/C
3 - N/C
4 - D7 - UART1 TX / CP2102 RX
5 - D8 - UART1 RX / CP2102 TX
6 - GND
Headers for PPM, RSSI, SoftSerial1 inputs and Motor outputs
Top centre
Top Row = GROUND
Middle Row = 5V
Bottom Row = Signals
Signal pinouts (left to right)
1 - D2 - PWM1 - PPM
2 - D3 - PWM2 - RSSI
3 - D11 - PWM6 - INPUT CH6 / SS1 TX
4 - D12 - PWM5 - INPUT CH5 / SS1 RX
5 - D5 - PWM11 - OUTPUT CH3
6 - D9 - PWM12 - OUTPUT CH4
7 - D14 - PWM13 - OUTPUT CH5
8 - D24 - PWM14 - OUTPUT CH6
SoftSerial 1 - Headers for FTDI
Top Right
6 way header pinouts (left to right)
1 - N/C
2 - D11 - SS1 or UART2 TX / FTDI RX
3 - D12 - SS1 or UART2 RX / FTDI TX
4 - N/C
5 - N/C
6 - GND
Top Right
3 way power selector header
1 - VIN
2 - 5V from FTDI
3 - N/C - Jumper Storage
Middle Left
3 way power selector header
1 - VIN
2 - 5V from CP2102
3 - N/C - Jumper Storage
Use either power selector to supply VIN from the serial port adapter sockets, ensure that both power selectors are not enabled at the same time.
One or both of the power selector jumpers MUST be in the jumper storage position.
HC-SR04 Rangefinder
Inner Middle Bottom Right
4 Header pins (top to bottom)
1 - VIN
2 - Trigger
3 - Echo
4 - GND
Serial IO & Serial Loopback
Bottom right
The header pins allows combinations of serial loopback and Serial IO. Any amount of connections or jumpers can be used at the same time.
Jumper positions
>< = Horizontal jumper
v = Vertical jumper
^
><- FTDI RX connected to SS1 TX
><- FTDI TX connected to SS1 RX
->< FTDI RX connected to UART2 TX
->< FTDI TX connected to UART2 RX
-v- FTDI LOOPBACK
-^-
v-- SS1 LOOPBACK
^--
--v UART2 LOOPBACK
--^
6 way header pinouts (top left to bottom right)
123
456
1 - SS 1 TX
2 - FTDI RX
3 - UART2 TX
4 - SS1 RX
5 - FTDI TX
6 - UART2 RX
Bottom Right
HoTT Telemetry port
When the HoTT enable jumper is on pins 2 and 3 then HoTT data can be received/transmitted on either
serial port depending on the placement of the Derial IO selection jumpers.
When not in use the HoTT enable jumper can be stored on pins 3 and 4
The HoTT telemetry is connected to the center pins (2 & 5) of the Serial IO header.
4 way header (left to right)
1 - HoTT Telemetry In/Out
2 - HoTT Enable Jumper
3 - HoTT Enable Jumper
4 - N/C - Jumper Storage

View file

@ -8,7 +8,7 @@ The sonar sensor is only used when the aircraft inclination angle (attitude) is
## Hardware
Currently the only supported sensor is the HCSR04 sensor.
Currently the only supported sensors is the HCSR04 sensor.
## Connections
@ -16,14 +16,4 @@ Target dependent
#### Constraints
Current meter cannot be used in conjunction with Parallel PWM and Sonar.
### Olimexino
| Trigger | Echo | Inline 1k resistors |
| ------------- | ------------- | ------------------- |
| PB0 / RC7 | PB1 / RC8 | YES (3.3v input) |
#### Constraints
Current meter cannot be used in conjunction with Sonar.
Target dependent

View file

@ -47,7 +47,7 @@ If you use cygwin to build the binaries then be sure to have configured your com
Create a new `GDB Hardware Debugging` launch configuration from the `Run` menu
It's important to have build the executable compiled with GDB debugging information first.
Select the appropriate .elf file (not hex file) - In these examples the target platform is an OLIMEXINO.
Select the appropriate .elf file (not hex file).
DISABLE auto-build

View file

@ -67,7 +67,7 @@ use `DEBUG=GDB` make argument.
You may find that if you compile all the files with debug information on that the program is too big to fit on the target device. If this happens you have some options:
* Compile all files without debug information (`make clean`, `make ...`), then re-save or `touch` the files you want to be able to step though and then run `make DEBUG=GDB`. This will then re-compile the files you're interested in debugging with debugging symbols and you will get a smaller binary file which should then fit on the device.
* You could use a development board such as an Olimexino or an EUSTM32F103RB, development boards often have more flash rom.
* You could use a development board such as an EUSTM32F103RB, development boards often have more flash rom.
## OSX

View file

@ -10,7 +10,6 @@ targets=("PUBLISHMETA=True" \
"TARGET=SPRACINGF3EVO" \
"TARGET=LUX_RACE" \
"TARGET=MOTOLAB" \
"TARGET=OLIMEXINO" \
"TARGET=PORT103R" \
"TARGET=RMDO" \
"TARGET=SPARKY" \

View file

@ -69,14 +69,6 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
int type = MAP_TO_NONE;
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
// PWM2 is connected to LED2 on the board and cannot be connected unless you cut LED2_E
if (timerIndex == PWM2) {
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
continue;
}
#endif
#ifdef STM32F10X
// skip UART2 ports
if (init->useUART2 && (timerHardwarePtr->tag == IO_TAG(PA2) || timerHardwarePtr->tag == IO_TAG(PA3))) {

View file

@ -309,12 +309,6 @@ void validateAndFixConfig(void)
}
#endif
#if defined(OLIMEXINO) && defined(USE_RANGEFINDER_HCSR04)
if ((rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) && feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
featureClear(FEATURE_CURRENT_METER);
}
#endif
#ifndef USE_PMW_SERVO_DRIVER
featureClear(FEATURE_PWM_SERVO_DRIVER);
#endif

View file

@ -1,42 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
};

View file

@ -1,94 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "OLI1" // Olimexino
//#define OLIMEXINO_UNCUT_LED1_E_JUMPER
//#define OLIMEXINO_UNCUT_LED2_E_JUMPER
#ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER
#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#endif
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
// "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit()
#define LED1 PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#endif
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_MPU6050
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_MPU6050
#define MPU6050_I2C_BUS BUS_I2C2
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
// #define USE_RANGEFINDER
// #define USE_RANGEFINDER_HCSR04
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define RANGEFINDER_HCSR04_ECHO_PIN PB1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define USE_UART1
#define USE_UART2
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4
#define SOFTSERIAL_1_RX_PIN PA6
#define SOFTSERIAL_1_TX_PIN PA7
#define SOFTSERIAL_2_RX_PIN PB0
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define USE_I2C_DEVICE_2
#define USE_ADC
#define ADC_CHANNEL_1_PIN PB1
#define ADC_CHANNEL_2_PIN PA4
#define ADC_CHANNEL_3_PIN PA1
#define ADC_CHANNEL_4_PIN PA5
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10
// IO - assuming all IOs on smt32f103rb LQFP64 package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -1,16 +0,0 @@
F1_TARGETS += $(TARGET)
FEATURES = HIGHEND
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_mag3110.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stdperiph.c