[boards] support for OpenPilot Revolution board

IMU, mag, baro and telemetry tested.
Positive x-axis of the IMU is indicated by the arrows on the board, the side with LEDS and F4 is up (negative z-axis).
Still missing support for the modem and the external flash...

To get the axes correct also extended the imu_mpu600_hmc5883 driver to allow different axes/channel assignments.
This commit is contained in:
Felix Ruess
2016-03-17 22:34:47 +01:00
parent 6f90a1d88b
commit 18fadbde59
10 changed files with 853 additions and 6 deletions
+182
View File
@@ -0,0 +1,182 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- this is a quadrotor frame in X-configuration equiped with
* Autopilot: OpenPilot Revo with STM32F4
* IMU: MPU6000 & MS5611
* Actuators: PWM motor controllers http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
* RC: Spektrum satellite http://wiki.paparazziuav.org/wiki/Subsystem/radio_control#Spektrum
-->
<airframe name="Quadrotor OpenPilot Revo">
<firmware name="rotorcraft">
<target name="ap" board="openpilot_revo_1.0">
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
</target>
<module name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
</module>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
</module>
<module name="telemetry" type="transparent"/>
<module name="imu" type="openpilot_revo"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="float_mlkf">
<!-- Uncomment to enable all axis update from the Magnetometer. Do
it only if you have a very well calibrated and tested
magnetometer otherwise your attitude will drift. -->
<!--define name="AHRS_MAG_UPDATE_ALL_AXES" value="1"/-->
</module>
<module name="ins" type="hff"/>
<module name="gps_ubx_ucenter"/>
<module name="geo_mag"/>
<module name="air_data"/>
</firmware>
<servos driver="Pwm">
<servo name="FR" no="0" min="1000" neutral="1100" max="2000"/>
<servo name="BR" no="1" min="1000" neutral="1100" max="2000"/>
<servo name="BL" no="2" min="1000" neutral="1100" max="2000"/>
<servo name="FL" no="3" min="1000" neutral="1100" max="2000"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<!-- front left (CW), front right (CCW), back right (CW), back left (CCW) -->
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FR" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BR" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BL" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="30"/>
<define name="MAG_Y_NEUTRAL" value="127"/>
<define name="MAG_Z_NEUTRAL" value="140"/>
<define name="MAG_X_SENS" value="7.11726808648" integer="16"/>
<define name="MAG_Y_SENS" value="7.09366475279" integer="16"/>
<define name="MAG_Z_SENS" value="6.84467824688" 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_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="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="250" 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="1000"/>
<define name="PHI_DGAIN" value="400"/>
<define name="PHI_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="1000"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="200"/>
<define name="PSI_PGAIN" value="500"/>
<define name="PSI_DGAIN" value="300"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="300"/>
<define name="THETA_DDGAIN" value="300"/>
<define name="PSI_DDGAIN" value="300"/>
</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="20" 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="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<define name="JS_AXIS_MODE" value="4"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="10.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
+58
View File
@@ -0,0 +1,58 @@
# Hey Emacs, this is a -*- makefile -*-
#
# openpilot_revo_1.0.makefile
#
# https://www.openpilot.org/products/openpilot-revolution-platform/
#
BOARD=openpilot_revo
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)/openpilot_revo.ld
# -----------------------------------------------------------------------
# default flash mode is via SWD
# other possibilities: DFU, DFU-UTIL, SWD, STLINK
FLASH_MODE ?= SWD
#
# default LED configuration
#
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 2
GPS_LED ?= none
SYS_TIME_LED ?= 1
#
# default uart configuration
#
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2
MODEM_PORT ?= UART1
MODEM_BAUD ?= B57600
GPS_PORT ?= UART3
GPS_BAUD ?= B38400
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
# and by setting the correct "driver" attribute in servo section
# e.g. <servo driver="Ppm">
#
ACTUATORS ?= actuators_pwm
+11
View File
@@ -263,6 +263,17 @@
settings_modules="modules/gps_ubx_ucenter.xml"
gui_color="#710080"
/>
<aircraft
name="Quad_Revolution"
ac_id="3"
airframe="airframes/examples/quadrotor_revo.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int_quat.xml settings/nps.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/geo_mag.xml modules/air_data.xml"
gui_color="blue"
/>
<aircraft
name="Twinjet"
ac_id="6"
@@ -210,6 +210,16 @@ else ifeq ($(BOARD), opa_ap)
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
# OpenPilot Revo
else ifeq ($(BOARD), openpilot_revo)
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_I2C
BARO_BOARD_CFLAGS += -DUSE_I2C1
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c1
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c
endif # check board
BARO_LED ?= none
@@ -0,0 +1,85 @@
# Hey Emacs, this is a -*- makefile -*-
#
# IMU with MPU6000 via SPI and HMC5883 via I2c on the OpenPilot Revolution board.
# The IMU positive X-axis is as inidcated with arrows on the board,
# Z-axis is negative towards the side of the MPU and LEDs (that side is up)
#
# if ACCEL and GYRO SENS/NEUTRAL are not defined,
# the defaults from the datasheet will be used
#
# required xml:
# <section name="IMU" prefix="IMU_">
#
# <define name="MAG_X_NEUTRAL" value="2358"/>
# <define name="MAG_Y_NEUTRAL" value="2362"/>
# <define name="MAG_Z_NEUTRAL" value="2119"/>
#
# <define name="MAG_X_SENS" value="3.4936416" integer="16"/>
# <define name="MAG_Y_SENS" value="3.607713" integer="16"/>
# <define name="MAG_Z_SENS" value="4.90788848" integer="16"/>
#
# </section>
#
#
include $(CFG_SHARED)/spi_master.makefile
IMU_CFLAGS = -DIMU_TYPE_H=\"imu/imu_mpu6000_hmc5883.h\"
IMU_SRCS = $(SRC_SUBSYSTEMS)/imu.c
IMU_SRCS += $(SRC_SUBSYSTEMS)/imu/imu_mpu6000_hmc5883.c
# MPU
IMU_SRCS += peripherals/mpu60x0.c
IMU_SRCS += peripherals/mpu60x0_spi.c
# Magnetometer
IMU_SRCS += peripherals/hmc58xx.c
# for fixedwing firmware and ap only
ifeq ($(TARGET), ap)
IMU_CFLAGS += -DUSE_IMU
endif
# HMC is on I2C1 on OpenPilot Revolution
IMU_HMC_I2C_DEV = i2c1
# convert i2cx to upper/lower case
IMU_HMC_I2C_DEV_UPPER=$(shell echo $(IMU_HMC_I2C_DEV) | tr a-z A-Z)
IMU_HMC_I2C_DEV_LOWER=$(shell echo $(IMU_HMC_I2C_DEV) | tr A-Z a-z)
IMU_CFLAGS += -DIMU_HMC_I2C_DEV=$(IMU_HMC_I2C_DEV_LOWER)
IMU_CFLAGS += -DUSE_$(IMU_HMC_I2C_DEV_UPPER)
# MPU600 is on SPI1 using SPI_SLAVE_2 as defined in openpilot_revo_1.0.h
IMU_MPU_SPI_DEV = spi1
IMU_MPU_SPI_SLAVE_IDX = SPI_SLAVE2
# convert spix to upper/lower case
IMU_MPU_SPI_DEV_UPPER=$(shell echo $(IMU_MPU_SPI_DEV) | tr a-z A-Z)
IMU_MPU_SPI_DEV_LOWER=$(shell echo $(IMU_MPU_SPI_DEV) | tr A-Z a-z)
IMU_CFLAGS += -DIMU_MPU_SPI_DEV=$(IMU_MPU_SPI_DEV_LOWER)
IMU_CFLAGS += -DUSE_$(IMU_MPU_SPI_DEV_UPPER)
IMU_CFLAGS += -DIMU_MPU_SPI_SLAVE_IDX=$(IMU_MPU_SPI_SLAVE_IDX)
IMU_CFLAGS += -DUSE_$(IMU_MPU_SPI_SLAVE_IDX)
# set channels and signs so that positive x-axis is indicated by arrows on board
# and the side with MPU and LEDs is up (negative z-axis)
IMU_CFLAGS += -DIMU_MPU_CHAN_X=1 -DIMU_MPU_CHAN_Y=0 -DIMU_MPU_CHAN_Z=2
IMU_CFLAGS += -DIMU_MPU_X_SIGN=-1 -DIMU_MPU_Y_SIGN=-1 -DIMU_MPU_Z_SIGN=-1
IMU_CFLAGS += -DIMU_HMC_CHAN_X=1 -DIMU_HMC_CHAN_Y=0 -DIMU_HMC_CHAN_Z=2
IMU_CFLAGS += -DIMU_HMC_X_SIGN=1 -DIMU_HMC_Y_SIGN=1 -DIMU_HMC_Z_SIGN=-1
# add it for all targets except sim, fbw and nps
ifeq (,$(findstring $(TARGET),sim fbw nps))
$(TARGET).CFLAGS += $(IMU_CFLAGS)
$(TARGET).srcs += $(IMU_SRCS)
endif
#
# NPS simulator
#
include $(CFG_SHARED)/imu_nps.makefile
+3
View File
@@ -57,6 +57,7 @@
<board name="li[s]?a_mx_.*"/>
<board name="navstik_.*"/>
<board name="elle*"/>
<board name="openpilot_revo.*"/>
</boards>
</mode>
<mode name="STLink (SWD)">
@@ -68,6 +69,7 @@
<board name="cc3d"/>
<board name="elle*"/>
<board name="naze32*"/>
<board name="openpilot_revo.*"/>
</boards>
</mode>
<mode name="BlackMagic Probe (SWD)">
@@ -82,6 +84,7 @@
<board name="elle*"/>
<board name="naze32*"/>
<board name="cjmcu*"/>
<board name="openpilot_revo.*"/>
</boards>
</mode>
<mode name="BlackMagic Probe (JTAG)">
+35
View File
@@ -0,0 +1,35 @@
/*
* Hey Emacs, this is a -*- makefile -*-
*
* Copyright (C) 2016 Felix Ruess <felix.ruess@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.
*/
/* Linker script for OpenPilot Revo (STM32F405RGT6, 1024K flash, 192K RAM). */
/* Define memory regions. */
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
/* Reserving 128kb flash for persistent settings. */
rom (rx) : ORIGIN = 0x08000000, LENGTH = 896K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f4.ld
@@ -0,0 +1,17 @@
/*
* board specific functions for the openpilot_revo board
*
*/
#ifndef BOARDS_OPENPILOT_REVO_BARO_H
#define BOARDS_OPENPILOT_REVO_BARO_H
// only for printing the baro type during compilation
#ifndef BARO_BOARD
#define BARO_BOARD BARO_MS5611_I2C
#endif
extern void baro_event(void);
#define BaroEvent baro_event
#endif /* BOARDS_OPENPILOT_REVO_BARO_H */
+379
View File
@@ -0,0 +1,379 @@
/*
* Copyright (C) 2016 Felix Ruess <felix.ruess@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_OPENPILOT_REVO_1_0_H
#define CONFIG_OPENPILOT_REVO_1_0_H
#define BOARD_REVO
/* OpenPilot Revo has a 8MHz external clock and 168MHz internal. */
#define EXT_CLK 8000000
#define AHB_CLK 168000000
/*
* Onboard LEDs
*/
/* STAT blue, on PB5 */
#ifndef USE_LED_1
#define USE_LED_1 1
#endif
#define LED_1_GPIO GPIOB
#define LED_1_GPIO_PIN GPIO5
#define LED_1_GPIO_ON gpio_clear
#define LED_1_GPIO_OFF gpio_set
#define LED_1_AFIO_REMAP ((void)0)
/* WARN red, on PB4 */
#ifndef USE_LED_2
#define USE_LED_2 1
#endif
#define LED_2_GPIO GPIOB
#define LED_2_GPIO_PIN GPIO4
#define LED_2_GPIO_ON gpio_clear
#define LED_2_GPIO_OFF gpio_set
#define LED_2_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 */
/* Main Port */
#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 GPIOC
#define UART3_GPIO_RX GPIO11
#define UART3_GPIO_PORT_TX GPIOC
#define UART3_GPIO_TX GPIO10
#define UART5_GPIO_AF GPIO_AF8
#define UART5_GPIO_PORT_RX GPIOD
#define UART5_GPIO_RX GPIO2
#define UART5_GPIO_PORT_TX GPIOC
#define UART5_GPIO_TX GPIO12
/*
* Spektrum
*/
/* The line that is pulled low at power up to initiate the bind process */
#define SPEKTRUM_BIND_PIN GPIO0
#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_UART2_RCC RCC_USART2
#define SPEKTRUM_UART2_BANK GPIOA
#define SPEKTRUM_UART2_PIN GPIO3
#define SPEKTRUM_UART2_AF GPIO_AF7
#define SPEKTRUM_UART2_IRQ NVIC_USART2_IRQ
#define SPEKTRUM_UART2_ISR usart2_isr
#define SPEKTRUM_UART2_DEV USART2
#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
/* PPM
*
* Default is PPM config 2, input on GPIOA1 (Servo pin 6)
*/
#ifndef PPM_CONFIG
#define PPM_CONFIG 2
#endif
#if PPM_CONFIG == 1
/* input on PA10 (UART1_RX) */
#define USE_PPM_TIM1 1
#define PPM_CHANNEL TIM_IC3
#define PPM_TIMER_INPUT TIM_IC_IN_TI3
#define PPM_IRQ NVIC_TIM1_CC_IRQ
#define PPM_IRQ2 NVIC_TIM1_UP_TIM10_IRQ
// Capture/Compare InteruptEnable and InterruptFlag
#define PPM_CC_IE TIM_DIER_CC3IE
#define PPM_CC_IF TIM_SR_CC3IF
#define PPM_GPIO_PORT GPIOA
#define PPM_GPIO_PIN GPIO10
#define PPM_GPIO_AF GPIO_AF1
#elif PPM_CONFIG == 2
/* input on PA01 (Servo 6 pin) */
#define USE_PPM_TIM2 1
#define PPM_CHANNEL TIM_IC2
#define PPM_TIMER_INPUT TIM_IC_IN_TI2
#define PPM_IRQ NVIC_TIM2_IRQ
// Capture/Compare InteruptEnable and InterruptFlag
#define PPM_CC_IE TIM_DIER_CC2IE
#define PPM_CC_IF TIM_SR_CC2IF
#define PPM_GPIO_PORT GPIOA
#define PPM_GPIO_PIN GPIO1
#define PPM_GPIO_AF GPIO_AF1
// Move default ADC timer
#if USE_AD_TIM2
#undef USE_AD_TIM2
#endif
#define USE_AD_TIM1 1
#else
#error "Unknown PPM config"
#endif // PPM_CONFIG
/* SPI */
/* MPU6000 */
#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
/* flash and RFM22B-S2 modem */
#define SPI3_GPIO_AF GPIO_AF5
#define SPI3_GPIO_PORT_MISO GPIOC
#define SPI3_GPIO_MISO GPIO11
#define SPI3_GPIO_PORT_MOSI GPIOC
#define SPI3_GPIO_MOSI GPIO12
#define SPI3_GPIO_PORT_SCK GPIOC
#define SPI3_GPIO_SCK GPIO10
/* modem CS */
#define SPI3_GPIO_PORT_NSS GPIOA
#define SPI3_GPIO_NSS GPIO15
/* MODEM select */
#define SPI_SELECT_SLAVE0_PORT GPIOA
#define SPI_SELECT_SLAVE0_PIN GPIO15
/* external flash chip select */
#define SPI_SELECT_SLAVE1_PORT GPIOB
#define SPI_SELECT_SLAVE1_PIN GPIO3
/* MPU6000 select */
#define SPI_SELECT_SLAVE2_PORT GPIOA
#define SPI_SELECT_SLAVE2_PIN GPIO4
/* I2C mapping */
/* HMC5883L mag on I2C1 with DRDY on PB7 */
/* MS5611 baro on I2C1 */
#define I2C1_GPIO_PORT GPIOB
#define I2C1_GPIO_SCL GPIO8
#define I2C1_GPIO_SDA GPIO9
/*
* ADC
*/
/* Onboard ADCs */
/*
ADC1 PC3/ADC13
ADC2 PC0/ADC10
ADC3 PC1/ADC11
ADC4 PC5/ADC15
ADC6 PC2/ADC12
BATT PC4/ADC14
*/
/* provide defines that can be used to access the ADC_x in the code or airframe file
* these directly map to the index number of the 4 adc channels defined above
* 4th (index 3) is used for bat monitoring by default
*/
#ifndef USE_ADC_1
#define USE_ADC_1 1
#endif
/* Voltage on Pwr/Sen/Sonar CONN3 */
#if USE_ADC_1
#define AD1_1_CHANNEL 12
#define ADC_1 AD1_1
#define ADC_1_GPIO_PORT GPIOC
#define ADC_1_GPIO_PIN GPIO2
#endif
/* Current on Pwr/Sen/Sonar CONN3 */
#if USE_ADC_2
#define AD1_2_CHANNEL 11
#define ADC_2 AD1_2
#define ADC_2_GPIO_PORT GPIOC
#define ADC_2_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
/* no voltage divider on board, adjust VoltageOfAdc in airframe file */
#define DefaultVoltageOfAdc(adc) (0.0045*adc)
/*
* PWM
*
*/
#define PWM_USE_TIM3 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
#if USE_SERVOS_7AND8
#if USE_I2C1
#error "You cannot USE_SERVOS_7AND8 and USE_I2C1 at the same time"
#else
#define ACTUATORS_PWM_NB 8
#define USE_PWM7 1
#define USE_PWM8 1
#define PWM_USE_TIM4 1
#define ACTUATORS_PWM_NB 8
#endif
#else
#define ACTUATORS_PWM_NB 6
#endif
// 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 GPIOB
#define PWM_SERVO_1_PIN GPIO0
#define PWM_SERVO_1_AF GPIO_AF2
#define PWM_SERVO_1_OC TIM_OC3
#define PWM_SERVO_1_OC_BIT (1<<2)
#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 GPIOB
#define PWM_SERVO_2_PIN GPIO1
#define PWM_SERVO_2_AF GPIO_AF2
#define PWM_SERVO_2_OC TIM_OC4
#define PWM_SERVO_2_OC_BIT (1<<3)
#else
#define PWM_SERVO_2_OC_BIT 0
#endif
#if USE_PWM3
#define PWM_SERVO_3 2
#define PWM_SERVO_3_TIMER TIM9
#define PWM_SERVO_3_GPIO GPIOA
#define PWM_SERVO_3_PIN GPIO3
#define PWM_SERVO_3_AF GPIO_AF2
#define PWM_SERVO_3_OC TIM_OC2
#define PWM_SERVO_3_OC_BIT (1<<1)
#else
#define PWM_SERVO_3_OC_BIT 0
#endif
#if USE_PWM4
#define PWM_SERVO_4 3
#define PWM_SERVO_4_TIMER TIM2
#define PWM_SERVO_4_GPIO GPIOA
#define PWM_SERVO_4_PIN GPIO2
#define PWM_SERVO_4_AF GPIO_AF2
#define PWM_SERVO_4_OC TIM_OC3
#define PWM_SERVO_4_OC_BIT (1<<2)
#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 GPIO1
#define PWM_SERVO_5_AF GPIO_AF2
#define PWM_SERVO_5_OC TIM_OC2
#define PWM_SERVO_5_OC_BIT (1<<1)
#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 GPIO0
#define PWM_SERVO_6_AF GPIO_AF2
#define PWM_SERVO_6_OC TIM_OC1
#define PWM_SERVO_6_OC_BIT (1<<0)
#else
#define PWM_SERVO_6_OC_BIT 0
#endif
/* servos 1-2 on TIM3 */
#define PWM_TIM3_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT)
/* servos 3 on TIM9 */
#define PWM_TIM9_CHAN_MASK (PWM_SERVO_3_OC_BIT)
/* servos 4 on TIM2 */
#define PWM_TIM2_CHAN_MASK (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)
/* by default activate onboard baro */
#ifndef USE_BARO_BOARD
#define USE_BARO_BOARD 1
#endif
#endif /* CONFIG_OPENPILOT_REVO_1_0_H */
@@ -69,6 +69,60 @@ PRINT_CONFIG_VAR(IMU_MPU_GYRO_RANGE)
#endif
PRINT_CONFIG_VAR(IMU_MPU_ACCEL_RANGE)
// Default channels order
#ifndef IMU_MPU_CHAN_X
#define IMU_MPU_CHAN_X 0
#endif
PRINT_CONFIG_VAR(IMU_MPU_CHAN_X)
#ifndef IMU_MPU_CHAN_Y
#define IMU_MPU_CHAN_Y 1
#endif
PRINT_CONFIG_VAR(IMU_MPU_CHAN_Y)
#ifndef IMU_MPU_CHAN_Z
#define IMU_MPU_CHAN_Z 2
#endif
PRINT_CONFIG_VAR(IMU_MPU_CHAN_Z)
#ifndef IMU_MPU_X_SIGN
#define IMU_MPU_X_SIGN 1
#endif
PRINT_CONFIG_VAR(IMU_MPU_X_SIGN)
#ifndef IMU_MPU_Y_SIGN
#define IMU_MPU_Y_SIGN 1
#endif
PRINT_CONFIG_VAR(IMU_MPU_Y_SIGN)
#ifndef IMU_MPU_Z_SIGN
#define IMU_MPU_Z_SIGN 1
#endif
PRINT_CONFIG_VAR(IMU_MPU_Z_SIGN)
/* mag by default rotated by 90deg around z axis relative to MPU */
#ifndef IMU_HMC_CHAN_X
#define IMU_HMC_CHAN_X 1
#endif
PRINT_CONFIG_VAR(IMU_HMC_CHAN_X)
#ifndef IMU_HMC_CHAN_Y
#define IMU_HMC_CHAN_Y 0
#endif
PRINT_CONFIG_VAR(IMU_HMC_CHAN_Y)
#ifndef IMU_HMC_CHAN_Z
#define IMU_HMC_CHAN_Z 2
#endif
PRINT_CONFIG_VAR(IMU_HMC_CHAN_Z)
#ifndef IMU_HMC_X_SIGN
#define IMU_HMC_X_SIGN 1
#endif
PRINT_CONFIG_VAR(IMU_HMC_X_SIGN)
#ifndef IMU_HMC_Y_SIGN
#define IMU_HMC_Y_SIGN -1
#endif
PRINT_CONFIG_VAR(IMU_HMC_Y_SIGN)
#ifndef IMU_HMC_Z_SIGN
#define IMU_HMC_Z_SIGN 1
#endif
PRINT_CONFIG_VAR(IMU_HMC_Z_SIGN)
struct ImuMpu6000Hmc5883 imu_mpu_hmc;
@@ -102,8 +156,21 @@ void imu_mpu_hmc_event(void)
mpu60x0_spi_event(&imu_mpu_hmc.mpu);
if (imu_mpu_hmc.mpu.data_available) {
RATES_COPY(imu.gyro_unscaled, imu_mpu_hmc.mpu.data_rates.rates);
VECT3_COPY(imu.accel_unscaled, imu_mpu_hmc.mpu.data_accel.vect);
// set channel order
struct Int32Vect3 accel = {
IMU_MPU_X_SIGN * (int32_t)(imu_mpu_hmc.mpu.data_accel.value[IMU_MPU_CHAN_X]),
IMU_MPU_Y_SIGN * (int32_t)(imu_mpu_hmc.mpu.data_accel.value[IMU_MPU_CHAN_Y]),
IMU_MPU_Z_SIGN * (int32_t)(imu_mpu_hmc.mpu.data_accel.value[IMU_MPU_CHAN_Z])
};
struct Int32Rates rates = {
IMU_MPU_X_SIGN * (int32_t)(imu_mpu_hmc.mpu.data_rates.value[IMU_MPU_CHAN_X]),
IMU_MPU_Y_SIGN * (int32_t)(imu_mpu_hmc.mpu.data_rates.value[IMU_MPU_CHAN_Y]),
IMU_MPU_Z_SIGN * (int32_t)(imu_mpu_hmc.mpu.data_rates.value[IMU_MPU_CHAN_Z])
};
// unscaled vector
VECT3_COPY(imu.accel_unscaled, accel);
RATES_COPY(imu.gyro_unscaled, rates);
imu_mpu_hmc.mpu.data_available = false;
imu_scale_gyro(&imu);
imu_scale_accel(&imu);
@@ -114,10 +181,10 @@ void imu_mpu_hmc_event(void)
/* HMC58XX event task */
hmc58xx_event(&imu_mpu_hmc.hmc);
if (imu_mpu_hmc.hmc.data_available) {
/* mag rotated by 90deg around z axis relative to MPU */
imu.mag_unscaled.x = imu_mpu_hmc.hmc.data.vect.y;
imu.mag_unscaled.y = -imu_mpu_hmc.hmc.data.vect.x;
imu.mag_unscaled.z = imu_mpu_hmc.hmc.data.vect.z;
/* mag by default rotated by 90deg around z axis relative to MPU */
imu.mag_unscaled.x = IMU_HMC_X_SIGN * imu_mpu_hmc.hmc.data.value[IMU_HMC_CHAN_X];
imu.mag_unscaled.y = IMU_HMC_Y_SIGN * imu_mpu_hmc.hmc.data.value[IMU_HMC_CHAN_Y];
imu.mag_unscaled.z = IMU_HMC_Z_SIGN * imu_mpu_hmc.hmc.data.value[IMU_HMC_CHAN_Z];
imu_mpu_hmc.hmc.data_available = false;
imu_scale_mag(&imu);
AbiSendMsgIMU_MAG_INT32(IMU_MPU6000_HMC_ID, now_ts, &imu.mag);