Pawel Spychalski (DzikuVx)
7 years ago
7 changed files with 0 additions and 364 deletions
-
1fake_travis_build.sh
-
64src/main/target/CRAZEPONYMINI/target.c
-
93src/main/target/CRAZEPONYMINI/target.h_
-
10src/main/target/CRAZEPONYMINI/target.mk_
-
41src/main/target/PORT103R/target.c
-
129src/main/target/PORT103R/target.h
-
26src/main/target/PORT103R/target.mk_
@ -1,64 +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 uint16_t multiPPM[] = { |
|||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 (M2) |
|||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 (M3) |
|||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 (M1) |
|||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 (M4) |
|||
0xFFFF |
|||
}; |
|||
|
|||
const uint16_t multiPWM[] = { |
|||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 |
|||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 |
|||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 |
|||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 |
|||
0xFFFF |
|||
}; |
|||
|
|||
const uint16_t airPPM[] = { |
|||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 |
|||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 |
|||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 |
|||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 |
|||
0xFFFF |
|||
}; |
|||
|
|||
const uint16_t airPWM[] = { |
|||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 |
|||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 |
|||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 |
|||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 |
|||
0xFFFF |
|||
}; |
|||
|
|||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { |
|||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, }, // PWM1 - OUT1 |
|||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, }, // PWM2 - OUT2 |
|||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, }, // PWM3 - OUT3 |
|||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, }, // PWM4 - OUT4 |
|||
}; |
|||
|
@ -1,93 +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 "CPM1" // CrazePony MINI |
|||
|
|||
#define BRUSHED_MOTORS |
|||
|
|||
#define LED0 PA11 |
|||
#define LED1 PA8 |
|||
#define LED2 PB1 |
|||
|
|||
#define USE_ACC |
|||
#define USE_ACC_MPU6050 |
|||
|
|||
#define USE_GYRO |
|||
#define USE_GYRO_MPU6050 |
|||
|
|||
#define USE_BARO |
|||
#define USE_BARO_MS5611 |
|||
|
|||
//#define USE_MAG |
|||
//#define USE_MAG_HMC5883 |
|||
|
|||
#define USE_UART1 |
|||
#define SERIAL_PORT_COUNT 1 |
|||
|
|||
#define USE_ADC |
|||
#define ADC_CHANNEL_1_PIN PB0 |
|||
#define VBAT_ADC_CHANNEL ADC_CHN_1 |
|||
|
|||
#define USE_I2C |
|||
#define USE_I2C_DEVICE_1 |
|||
|
|||
#define USE_SPI |
|||
#define USE_SPI_DEVICE_1 |
|||
|
|||
#define USE_RX_SPI |
|||
#define RX_SPI_INSTANCE SPI1 |
|||
#define USE_RX_NRF24 |
|||
//#define USE_RX_CX10 |
|||
//#define USE_RX_H8_3D |
|||
//#define USE_RX_SYMA |
|||
#define USE_RX_V202 |
|||
#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M |
|||
|
|||
|
|||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS' |
|||
#define RX_CE_PIN PA12 |
|||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA |
|||
#define RX_NSS_PIN PA4 |
|||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA |
|||
#define RX_IRQ_PIN PA15 |
|||
#define RX_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA |
|||
|
|||
#undef USE_RX_MSP |
|||
#define SKIP_INFLIGHT_ADJUSTMENTS |
|||
#undef USE_SERIAL_PASSTHROUGH |
|||
#undef USE_RX_PWM |
|||
#undef USE_RX_PPM |
|||
#undef USE_SERIAL_RX |
|||
#undef USE_BLACKBOX |
|||
|
|||
#define DEFAULT_RX_TYPE RX_TYPE_SPI |
|||
|
|||
// Since the CrazePony MINI PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers. |
|||
#undef USE_SERVOS |
|||
#define USE_QUAD_MIXER_ONLY |
|||
|
|||
// Number of available PWM outputs |
|||
#define MAX_PWM_OUTPUT_PORTS 4 |
|||
|
|||
// IO - assuming all IOs on 48pin package TODO |
|||
#define TARGET_IO_PORTA 0xffff |
|||
#define TARGET_IO_PORTB 0xffff |
|||
|
|||
#define USABLE_TIMER_CHANNEL_COUNT 14 |
|||
#define USED_TIMERS TIM_N(2) |
@ -1,10 +0,0 @@ |
|||
F1_TARGETS += $(TARGET) |
|||
FEATURES = HIGHEND |
|||
FLASH_SIZE = 64 |
|||
|
|||
TARGET_SRC = \ |
|||
drivers/accgyro_mpu.c \ |
|||
drivers/accgyro_mpu6050.c \ |
|||
drivers/barometer_ms56xx.c \ |
|||
drivers/compass_hmc5883l.c \ |
|||
|
@ -1,41 +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 <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_PWM | TIM_USE_PPM }, // 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 |
|||
{ 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 |
|||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM5 - RC5 |
|||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6 - RC6 |
|||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM7 - RC7 |
|||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM8 - RC8 |
|||
}; |
|||
|
@ -1,129 +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 "103R" |
|||
|
|||
#define LED0 PB3 |
|||
#define LED1 PB4 |
|||
#define LED2 PD2 // Labelled LED4 |
|||
|
|||
#define BEEPER PA12 // PA12 (Beeper) |
|||
|
|||
#define INVERTER_PIN_UART2 PB2 // PB2 (BOOT1) abused as inverter select GPIO |
|||
|
|||
#define BARO_XCLR_PIN PC13 |
|||
#define BARO_EOC_PIN PC14 |
|||
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC |
|||
|
|||
#define USE_SPI |
|||
#define USE_SPI_DEVICE_2 |
|||
|
|||
#define PORT103R_SPI_INSTANCE SPI2 |
|||
#define PORT103R_SPI_CS_PIN PB12 |
|||
|
|||
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: |
|||
#define M25P16_CS_PIN PORT103R_SPI_CS_PIN |
|||
#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE |
|||
|
|||
#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN |
|||
#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE |
|||
|
|||
#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN |
|||
#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE |
|||
|
|||
#define USE_GYRO |
|||
#define USE_FAKE_GYRO |
|||
//#define USE_GYRO_L3G4200D |
|||
//#define USE_GYRO_L3GD20 |
|||
//#define USE_GYRO_MPU3050 |
|||
#define USE_GYRO_MPU6050 |
|||
#define USE_GYRO_SPI_MPU6000 |
|||
#define USE_GYRO_SPI_MPU6500 |
|||
|
|||
#define USE_ACC |
|||
#define USE_FAKE_ACC |
|||
//#define USE_ACC_ADXL345 |
|||
//#define USE_ACC_BMA280 |
|||
//#define USE_ACC_MMA8452 |
|||
#define USE_ACC_MPU6050 |
|||
#define USE_ACC_SPI_MPU6000 |
|||
#define USE_ACC_SPI_MPU6500 |
|||
|
|||
//#define USE_BARO |
|||
#define USE_BARO_MS5611 |
|||
#define USE_BARO_BMP085 |
|||
#define USE_BARO_BMP280 |
|||
|
|||
#define USE_MAG |
|||
#define USE_MAG_HMC5883 |
|||
#define USE_MAG_AK8975 |
|||
|
|||
#define USE_FLASHFS |
|||
#define USE_FLASHTOOLS |
|||
#define USE_FLASH_M25P16 |
|||
|
|||
// #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 RANGEFINDER_HCSR04_TRIGGER_PIN_PWM PB8 // PWM5 (PB8) - 5v tolerant |
|||
#define RANGEFINDER_HCSR04_ECHO_PIN_PWM PB9 // PWM6 (PB9) - 5v tolerant |
|||
|
|||
#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 SOFT_I2C // enable to test software i2c |
|||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) |
|||
// #define SOFT_I2C_PB67 |
|||
|
|||
#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 VBAT_ADC_CHANNEL ADC_CHN_2 |
|||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 |
|||
#define RSSI_ADC_CHANNEL ADC_CHN_3 |
|||
|
|||
//#define USE_DASHBOARD |
|||
|
|||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE |
|||
|
|||
// Number of available PWM outputs |
|||
#define MAX_PWM_OUTPUT_PORTS 10 |
|||
|
|||
// IO - stm32f103RCT6 in 64pin package |
|||
#define TARGET_IO_PORTA 0xffff |
|||
#define TARGET_IO_PORTB 0xffff |
|||
#define TARGET_IO_PORTC 0xffff |
|||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) |
|||
|
|||
#define USABLE_TIMER_CHANNEL_COUNT 14 |
|||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) |
@ -1,26 +0,0 @@ |
|||
F1_TARGETS += $(TARGET) |
|||
FEATURES = ONBOARDFLASH HIGHEND |
|||
|
|||
DEVICE_FLAGS = -DSTM32F10X_HD |
|||
|
|||
TARGET_SRC = \ |
|||
drivers/accgyro/accgyro_adxl345.c \ |
|||
drivers/accgyro/accgyro_bma280.c \ |
|||
drivers/accgyro/accgyro_fake.c \ |
|||
drivers/accgyro/accgyro_l3g4200d.c \ |
|||
drivers/accgyro/accgyro_mma845x.c \ |
|||
drivers/accgyro/accgyro_mpu.c \ |
|||
drivers/accgyro/accgyro_mpu3050.c \ |
|||
drivers/accgyro/accgyro_mpu6050.c \ |
|||
drivers/accgyro/accgyro_spi_mpu6000.c \ |
|||
drivers/accgyro/accgyro_mpu6500.c \ |
|||
drivers/accgyro/accgyro_spi_mpu6500.c \ |
|||
drivers/barometer/barometer_bmp085.c \ |
|||
drivers/barometer/barometer_bmp280.c \ |
|||
drivers/barometer/barometer_ms56xx.c \ |
|||
drivers/compass/compass_ak8975.c \ |
|||
drivers/compass/compass_mag3110.c \ |
|||
drivers/compass/compass_hmc5883l.c \ |
|||
drivers/flash_m25p16.c \ |
|||
drivers/light_ws2811strip.c \ |
|||
drivers/light_ws2811strip_stdperiph.c |
Write
Preview
Loading…
Cancel
Save
Reference in new issue