[boards] Add the new OPA board

This commit is contained in:
Freek van Tienen
2016-04-22 16:59:47 +02:00
parent fc988a24fa
commit 38cbd8eb37
10 changed files with 950 additions and 9 deletions
+12 -1
View File
@@ -208,6 +208,17 @@
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/light.xml modules/digital_cam.xml"
gui_color="white"
/>
<aircraft
name="Outback"
ac_id="6"
airframe="airframes/TUDELFT/tudelft_outback.xml"
radio="radios/dummy.xml"
telemetry="telemetry/rotorcraft_with_logger.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml settings/control/rotorcraft_guidance.xml"
settings_modules="modules/geo_mag.xml modules/air_data.xml modules/temp_adc.xml modules/logger_sd_spi_direct.xml modules/gps_ubx_ucenter.xml"
gui_color="#ffffdffac31f"
/>
<aircraft
name="Quad_Navstik"
ac_id="50"
@@ -342,7 +353,7 @@
/>
<aircraft
name="quadshot"
ac_id="6"
ac_id="7"
airframe="airframes/examples/quadshot_asp21_spektrum.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
+236
View File
@@ -0,0 +1,236 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- this is a helicopter with a double wing as frame
* Autopilot: OPA/FTD 1.0 and OPA/AP 1.0 with STM32F4
* IMU: MPU6000 (FTD), MPU6000 (AP)
* Baro: MS5611 (AP)
* Actuators: 10 PWM (FTD)
* GPS: UBlox ??
* RC: Spektrum sats (2x)
* Telemetry: Iridium (FTD), 900Mhz ??? (AP)
-->
<airframe name="Outback">
<firmware name="rotorcraft">
<!-- AP (autopilot) part of the board -->
<target name="ap" board="opa_ap_1.0">
<!--target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
</target-->
<module name="telemetry" type="xbee_api"/>
<module name="imu" type="mpu6000"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins" type="hff"/>
<module name="guidance" type="indi"/>
<module name="intermcu" type="uart"/>
<module name="current_sensor"/>
<module name="geo_mag"/>
<module name="air_data"/>
<module name="temp_adc"/>
<module name="logger_sd_spi_direct">
<define name="SDLOGGER_DIRECT_CONTROL_SWITCH" value="AUX3"/>
</module>
<module name="gps_ubx_ucenter"/>
</target>
<!-- FBW (Flight by Wire) part of the board -->
<target name="fbw" board="opa_ftd_1.0">
<module name="radio_control" type="spektrum">
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>
</module>
<module name="actuators" type="pwm"/>
<module name="intermcu" type="uart"/>
<module name="heli_throttle_curve"/>
<module name="heli_swashplate_mixing"/>
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE"/><!-- Switch to Failsafe or to Autopilot on RC loss? -->
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_FAILSAFE"/><!-- Switch to Failsafe with a working autopilot on RC loss? -->
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL"/><!-- Switch to Failsafe or to Manual on AP loss? -->
</target>
</firmware>
<!-- This should be different for AP and FBW -->
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="21.0" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="21.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="22.2" unit="V"/>
<define name="MAX_BAT_LEVEL" value="25.2" unit="V"/>
</section>
<servos driver="Pwm">
<servo name="THROTTLE" no="0" min="1100" neutral="1100" max="1900"/>
<servo name="SW_BACK" no="1" min="1900" neutral="1500" max="1100"/>
<servo name="SW_LEFTFRONT" no="2" min="1100" neutral="1500" max="1900"/>
<servo name="SW_RIGHTFRONT" no="3" min="1900" neutral="1500" max="1100"/>
<servo name="TAIL_LEFT" no="4" min="1100" neutral="1500" max="1900"/>
<servo name="TAIL_RIGHT" no="5" min="1100" neutral="1500" max="1900"/>
<servo name="AIL_LEFTFRONT" no="6" min="1100" neutral="1500" max="1900"/>
<servo name="AIL_LEFTBACK" no="7" min="1100" neutral="1500" max="1900"/>
<servo name="AIL_RIGHTFRONT" no="8" min="1100" neutral="1500" max="1900"/>
<servo name="AIL_RIGHTBACK" no="9" min="1100" neutral="1500" max="1900"/>
</servos>
<rc_commands>
<set command="THRUST" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
<set command="FMODE" value="@AUX2"/>
</rc_commands>
<commands>
<axis name="THRUST" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="FMODE" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="SW_MIXING_">
<define name="TYPE" value="HR120"/>
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_COLL" value="0"/>
</section>
<command_laws>
<call fun="throttle_curve_run(autopilot_motors_on, values)"/>
<call fun="swashplate_mixing_run(values)"/>
<set servo="THROTTLE" value="throttle_curve.throttle"/>
<set servo="SW_BACK" value="swashplate_mixing.commands[SW_BACK]"/>
<set servo="SW_LEFTFRONT" value="swashplate_mixing.commands[SW_LEFTFRONT]"/>
<set servo="SW_RIGHTFRONT" value="swashplate_mixing.commands[SW_RIGHTFRONT]"/>
<set servo="TAIL_LEFT" value="@YAW"/>
<set servo="TAIL_RIGHT" value="-@YAW"/>
<set servo="AIL_LEFTFRONT" value="@YAW"/>
<set servo="AIL_LEFTBACK" value="@YAW"/>
<set servo="AIL_RIGHTFRONT" value="@YAW"/>
<set servo="AIL_RIGHTBACK" value="@YAW"/>
</command_laws>
<heli_curves>
<curve throttle="0,4800,7200,8400,9600" collective="-1000,750,2500,4250,6000"/>
<curve throttle="9600,7200,9600" collective="-7500,0,7500"/>
</heli_curves>
<section name="MISC">
<define name="NAV_CLIMB_VSPEED" value="2.5"/>
<define name="NAV_DESCEND_VSPEED" value="-1.0"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="11"/>
<define name="ACCEL_Y_NEUTRAL" value="11"/>
<define name="ACCEL_Z_NEUTRAL" value="-25"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="-2"/>
<define name="MAG_Y_NEUTRAL" value="484"/>
<define name="MAG_Z_NEUTRAL" value="53"/>
<define name="MAG_X_SENS" value="4.02836351262" integer="16"/>
<define name="MAG_Y_SENS" value="3.97184580645" integer="16"/>
<define name="MAG_Z_SENS" value="4.08689235615" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<define name="H_X" value="0.3770441"/>
<define name="H_Y" value="0.0193986"/>
<define name="H_Z" value="0.9259921"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" unit="deg/s" value="280"/>
<define name="SP_MAX_Q" unit="deg/s" value="280"/>
<define name="SP_MAX_R" unit="deg/s" value="140"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="150." unit="deg/s"/>
<define name="DEADBAND_R" value="200"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="500"/>
<define name="PHI_DGAIN" value="100"/>
<define name="PHI_IGAIN" value="0"/>
<define name="THETA_PGAIN" value="500"/>
<define name="THETA_DGAIN" value="100"/>
<define name="THETA_IGAIN" value="0"/>
<define name="PSI_PGAIN" value="200"/>
<define name="PSI_DGAIN" value="0"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.5"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="35" unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_RATE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
</airframe>
+70
View File
@@ -0,0 +1,70 @@
# Hey Emacs, this is a -*- makefile -*-
#
# Oversized Paparazzi (AP) Board
#
# http://wiki.paparazziuav.org/wiki/OPA
#
BOARD=opa_ap
BOARD_VERSION=1.0
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
ARCH=stm32
ARCH_L=f4
HARD_FLOAT=yes
$(TARGET).ARCHDIR = $(ARCH)
$(TARGET).LDSCRIPT=$(SRC_ARCH)/lisa-mx.ld
# -----------------------------------------------------------------------
#
# default flash mode is via SWD (JTAG)
#
FLASH_MODE ?= SWD
#
# default LED configuration
#
SYS_TIME_LED ?= 1
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= none
GPS_LED ?= none
LOGGER_LED ?= none
#
# default uart configuration
#
MODEM_PORT ?= UART2
MODEM_BAUD ?= B57600
GPS_PORT ?= UART1
GPS_BAUD ?= B57600
INTERMCU_PORT ?= UART3
INTERMCU_BAUD ?= B230400
#
# default IMU configuration
#
IMU_MPU_SPI_DEV ?= spi2
IMU_MPU_SPI_SLAVE_IDX ?= SPI_SLAVE1
#
# BARO configuration
#
# See baro_board.makefile
#
# default SPI logger configuration
#
SDLOGGER_DIRECT_SPI ?= spi1
SDLOGGER_DIRECT_SPI_SLAVE ?= SPI_SLAVE0
HS_LOG_SPI_DEV ?= spi1
HS_LOG_SPI_SLAVE_IDX ?= SPI_SLAVE0
#
# default Current Sensor configuration
#
ADC_CURRENT_SENSOR ?= ADC_2
+48
View File
@@ -0,0 +1,48 @@
# Hey Emacs, this is a -*- makefile -*-
#
# Oversized Paparazzi (AP) Board
#
# http://wiki.paparazziuav.org/wiki/OPA
#
BOARD=opa_ftd
BOARD_VERSION=1.0
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
ARCH=stm32
ARCH_L=f4
HARD_FLOAT=yes
$(TARGET).ARCHDIR = $(ARCH)
$(TARGET).LDSCRIPT=$(SRC_ARCH)/lisa-mx.ld
# -----------------------------------------------------------------------
#
# default flash mode is via SWD (JTAG)
#
FLASH_MODE ?= SWD
#
# default LED configuration
#
SYS_TIME_LED ?= 1
RADIO_CONTROL_LED ?= 2
ARMING_LED ?= 3
FBW_MODE_LED ?= none
#
# default uart configuration
#
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART1
RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT ?= UART5
MODEM_PORT ?= UART3
MODEM_BAUD ?= B57600
INTERMCU_PORT ?= UART2
INTERMCU_BAUD ?= B230400
#
# default actuator configuration
#
ACTUATORS ?= actuators_pwm
@@ -194,15 +194,25 @@ else ifeq ($(BOARD), umarim)
# Naze32
else ifeq ($(BOARD), naze32)
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_I2C
BARO_BOARD_CFLAGS += -DUSE_I2C2
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c2
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_I2C
BARO_BOARD_CFLAGS += -DUSE_I2C2
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c2
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c
# OPA (AP)
else ifeq ($(BOARD), opa_ap)
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE2
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi2
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE2
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
endif # check board
BARO_LED ?= none
ifneq ($(BARO_LED),none)
BARO_BOARD_CFLAGS += -DBARO_LED=$(BARO_LED)
endif
+1 -1
View File
@@ -9,7 +9,7 @@
<file name="swashplate_mixing.h"/>
</header>
<init fun="swashplate_mixing_init()"/>
<makefile>
<makefile target="ap|fbw">
<file name="swashplate_mixing.c"/>
<define name="ROTORCRAFT_IS_HELI" value="TRUE"/>
</makefile>
+1 -1
View File
@@ -8,7 +8,7 @@
<file name="throttle_curve.h"/>
</header>
<init fun="throttle_curve_init()"/>
<makefile>
<makefile target="ap|fbw">
<file name="throttle_curve.c"/>
</makefile>
</module>
+18
View File
@@ -0,0 +1,18 @@
/*
* board specific functions for the opa_ap board
*
*/
#ifndef BOARDS_OPA_AP_BARO_H
#define BOARDS_OPA_AP_BARO_H
// only for printing the baro type during compilation
#ifndef BARO_BOARD
#define BARO_BOARD BARO_MS5611_SPI
#endif
extern void baro_event(void);
#define BaroEvent baro_event
#endif /* BOARDS_OPA_AP_BARO_H */
+210
View File
@@ -0,0 +1,210 @@
/*
* Copyright (C) 2015 Freek van Tienen <freek.v.tienen@gmail.com>
*
* This file is part of paparazzi.
*
* paparazzi 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 2, or (at your option)
* any later version.
*
* paparazzi 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 paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/
#ifndef CONFIG_OPA_FTD_1_0_H
#define CONFIG_OPA_FTD_1_0_H
#define BOARD_OPA_AP
/* OPA/FTD has a 12MHz external clock and 168MHz internal. */
#define EXT_CLK 12000000
#define AHB_CLK 168000000
/*
* Power control
*/
/* VISION power */
#define VISION_PWR GPIOA
#define VISION_PWR_PIN GPIO1
#define VISION_PWR_ON gpio_set
#define VISION_PWR_OFF gpio_clear
/*
* Onboard LEDs
*/
/* Status (red), on PA8 */
#ifndef USE_LED_1
#define USE_LED_1 1
#endif
#define LED_1_GPIO GPIOA
#define LED_1_GPIO_PIN GPIO8
#define LED_1_GPIO_ON gpio_set
#define LED_1_GPIO_OFF gpio_clear
#define LED_1_AFIO_REMAP ((void)0)
/* UART */
#define UART1_GPIO_AF GPIO_AF7
#define UART1_GPIO_PORT_RX GPIOA
#define UART1_GPIO_RX GPIO10
#define UART1_GPIO_PORT_TX GPIOA
#define UART1_GPIO_TX GPIO9
#define UART2_GPIO_AF GPIO_AF7
#define UART2_GPIO_PORT_RX GPIOA
#define UART2_GPIO_RX GPIO3
#define UART2_GPIO_PORT_TX GPIOA
#define UART2_GPIO_TX GPIO2
#define UART3_GPIO_AF GPIO_AF7
#define UART3_GPIO_PORT_RX GPIOB
#define UART3_GPIO_RX GPIO11
#define UART3_GPIO_PORT_TX GPIOB
#define UART3_GPIO_TX GPIO10
#define UART4_GPIO_AF GPIO_AF8
#define UART4_GPIO_PORT_RX GPIOC
#define UART4_GPIO_RX GPIO11
#define UART4_GPIO_PORT_TX GPIOC
#define UART4_GPIO_TX GPIO10
#define UART5_GPIO_AF GPIO_AF8
#define UART5_GPIO_PORT_RX GPIOD
#define UART5_GPIO_RX GPIO2
/* SPI */
#define SPI1_GPIO_AF GPIO_AF5
#define SPI1_GPIO_PORT_MISO GPIOA
#define SPI1_GPIO_MISO GPIO6
#define SPI1_GPIO_PORT_MOSI GPIOA
#define SPI1_GPIO_MOSI GPIO7
#define SPI1_GPIO_PORT_SCK GPIOA
#define SPI1_GPIO_SCK GPIO5
#define SPI1_GPIO_PORT_NSS GPIOA
#define SPI1_GPIO_NSS GPIO4
#define SPI2_GPIO_AF GPIO_AF5
#define SPI2_GPIO_PORT_MISO GPIOB
#define SPI2_GPIO_MISO GPIO14
#define SPI2_GPIO_PORT_MOSI GPIOB
#define SPI2_GPIO_MOSI GPIO15
#define SPI2_GPIO_PORT_SCK GPIOB
#define SPI2_GPIO_SCK GPIO13
#define SPI2_GPIO_PORT_NSS GPIOB
#define SPI2_GPIO_NSS GPIO12
#define SPI_SELECT_SLAVE0_PORT GPIOA // SD CARD (on spi1)
#define SPI_SELECT_SLAVE0_PIN GPIO4
#define SPI_SELECT_SLAVE1_PORT GPIOB // IMU (on spi2)
#define SPI_SELECT_SLAVE1_PIN GPIO12
#define SPI_SELECT_SLAVE2_PORT GPIOC // BARO (on spi2)
#define SPI_SELECT_SLAVE2_PIN GPIO13
/*
* ADC
*/
/* BATT PC4/ADC14 */
#ifndef USE_ADC_1
#define USE_ADC_1 1
#endif
#if USE_ADC_1
#define AD1_1_CHANNEL 14
#define ADC_1 AD1_1
#define ADC_1_GPIO_PORT GPIOC
#define ADC_1_GPIO_PIN GPIO4
#endif
/* CURRENT PC3/ADC13 */
#if USE_ADC_2
#define AD1_2_CHANNEL 13
#define ADC_2 AD1_2
#define ADC_2_GPIO_PORT GPIOC
#define ADC_2_GPIO_PIN GPIO3
#endif
/* TEMP_MOTOR PC0/ADC10 */
#ifndef USE_ADC_3
#define USE_ADC_3 1
#endif
#if USE_ADC_3
#define AD1_3_CHANNEL 10
#define ADC_3 AD1_3
#define ADC_3_GPIO_PORT GPIOC
#define ADC_3_GPIO_PIN GPIO0
#endif
/* TEMP_BATT PC1/ADC11 */
#ifndef USE_ADC_4
#define USE_ADC_4 1
#endif
#if USE_ADC_4
#define AD1_4_CHANNEL 11
#define ADC_4 AD1_4
#define ADC_4_GPIO_PORT GPIOC
#define ADC_4_GPIO_PIN GPIO1
#endif
/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
#ifndef ADC_CHANNEL_VSUPPLY
#define ADC_CHANNEL_VSUPPLY ADC_1
#endif
// Default: 10k / 2k2
// #define DefaultVoltageOfAdc(adc) (0.0045*adc)
// Opa: 31k6 / 4k7
#define DefaultVoltageOfAdc(adc) (0.0063*adc)
// ADC756-B050: +/-50Amp range bidirectional
// 40 mV / Ampere
// 1 ADC-count = 0,000805664 Volt, 0.040 V = 1 Ampere -> 1 Ampere = 49,6484887 ADC ticks: 1 ADC-tck = 20mA
// 5.0/3.3 from datasheet
#define DefaultMilliAmpereOfAdc(adc) (20.142*(adc-2048) * 5.0/3.3)
/* TEMP MOTOR: NTC with 2k fixed pull up */
// R0: 10k (@25C)
// T0: 25C -> 298.15K
// B: 3976 K
// a = (1/T0) - (1/B)*ln(R0) = 0.00103753243
// b = 1/B = 0.00025150905
// c = 0
#define TEMP_ADC_CHANNEL1 ADC_3
#define TEMP_ADC_CHANNEL1_TYPE NTC
#define TEMP_ADC_CHANNEL1_PU_R 2000
#define TEMP_ADC_CHANNEL1_A 0.00103753243
#define TEMP_ADC_CHANNEL1_B 0.00025150905
#define TEMP_ADC_CHANNEL1_C 0
/* TEMP BATT: NTC with 2k fixed pull up */
// R0: 10k (@25C)
// T0: 25C -> 298.15K
// B: 3976 K
// a = (1/T0) - (1/B)*ln(R0) = 0.00103753243
// b = 1/B = 0.00025150905
// c = 0
#define TEMP_ADC_CHANNEL2 ADC_4
#define TEMP_ADC_CHANNEL2_TYPE NTC
#define TEMP_ADC_CHANNEL2_PU_R 2000
#define TEMP_ADC_CHANNEL2_A 0.00103753243
#define TEMP_ADC_CHANNEL2_B 0.00025150905
#define TEMP_ADC_CHANNEL2_C 0
/* by default activate onboard baro */
#ifndef USE_BARO_BOARD
#define USE_BARO_BOARD 1
#endif
#endif /* CONFIG_OPA_AP_1_0_H */
+338
View File
@@ -0,0 +1,338 @@
/*
* Copyright (C) 2015 Freek van Tienen <freek.v.tienen@gmail.com>
*
* This file is part of paparazzi.
*
* paparazzi 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 2, or (at your option)
* any later version.
*
* paparazzi 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 paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/
#ifndef CONFIG_OPA_FTD_1_0_H
#define CONFIG_OPA_FTD_1_0_H
#define BOARD_OPA_FTD
/* OPA/FTD has a 12MHz external clock and 168MHz internal. */
#define EXT_CLK 12000000
#define AHB_CLK 168000000
/*
* MCU Power control
*/
#define MCU_PWR GPIOB
#define MCU_PWR_PIN GPIO5
#define MCU_PWR_ON gpio_set
#define MCU_PWR_OFF gpio_clear
/*
* Buttons
*/
/* E-Stop button */
#define BTN_ESTOP GPIOB
#define BTN_ESTOP_PIN GPIO12
/*
* Onboard LEDs
*/
/* Status (red), on PA8 */
#ifndef USE_LED_1
#define USE_LED_1 1
#endif
#define LED_1_GPIO GPIOA
#define LED_1_GPIO_PIN GPIO8
#define LED_1_GPIO_ON gpio_set
#define LED_1_GPIO_OFF gpio_clear
#define LED_1_AFIO_REMAP ((void)0)
/* RC (green), on PC5 */
#ifndef USE_LED_2
#define USE_LED_2 1
#endif
#define LED_2_GPIO GPIOC
#define LED_2_GPIO_PIN GPIO5
#define LED_2_GPIO_ON gpio_set
#define LED_2_GPIO_OFF gpio_clear
#define LED_2_AFIO_REMAP ((void)0)
/* Status LED ext, PB13 */
#ifndef USE_LED_3
#define USE_LED_3 1
#endif
#define LED_3_GPIO GPIOB
#define LED_3_GPIO_PIN GPIO13
#define LED_3_GPIO_ON gpio_set
#define LED_3_GPIO_OFF gpio_clear
#define LED_3_AFIO_REMAP ((void)0)
/* Default actuators driver */
#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
#define ActuatorsDefaultInit() ActuatorsPwmInit()
#define ActuatorsDefaultCommit() ActuatorsPwmCommit()
/* UART */
#define UART1_GPIO_AF GPIO_AF7
#define UART1_GPIO_PORT_RX GPIOA
#define UART1_GPIO_RX GPIO10
#define UART2_GPIO_AF GPIO_AF7
#define UART2_GPIO_PORT_RX GPIOA
#define UART2_GPIO_RX GPIO3
#define UART2_GPIO_PORT_TX GPIOA
#define UART2_GPIO_TX GPIO2
#define UART3_GPIO_AF GPIO_AF7
#define UART3_GPIO_PORT_RX GPIOB
#define UART3_GPIO_RX GPIO11
#define UART3_GPIO_PORT_TX GPIOB
#define UART3_GPIO_TX GPIO10
#define UART4_GPIO_AF GPIO_AF8
#define UART4_GPIO_PORT_RX GPIOC
#define UART4_GPIO_RX GPIO11
#define UART4_GPIO_PORT_TX GPIOC
#define UART4_GPIO_TX GPIO10
#define UART5_GPIO_AF GPIO_AF8
#define UART5_GPIO_PORT_RX GPIOD
#define UART5_GPIO_RX GPIO2
/*
* Spektrum
*/
/* Define power pin */
#define RADIO_CONTROL_POWER GPIOC
#define RADIO_CONTROL_POWER_PIN GPIO13
#define RADIO_CONTROL_POWER_ON gpio_set
#define RADIO_CONTROL_POWER_OFF gpio_clear
/* The line that is pulled low at power up to initiate the bind process */
#define SPEKTRUM_BIND_PIN GPIO2
#define SPEKTRUM_BIND_PIN_PORT GPIOB
#define SPEKTRUM_UART1_RCC RCC_USART1
#define SPEKTRUM_UART1_BANK GPIOA
#define SPEKTRUM_UART1_PIN GPIO10
#define SPEKTRUM_UART1_AF GPIO_AF7
#define SPEKTRUM_UART1_IRQ NVIC_USART1_IRQ
#define SPEKTRUM_UART1_ISR usart1_isr
#define SPEKTRUM_UART1_DEV USART1
#define SPEKTRUM_UART5_RCC RCC_UART5
#define SPEKTRUM_UART5_BANK GPIOD
#define SPEKTRUM_UART5_PIN GPIO2
#define SPEKTRUM_UART5_AF GPIO_AF8
#define SPEKTRUM_UART5_IRQ NVIC_UART5_IRQ
#define SPEKTRUM_UART5_ISR uart5_isr
#define SPEKTRUM_UART5_DEV UART5
/* SPI */
#define SPI1_GPIO_AF GPIO_AF5
#define SPI1_GPIO_PORT_MISO GPIOA
#define SPI1_GPIO_MISO GPIO6
#define SPI1_GPIO_PORT_MOSI GPIOA
#define SPI1_GPIO_MOSI GPIO7
#define SPI1_GPIO_PORT_SCK GPIOA
#define SPI1_GPIO_SCK GPIO5
#define SPI1_GPIO_PORT_NSS GPIOA
#define SPI1_GPIO_NSS GPIO4
#define SPI_SELECT_SLAVE0_PORT GPIOA
#define SPI_SELECT_SLAVE0_PIN GPIO4
/*
* ADC
*/
/* BATT PC4/ADC14 */
#ifndef USE_ADC_1
#define USE_ADC_1 1
#endif
#if USE_ADC_1
#define AD1_1_CHANNEL 14
#define ADC_1 AD1_1
#define ADC_1_GPIO_PORT GPIOC
#define ADC_1_GPIO_PIN GPIO4
#endif
/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
#ifndef ADC_CHANNEL_VSUPPLY
#define ADC_CHANNEL_VSUPPLY ADC_1
#endif
// Default: 10k / 2k2 ->
// #define DefaultVoltageOfAdc(adc) (0.00446777*adc)
// Opa-FBW: 10k / 4k7
#define DefaultVoltageOfAdc(adc) (00.00252*adc)
/*
* PWM
*
*/
#define PWM_USE_TIM3 1
#define PWM_USE_TIM4 1
#define PWM_USE_TIM5 1
#define USE_PWM1 1
#define USE_PWM2 1
#define USE_PWM3 1
#define USE_PWM4 1
#define USE_PWM5 1
#define USE_PWM6 1
#define USE_PWM7 1
#define USE_PWM8 1
#define USE_PWM9 1
#define USE_PWM10 1
#define ACTUATORS_PWM_NB 10
// PWM_SERVO_x is the index of the servo in the actuators_pwm_values array
#if USE_PWM1
#define PWM_SERVO_1 0
#define PWM_SERVO_1_TIMER TIM3
#define PWM_SERVO_1_GPIO GPIOC
#define PWM_SERVO_1_PIN GPIO6
#define PWM_SERVO_1_AF GPIO_AF2
#define PWM_SERVO_1_OC TIM_OC1
#define PWM_SERVO_1_OC_BIT (1<<0)
#else
#define PWM_SERVO_1_OC_BIT 0
#endif
#if USE_PWM2
#define PWM_SERVO_2 1
#define PWM_SERVO_2_TIMER TIM3
#define PWM_SERVO_2_GPIO GPIOC
#define PWM_SERVO_2_PIN GPIO7
#define PWM_SERVO_2_AF GPIO_AF2
#define PWM_SERVO_2_OC TIM_OC2
#define PWM_SERVO_2_OC_BIT (1<<1)
#else
#define PWM_SERVO_2_OC_BIT 0
#endif
#if USE_PWM3
#define PWM_SERVO_3 2
#define PWM_SERVO_3_TIMER TIM3
#define PWM_SERVO_3_GPIO GPIOC
#define PWM_SERVO_3_PIN GPIO8
#define PWM_SERVO_3_AF GPIO_AF2
#define PWM_SERVO_3_OC TIM_OC3
#define PWM_SERVO_3_OC_BIT (1<<2)
#else
#define PWM_SERVO_3_OC_BIT 0
#endif
#if USE_PWM4
#define PWM_SERVO_4 3
#define PWM_SERVO_4_TIMER TIM3
#define PWM_SERVO_4_GPIO GPIOC
#define PWM_SERVO_4_PIN GPIO9
#define PWM_SERVO_4_AF GPIO_AF2
#define PWM_SERVO_4_OC TIM_OC4
#define PWM_SERVO_4_OC_BIT (1<<3)
#else
#define PWM_SERVO_4_OC_BIT 0
#endif
#if USE_PWM5
#define PWM_SERVO_5 4
#define PWM_SERVO_5_TIMER TIM5
#define PWM_SERVO_5_GPIO GPIOA
#define PWM_SERVO_5_PIN GPIO0
#define PWM_SERVO_5_AF GPIO_AF2
#define PWM_SERVO_5_OC TIM_OC1
#define PWM_SERVO_5_OC_BIT (1<<0)
#else
#define PWM_SERVO_5_OC_BIT 0
#endif
#if USE_PWM6
#define PWM_SERVO_6 5
#define PWM_SERVO_6_TIMER TIM5
#define PWM_SERVO_6_GPIO GPIOA
#define PWM_SERVO_6_PIN GPIO1
#define PWM_SERVO_6_AF GPIO_AF2
#define PWM_SERVO_6_OC TIM_OC2
#define PWM_SERVO_6_OC_BIT (1<<1)
#else
#define PWM_SERVO_6_OC_BIT 0
#endif
#if USE_PWM7
#define PWM_SERVO_7 6
#define PWM_SERVO_7_TIMER TIM4
#define PWM_SERVO_7_GPIO GPIOB
#define PWM_SERVO_7_PIN GPIO6
#define PWM_SERVO_7_AF GPIO_AF2
#define PWM_SERVO_7_OC TIM_OC1
#define PWM_SERVO_7_OC_BIT (1<<0)
#else
#define PWM_SERVO_7_OC_BIT 0
#endif
#if USE_PWM8
#define PWM_SERVO_8 7
#define PWM_SERVO_8_TIMER TIM4
#define PWM_SERVO_8_GPIO GPIOB
#define PWM_SERVO_8_PIN GPIO7
#define PWM_SERVO_8_AF GPIO_AF2
#define PWM_SERVO_8_OC TIM_OC2
#define PWM_SERVO_8_OC_BIT (1<<1)
#else
#define PWM_SERVO_8_OC_BIT 0
#endif
#if USE_PWM9
#define PWM_SERVO_9 8
#define PWM_SERVO_9_TIMER TIM4
#define PWM_SERVO_9_GPIO GPIOB
#define PWM_SERVO_9_PIN GPIO8
#define PWM_SERVO_9_AF GPIO_AF2
#define PWM_SERVO_9_OC TIM_OC3
#define PWM_SERVO_9_OC_BIT (1<<2)
#else
#define PWM_SERVO_9_OC_BIT 0
#endif
#if USE_PWM10
#define PWM_SERVO_10 9
#define PWM_SERVO_10_TIMER TIM4
#define PWM_SERVO_10_GPIO GPIOB
#define PWM_SERVO_10_PIN GPIO9
#define PWM_SERVO_10_AF GPIO_AF2
#define PWM_SERVO_10_OC TIM_OC4
#define PWM_SERVO_10_OC_BIT (1<<3)
#else
#define PWM_SERVO_10_OC_BIT 0
#endif
/* servos 1-4 on TIM3 */
#define PWM_TIM3_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT)
/* servos 5-6 on TIM5 */
#define PWM_TIM5_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT)
/* servos 7-10 on TIM4 */
#define PWM_TIM4_CHAN_MASK (PWM_SERVO_7_OC_BIT|PWM_SERVO_8_OC_BIT|PWM_SERVO_9_OC_BIT|PWM_SERVO_10_OC_BIT)
#endif /* CONFIG_OPA_FTD_1_0_H */