F3 and X-Vert support (#2113)

* Make mpu9250 compatible with mpu6500, by providing option to disable mag

* Upgrade QTC version, add more QTCreator compatibility with chibios

* F3 support

* Add priliminary support stm32f3 discovery board using chibios

* Add support for the stm32f37 xvert board by means of chibios

* Give INDI simple full control authority

* Motor driver for the vertx

* Create define out of required THD_WORKING_AREA space
This commit is contained in:
kevindehecker
2017-10-06 15:53:18 +02:00
committed by Gautier Hattenberger
parent 2581a9798c
commit 2a6ad556f1
36 changed files with 4981 additions and 203 deletions
+1 -1
View File
@@ -42,7 +42,7 @@ paparazzi.sublime-workspace
# QtCreator IDE
*.creator
*.creator.user
*.creator.user*
*.config
*.files
*.includes
+10 -3
View File
@@ -56,6 +56,7 @@ RADIO_H=$(AC_GENERATED)/radio.h
FLIGHT_PLAN_H=$(AC_GENERATED)/flight_plan.h
FLIGHT_PLAN_XML=$(AIRCRAFT_BUILD_DIR)/flight_plan.xml
SRCS_LIST=$(AIRCRAFT_BUILD_DIR)/$(TARGET)_srcs.list
TMP_LIST=$(AIRCRAFT_BUILD_DIR)/$(TARGET)_tmp.list
SETTINGS_H=$(AC_GENERATED)/settings.h
SETTINGS_XMLS=$(patsubst %,$(CONF)/%,$(SETTINGS))
SETTINGS_XMLS_DEP=$(filter-out %~,$(SETTINGS_XMLS))
@@ -155,14 +156,20 @@ all_ac_h: $(SRCS_LIST) qt_project
$(SRCS_LIST) : $(CONF_XML) $(AIRFRAME_H) $(MODULES_H) autopilot_h $(SETTINGS_H) $(MAKEFILE_AC) $(PERIODIC_H)
@echo "TARGET: " $(TARGET) > $(SRCS_LIST)
@echo "CFLAGS: " $(CFLAGS) >> $(SRCS_LIST)
@echo "CFLAGS: " $(CFLAGS) $(IINCDIR) $(TOPT) >> $(SRCS_LIST)
@echo "LDFLAGS: " $($(TARGET).LDFLAGS) >> $(SRCS_LIST)
@echo "srcs: " $($(TARGET).srcs) >> $(SRCS_LIST)
@echo -n "headers: " >> $(SRCS_LIST)
@echo $(VPATH) > $(TMP_LIST)
@echo $($(TARGET).srcs) >> $(TMP_LIST)
@echo $(CFLAGS) >> $(TMP_LIST)
@echo $(IINCDIR) >> $(TMP_LIST)
@echo $(TOPT)>> $(TMP_LIST)
@echo ../../sw/tools/find_vpaths.py $(CC) $(TMP_LIST) $(PAPARAZZI_SRC)
ifeq (,$(findstring cpp,$($(TARGET).srcs)))
$(Q)cd $(AIRBORNE) ; ../../sw/tools/find_vpaths.py $(CC) $(VPATH) + $($(TARGET).srcs) + $(CFLAGS) $(IINCDIR) $(TOPT) >> $(SRCS_LIST)
$(Q)cd $(PAPARAZZI_SRC) ; ./sw/tools/find_vpaths.py $(CC) $(TMP_LIST) $(PAPARAZZI_SRC) >> $(SRCS_LIST)
else
$(Q)cd $(AIRBORNE) ; ../../sw/tools/find_vpaths.py $(CXX) $(VPATH) + $($(TARGET).srcs) + $(CXXFLAGS) $(IINCDIR) $(TOPT) >> $(SRCS_LIST)
$(Q)cd $(PAPARAZZI_SRC) ; ./sw/tools/find_vpaths.py $(CXX) $(TMP_LIST) $(PAPARAZZI_SRC) >> $(SRCS_LIST)
endif
qt_project : $(SRCS_LIST)
+11
View File
@@ -527,4 +527,15 @@
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml"
gui_color="#b29eb22cffff"
/>
<aircraft
name="xvert"
ac_id="69"
airframe="airframes/TUDELFT/tudelft_xvert.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft_slow.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/gps.xml modules/ahrs_float_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/air_data.xml modules/gps_ubx_ucenter.xml modules/guidance_hybrid.xml"
gui_color="#ffffcccaccca"
/>
</conf>
+226
View File
@@ -0,0 +1,226 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<?xml version="1.0" encoding="UTF-8"?>
<!-- this is a quadrotor frame equiped with
* Autopilot: xvert
* IMU: MPU6500 + external HMC58XX
* Actuators: 2 PWM servo's, 2 escs through some proprietary atmega uart protocol
* GPS: Ublox through I2C
* RC: Datalink
-->
<airframe name="xvert">
<firmware name="rotorcraft">
<target name="ap" board="xvert_1.0"/>
<define name="BAT_CHECKER_DELAY" value="80" />
<!-- amount of time it take for the bat to check -->
<!-- to avoid bat low spike detection when strong pullup withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" />
<!-- To fix the 32k ram limit issue:-->
<!--<define name="PPRZ_TRIG_INT_USE_FLOAT"/>-->
<define name="PPRZ_TRIG_CONST" value="const"/>
<define name="THD_WORKING_AREA_MAIN" value="1024"/>
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<!-- in seconds-->
<module name="telemetry" type="transparent" >
<define name="MODEM_BAUD" value="57600"/>
</module>
<module name="guidance" type="hybrid"/>
<module name="motor_mixing"/>
<module name="sys_mon"/>
<module name="gps" type="ubx_ucenter"/>
<module name="send_imu_mag_current"/>
<module name="air_data"/>
<module name="imu" type="mpu9250_i2c">
<configure name="IMU_MPU9250_I2C_DEV" value="i2c1"/>
<define name="IMU_MPU9250_READ_MAG" value="FALSE"/>
<define name="IMU_MPU9250_I2C_ADDR" value="MPU9250_ADDR"/>
<define name="AHRS_ICQ_MAG_ID" value="MAG_HMC58XX_SENDER_ID" /> <!-- Meaning the external hmc-->
</module>
<module name="stabilization" type="indi_simple" />
<module name="ahrs" type="float_cmpl_quat" >
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module>
<module name="ins" type="float_invariant">
<define name="INS_PROPAGATE_FREQUENCY" value="500"/>
<define name="INS_FINV_MAG_ID" value="MAG_HMC58XX_SENDER_ID"/>
</module>
<module name="actuators" type="xvert">
<define name="SERVO_HZ" value="400" />
</module>
<module name="radio_control" type="datalink"/>
<module name="gps" type="ubx_i2c">
<configure name="GPS_UBX_I2C_DEV" value="i2c2"/>
</module>
<module name="mag" type="hmc58xx">
<configure name="MAG_HMC58XX_I2C_DEV" value="i2c2"/>
<define name="MODULE_HMC58XX_UPDATE_AHRS" value="TRUE"/>
<define name="HMC58XX_CHAN_X" value="1"/>
<define name="HMC58XX_CHAN_Y" value="0"/>
<define name="HMC58XX_CHAN_Z" value="2"/>
<define name="HMC58XX_CHAN_X_SIGN" value="-"/>
<define name="HMC58XX_CHAN_Y_SIGN" value="+"/>
<define name="HMC58XX_CHAN_Z_SIGN" value="+"/>
</module>
</firmware>
<section name="INS" prefix="INS_">
<define name="H_X" value="0.5138"/>
<define name="H_Y" value="0.00019"/>
<define name="H_Z" value="0.8578"/>
</section>
<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="ACCEL_X_NEUTRAL" value="-52"/>
<define name="ACCEL_Y_NEUTRAL" value="-4"/>
<define name="ACCEL_Z_NEUTRAL" value="-7"/>
<define name="ACCEL_X_SENS" value="2.45056441681" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.44991708802" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.44199722843" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="90." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
</section>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<servos driver="Xvert">
<servo name="RM" no="0" min="1160" neutral="1200" max="1880"/>
<servo name="LM" no="1" min="1160" neutral="1200" max="1880"/>
<servo name="ELEVON_RIGHT" no="2" min="1000" neutral="1500" max="2000"/>
<servo name="ELEVON_LEFT" no="3" min="1000" neutral="1500" max="2000"/>
</servos>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="RM" value="motor_mixing.commands[0]"/>
<set servo="LM" value="motor_mixing.commands[1]"/>
<!-- Mode dependent actuator laws for the elevons. The elevons act different in rc attitude flight mode-->
<!-- First the correct feedback is stored in variables -->
<let var="aileron_feedback_left" value="@YAW"/>
<let var="aileron_feedback_right" value="@YAW"/>
<let var="elevator_feedback_left" value="-@PITCH"/>
<let var="elevator_feedback_right" value="+@PITCH"/>
<!-- if using PID with gain scheduling -->
<let var="forward_left" value="$aileron_feedback_left + $elevator_feedback_left"/>
<let var="forward_right" value="$aileron_feedback_right + $elevator_feedback_right"/>
<!-- This statement tells the autopilot to use the hover feedback if in mode attitude direct and to use the forward feedback in all other cases-->
<set servo="ELEVON_LEFT" value="$forward_left" />
<set servo="ELEVON_RIGHT" value="$forward_right" />
</command_laws>
<section name="AIR_DATA" prefix="AIR_DATA_">
<define name="CALC_AIRSPEED" value="FALSE" />
<define name="CALC_TAS_FACTOR" value="FALSE" />
<define name="CALC_AMSL_BARO" value="TRUE" />
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg" />
<define name="SP_MAX_THETA" value="45" unit="deg" />
<define name="SP_MAX_R" value="300" unit="deg/s" />
<define name="DEADBAND_A" value="0" />
<define name="DEADBAND_E" value="0" />
<define name="DEADBAND_R" value="50" />
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.01292" />
<define name="G1_Q" value="0.014867" />
<define name="G1_R" value="0.012055" />
<define name="G2_R" value="0.0" />
<!-- For the bebop2 we need to filter the roll rate due to the dampers -->
<define name="FILTER_ROLL_RATE" value="FALSE" />
<define name="FILTER_PITCH_RATE" value="FALSE" />
<define name="FILTER_YAW_RATE" value="FALSE" />
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="100.0" />
<define name="REF_ERR_Q" value="100.0" />
<define name="REF_ERR_R" value="100.0" />
<define name="REF_RATE_P" value="14.0" />
<define name="REF_RATE_Q" value="14.0" />
<define name="REF_RATE_R" value="14.0" />
<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="3.2"/>
<define name="FILT_CUTOFF_R" value="3.2"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.04" />
<define name="ACT_DYN_Q" value="0.04" />
<define name="ACT_DYN_R" value="0.04" />
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE" />
<define name="ADAPTIVE_MU" value="0.0001" />
<!-- max rates (conservative) -->
<define name="STABILIZATION_INDI_MAX_RATE" value="343.77" unit="deg/s"/>
<define name="STABILIZATION_INDI_MAX_R" value="200" unit="deg/s"/> <!--Does not seem to be applied-->
<define name="FULL_AUTHORITY" value="TRUE"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="350" />
<define name="HOVER_KD" value="85" />
<define name="HOVER_KI" value="20" />
<define name="NOMINAL_HOVER_THROTTLE" value="0.6" />
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE" />
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg" />
<define name="REF_MAX_SPEED" value="2" unit="m/s" />
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="50" />
<define name="DGAIN" value="100" />
<define name="IGAIN" value="30" />
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="4.5" />
<define name="DESCEND_VSPEED" value="-1.0" />
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT" />
<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_RC_DIRECT" />
<define name="NO_RC_THRUST_LIMIT" value="TRUE" />
</section>
<section name="BAT">
<!-- 2S LiPo with 950mAh -->
<define name="LOW_BAT_LEVEL" value="7.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="7.3" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.4" unit="V"/>
</section>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="2"/>
<define name="SCALE" value="256"/>
<define name="PITCH_COEF" value="{ 0, 0}"/>
<define name="ROLL_COEF" value="{ -256, 256 }"/>
<define name="YAW_COEF" value="{ 0, 0 }"/>
<define name="THRUST_COEF" value="{ 256, 256 }"/>
</section>
</airframe>
@@ -0,0 +1,76 @@
# Hey Emacs, this is a -*- makefile -*-
#
# stm32f3_discovery_chibios.makefile
#
#
BOARD=stm32f3_discovery
BOARD_VERSION=1.0
BOARD_DIR=$(BOARD)/chibios/v$(BOARD_VERSION)
BOARD_CFG=\"boards/$(BOARD_DIR)/board.h\"
ARCH=chibios
$(TARGET).ARCHDIR = $(ARCH)
RTOS=chibios
## FPU on F3
USE_FPU=hard
$(TARGET).CFLAGS += -DSTM32F3 -DPPRZLINK_ENABLE_FD
##############################################################################
# Architecture or project specific options
#
# Define project name here (target)
PROJECT = $(TARGET)
# Project specific files and paths (see Makefile.chibios for details)
CHIBIOS_BOARD_PLATFORM = STM32F3xx/platform.mk
CHIBIOS_BOARD_LINKER = STM32F303xC.ld
CHIBIOS_BOARD_STARTUP = startup_stm32f3xx.mk
##############################################################################
# Compiler settings
#
MCU = cortex-m4
# default flash mode is via DFU-UTIL
# possibilities: DFU-UTIL, SWD, STLINK
FLASH_MODE ?= DFU-UTIL
HAS_LUFTBOOT = FALSE
#
# default LED configuration
#
RADIO_CONTROL_LED ?= 4
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 5
GPS_LED ?= 6
SYS_TIME_LED ?= 3
#
# default UART configuration (modem, gps, spektrum)
#
MODEM_PORT ?= UART1
MODEM_BAUD ?= B57600
GPS_PORT ?= UART2
GPS_BAUD ?= B38400
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART3
SBUS_PORT ?= UART3
#
# 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
+71
View File
@@ -0,0 +1,71 @@
# Hey Emacs, this is a -*- makefile -*-
#
# stm32f37_vortex_chibios.makefile
#
#
BOARD=xvert
BOARD_VERSION=1.0
BOARD_DIR=$(BOARD)/chibios/v$(BOARD_VERSION)
BOARD_CFG=\"boards/$(BOARD_DIR)/board.h\"
ARCH=chibios
$(TARGET).ARCHDIR = $(ARCH)
RTOS=chibios
## FPU on F3
##TODO: there is some bug when using the hard FPU unit!!
USE_FPU=no
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
##############################################################################
# Architecture or project specific options
#
# Define project name here (target)
PROJECT = $(TARGET)
# Project specific files and paths (see Makefile.chibios for details)
CHIBIOS_BOARD_PLATFORM = STM32F37x/platform.mk
CHIBIOS_BOARD_LINKER = STM32F373xC.ld
CHIBIOS_BOARD_STARTUP = startup_stm32f3xx.mk
##############################################################################
# Compiler settings
#
MCU = cortex-m4
# default flash mode is via DFU-UTIL
# possibilities: DFU-UTIL, SWD, SWD_NOPWR, STLINK
FLASH_MODE ?= SWD_NOPWR
HAS_LUFTBOOT = FALSE
#
# default LED configuration
#
SYS_TIME_LED ?= 1
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 2
GPS_LED ?= none
#
# default UART configuration (modem, gps, spektrum)
#
MODEM_PORT ?= UART2
MODEM_BAUD ?= B57600
#
# 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_xvert
@@ -286,6 +286,15 @@ else ifeq ($(BOARD), chimera)
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c
else ifeq ($(BOARD), xvert)
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_I2C
BARO_BOARD_CFLAGS += -DUSE_I2C2
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c2
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_ADDR=MS5611_I2C_SLAVE_ADDR_ALT
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c
else ifeq ($(BOARD), vms_ecu)
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_SPI
include $(CFG_SHARED)/spi_master.makefile
+25
View File
@@ -0,0 +1,25 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="actuators_esc32" dir="actuators" task="actuators">
<doc>
<description>
Actuators Driver for x-vert vtol escs
</description>
<configure name="ESCS_PORT" value="usb_serial" description="Port used to connect to the atmegas escs."/>
<configure name="ESCS_BAUD" value="250000" description="Baud rate for ESCS_PORT if a UART"/>
</doc>
<header>
<file name="actuators_xvert.h" dir="subsystems/actuators"/>
</header>
<makefile target="ap">
<define name="ACTUATORS"/>
<file_arch name="actuators_xvert.c" dir="subsystems/actuators"/>
<file_arch name="actuators_pwm_arch.c" dir="subsystems/actuators"/>
<configure name="ESCS_PORT" default="uart1" case="upper|lower"/>
<configure name="ESCS_BAUD" default="250000"/>
<define name="USE_$(ESCS_PORT_UPPER)"/>
<define name="ESCS_UART" value="$(ESCS_PORT_LOWER)"/>
<define name="$(ESCS_PORT_UPPER)_BAUD" value="$(ESCS_BAUD)"/>
</makefile>
</module>
@@ -44,6 +44,7 @@
<define name="ACT_DYN_R" value="0.1" description="first order actuator dynamics on yaw rate"/>
<define name="USE_ADAPTIVE" value="FALSE|TRUE" description="enable adaptive gains"/>
<define name="ADAPTIVE_MU" value="0.0001" description="adaptation parameter"/>
<define name="FULL_AUTHORITY" value="FALSE" description="Enable full control authority"/>
</section>
</doc>
<settings>
+32 -7
View File
@@ -75,6 +75,11 @@
// STM32F4xx | STM32F7xx
#define ADC_SAMPLE_RATE ADC_SAMPLE_480
#define ADC_CR2_CFG ADC_CR2_SWSTART
#elif defined(__STM32F373xC_H)
#define ADC_SAMPLE_RATE ADC_SAMPLE_239P5
#define ADC_CR2_CFG ADC_CR2_SWSTART
#elif defined(__STM32F3xx_H)
#define ADC_SAMPLE_RATE ADC_SMPR_SMP_601P5
#endif
@@ -246,7 +251,7 @@ void adc1callback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
(adc_watchdog.cb != NULL)) {
if (adc1_buffers[adc_watchdog.channel]->sum <
(adc1_buffers[adc_watchdog.channel]->av_nb_sample * adc_watchdog.vmin)) {
adc_watchdog.cb ();
adc_watchdog.cb();
}
}
#endif // USE_ADC_WATCHDOG
@@ -276,7 +281,7 @@ static void adcerrorcallback(ADCDriver *adcp, adcerror_t err)
void adc_buf_channel(uint8_t adc_channel, struct adc_buf *s, uint8_t av_nb_sample)
{
// check for out-of-bounds access
if (adc_channel >= ADC_NUM_CHANNELS) return;
if (adc_channel >= ADC_NUM_CHANNELS) { return; }
adc1_buffers[adc_channel] = s;
if (av_nb_sample <= MAX_AV_NB_SAMPLE) {
s->av_nb_sample = av_nb_sample;
@@ -344,25 +349,45 @@ void adc_init(void)
uint32_t smpr1, smpr2;
adc_sample_time_on_all_channels(&smpr1, &smpr2, ADC_SAMPLE_RATE);
adcgrpcfg.cr2 = ADC_CR2_CFG;
#if USE_ADC_WATCHDOG
adc_watchdog.adc = NULL;
adc_watchdog.cb = NULL;
adc_watchdog.channel = 0;
adc_watchdog.vmin = (1<<12)-1; // max adc
adc_watchdog.vmin = (1 << 12) - 1; // max adc
#endif
adcgrpcfg.circular = TRUE;
adcgrpcfg.num_channels = ADC_NUM_CHANNELS;
adcgrpcfg.end_cb = adc1callback;
adcgrpcfg.error_cb = adcerrorcallback;
#if defined(__STM32F373xC_H)
adcgrpcfg.u.adc.smpr[0] = smpr1;
adcgrpcfg.u.adc.smpr[1] = smpr2;
adcgrpcfg.u.adc.sqr[0] = sqr1;
adcgrpcfg.u.adc.sqr[1] = sqr2;
adcgrpcfg.u.adc.sqr[2] = sqr3;
adcgrpcfg.u.adc.cr1 = 0;
adcgrpcfg.u.adc.cr2 = ADC_CR2_CFG;
#elif defined(__STM32F3xx_H)
//TODO: check if something needs to be done with the other regs (can be found in ~/paparazzi/sw/ext/chibios/os/hal/ports/STM32/LLD/ADCv3)
#warning ADCs not tested with stm32f30
// cfgr
// tr1
adcgrpcfg.smpr[0] = smpr1; // is this even correct?
adcgrpcfg.smpr[1] = smpr2;
adcgrpcfg.sqr[0] = sqr1;
adcgrpcfg.sqr[1] = sqr2;
adcgrpcfg.sqr[2] = sqr3;
#else
adcgrpcfg.cr2 = ADC_CR2_CFG;
adcgrpcfg.cr1 = 0;
adcgrpcfg.smpr1 = smpr1;
adcgrpcfg.smpr2 = smpr2;
adcgrpcfg.sqr1 = sqr1;
adcgrpcfg.sqr2 = sqr2;
adcgrpcfg.sqr3 = sqr3;
#endif
// Start ADC in continious conversion mode
adcStart(&ADCD1, NULL);
@@ -371,9 +396,9 @@ void adc_init(void)
#if USE_ADC_WATCHDOG
void register_adc_watchdog(ADCDriver *adc, adc_channels_num_t channel, adcsample_t vmin,
adc_watchdog_callback cb)
adc_watchdog_callback cb)
{
for (int i=0; i< NB_ADC1_CHANNELS; i++) { // FIXME when more than ADC1 will be in use
for (int i = 0; i < NB_ADC1_CHANNELS; i++) { // FIXME when more than ADC1 will be in use
if (adc_channel_map[i] == channel) {
adc_watchdog.adc = adc;
adc_watchdog.channel = i;
@@ -68,8 +68,8 @@ void gpio_setup_pin_af(ioportid_t port, uint16_t pin, uint8_t af, bool is_output
(void)pin;
(void)af;
(void)is_output;
#elif defined(STM32F4) || defined(STM32F7)
// STM32F4xx and STM32F7xx
#elif defined(STM32F4) || defined(STM32F3) || defined(STM32F7)
// STM32F4xx, STM32F3xx and STM32F7xx
if (af) {
palSetPadMode(port, pin, PAL_MODE_ALTERNATE(af));
} else {
+33 -34
View File
@@ -57,7 +57,7 @@ struct i2c_init {
static void handle_i2c_thd(struct i2c_periph *p);
// Timeout for I2C transaction
static const systime_t tmo = US2ST(1000000/PERIODIC_FREQUENCY);
static const systime_t tmo = US2ST(10000000 / PERIODIC_FREQUENCY);
/**
* main thread function
@@ -69,7 +69,7 @@ static void handle_i2c_thd(struct i2c_periph *p)
struct i2c_init *i = (struct i2c_init *) p->init_struct;
// wait for a transaction to be pushed in the queue
chSemWait (i->sem);
chSemWait(i->sem);
if (p->trans_insert_idx == p->trans_extract_idx) {
p->status = I2CIdle;
@@ -86,38 +86,38 @@ static void handle_i2c_thd(struct i2c_periph *p)
if (t->len_w > 0) {
#if defined STM32F7
// we do stupid mem copy because F7 needs a special RAM for DMA operation
memcpy(i->dma_buf, (void*)t->buf, (size_t)(t->len_w));
memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w));
status = i2cMasterTransmitTimeout(
(I2CDriver*)p->reg_addr,
(i2caddr_t)((t->slave_addr)>>1),
(uint8_t*)i->dma_buf, (size_t)(t->len_w),
(uint8_t*)i->dma_buf, (size_t)(t->len_r),
tmo);
memcpy((void*)t->buf, i->dma_buf, (size_t)(t->len_r));
(I2CDriver *)p->reg_addr,
(i2caddr_t)((t->slave_addr) >> 1),
(uint8_t *)i->dma_buf, (size_t)(t->len_w),
(uint8_t *)i->dma_buf, (size_t)(t->len_r),
tmo);
memcpy((void *)t->buf, i->dma_buf, (size_t)(t->len_r));
#else
status = i2cMasterTransmitTimeout(
(I2CDriver*)p->reg_addr,
(i2caddr_t)((t->slave_addr)>>1),
(uint8_t*)t->buf, (size_t)(t->len_w),
(uint8_t*)t->buf, (size_t)(t->len_r),
tmo);
(I2CDriver *)p->reg_addr,
(i2caddr_t)((t->slave_addr) >> 1),
(uint8_t *)t->buf, (size_t)(t->len_w),
(uint8_t *)t->buf, (size_t)(t->len_r),
tmo);
#endif
} else {
#if defined STM32F7
// we do stupid mem copy because F7 needs a special RAM for DMA operation
memcpy(i->dma_buf, (void*)t->buf, (size_t)(t->len_w));
memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w));
status = i2cMasterReceiveTimeout(
(I2CDriver*)p->reg_addr,
(i2caddr_t)((t->slave_addr)>>1),
(uint8_t*)i->dma_buf, (size_t)(t->len_r),
tmo);
memcpy((void*)t->buf, i->dma_buf, (size_t)(t->len_r));
(I2CDriver *)p->reg_addr,
(i2caddr_t)((t->slave_addr) >> 1),
(uint8_t *)i->dma_buf, (size_t)(t->len_r),
tmo);
memcpy((void *)t->buf, i->dma_buf, (size_t)(t->len_r));
#else
status = i2cMasterReceiveTimeout(
(I2CDriver*)p->reg_addr,
(i2caddr_t)((t->slave_addr)>>1),
(uint8_t*)t->buf, (size_t)(t->len_r),
tmo);
(I2CDriver *)p->reg_addr,
(i2caddr_t)((t->slave_addr) >> 1),
(uint8_t *)t->buf, (size_t)(t->len_r),
tmo);
#endif
}
@@ -140,13 +140,13 @@ static void handle_i2c_thd(struct i2c_periph *p)
//if a timeout occurred before operation end
// mark as failed and restart
t->status = I2CTransFailed;
i2cStart((I2CDriver*)p->reg_addr, i->cfg);
i2cStart((I2CDriver *)p->reg_addr, i->cfg);
break;
case MSG_RESET:
//if one or more I2C errors occurred, the errors can
//be retrieved using @p i2cGetErrors().
t->status = I2CTransFailed;
i2cflags_t errors = i2cGetErrors((I2CDriver*)p->reg_addr);
i2cflags_t errors = i2cGetErrors((I2CDriver *)p->reg_addr);
if (errors & I2C_BUS_ERROR) {
p->errors->miss_start_stop_cnt++;
}
@@ -198,7 +198,7 @@ static struct i2c_init i2c1_init_s = {
struct i2c_errors i2c1_errors;
// Thread
static __attribute__((noreturn)) void thd_i2c1(void *arg);
static THD_WORKING_AREA(wa_thd_i2c1, 1024);
static THD_WORKING_AREA(wa_thd_i2c1, 128);
/*
* I2C1 init
@@ -211,7 +211,7 @@ void i2c1_hw_init(void)
i2c1.init_struct = &i2c1_init_s;
// Create thread
chThdCreateStatic(wa_thd_i2c1, sizeof(wa_thd_i2c1),
NORMALPRIO+1, thd_i2c1, NULL);
NORMALPRIO + 1, thd_i2c1, NULL);
}
/*
@@ -252,7 +252,7 @@ static struct i2c_init i2c2_init_s = {
struct i2c_errors i2c2_errors;
// Thread
static __attribute__((noreturn)) void thd_i2c2(void *arg);
static THD_WORKING_AREA(wa_thd_i2c2, 1024);
static THD_WORKING_AREA(wa_thd_i2c2, 128);
/*
* I2C2 init
@@ -261,12 +261,11 @@ void i2c2_hw_init(void)
{
i2cStart(&I2CD2, &i2cfg2);
i2c2.reg_addr = &I2CD2;
i2c2.init_struct = NULL;
i2c2.errors = &i2c2_errors;
i2c2.init_struct = &i2c2_init_s;
// Create thread
chThdCreateStatic(wa_thd_i2c2, sizeof(wa_thd_i2c2),
NORMALPRIO+1, thd_i2c2, NULL);
NORMALPRIO + 1, thd_i2c2, NULL);
}
/*
@@ -307,7 +306,7 @@ static struct i2c_init i2c3_init_s = {
struct i2c_errors i2c3_errors;
// Thread
static __attribute__((noreturn)) void thd_i2c3(void *arg);
static THD_WORKING_AREA(wa_thd_i2c3, 1024);
static THD_WORKING_AREA(wa_thd_i2c3, 128);
/*
* I2C3 init
@@ -321,7 +320,7 @@ void i2c3_hw_init(void)
i2c3.init_struct = &i2c3_init_s;
// Create thread
chThdCreateStatic(wa_thd_i2c3, sizeof(wa_thd_i2c3),
NORMALPRIO+1, thd_i2c3, NULL);
NORMALPRIO + 1, thd_i2c3, NULL);
}
/*
@@ -395,7 +394,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t)
p->trans_insert_idx = temp;
chSysUnlock();
chSemSignal (((struct i2c_init *)p->init_struct)->sem);
chSemSignal(((struct i2c_init *)p->init_struct)->sem);
// transaction submitted
return TRUE;
#else
+10 -1
View File
@@ -26,6 +26,11 @@
* F1
* ram0: 64ko std
*
* F3
* ram4: 8ko ccm, fast, no dma
* ram0: 40Ko std
* F37
* ram0: 32Ko std
* F4
* ram4: 64ko ccm, fast, no dma
* ram0: 128Ko std
@@ -42,6 +47,10 @@
#define STD_SECTION ".ram0"
#define FAST_SECTION ".ram0"
#define DMA_SECTION ".ram0"
#elif defined STM32F3
#define STD_SECTION ".ram0"
#define FAST_SECTION ".ram4"
#define DMA_SECTION ".ram0"
#elif defined STM32F4
#define STD_SECTION ".ram0"
#define FAST_SECTION ".ram4"
@@ -57,7 +66,7 @@
#define IN_STD_SECTION_NOINIT(var) var __attribute__ ((section(STD_SECTION), aligned(8)))
#define IN_STD_SECTION_CLEAR(var) var __attribute__ ((section(STD_SECTION "_clear"), aligned(8)))
#define IN_STD_SECTION(var) var __attribute__ ((section(STD_SECTION "_init"), aligned(8)))
#define IN_FAST_SECTION_NOINIT(var) var __attribute__ ((section(FAST_SECTION), aligned(8)))
#define IN_FAST_SECTION_CLEAR(var) var __attribute__ ((section(FAST_SECTION "_clear"), aligned(8)))
#define IN_FAST_SECTION(var) var __attribute__ ((section(FAST_SECTION "_init"), aligned(8)))
+11 -12
View File
@@ -224,8 +224,7 @@ static inline uint16_t spi_resolve_CR2(struct spi_transaction *t __attribute__((
#if defined(STM32F7)
if (t->dss == SPIDss16bit) {
CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2 | SPI_CR2_DS_3;
}
else {
} else {
CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2;
}
#endif /* STM32F7 */
@@ -242,7 +241,7 @@ static void handle_spi_thd(struct spi_periph *p)
struct spi_init *i = (struct spi_init *) p->init_struct;
// wait for a transaction to be pushed in the queue
chSemWait (i->sem);
chSemWait(i->sem);
if ((p->trans_insert_idx == p->trans_extract_idx) || p->suspend) {
p->status = SPIIdle;
@@ -284,11 +283,11 @@ static void handle_spi_thd(struct spi_periph *p)
// Start synchronous data transfer
#if defined STM32F7
// we do stupid mem copy because F7 needs a special RAM for DMA operation
memcpy(i->dma_buf_out, (void*)t->output_buf, (size_t)t->output_length);
memcpy(i->dma_buf_out, (void *)t->output_buf, (size_t)t->output_length);
spiExchange((SPIDriver *)p->reg_addr, t_length, i->dma_buf_out, i->dma_buf_in);
memcpy((void*)t->input_buf, i->dma_buf_in, (size_t)t->input_length);
memcpy((void *)t->input_buf, i->dma_buf_in, (size_t)t->input_length);
#else
spiExchange((SPIDriver *)p->reg_addr, t_length, (uint8_t*)t->output_buf, (uint8_t*)t->input_buf);
spiExchange((SPIDriver *)p->reg_addr, t_length, (uint8_t *)t->output_buf, (uint8_t *)t->input_buf);
#endif
// Unselect the slave
@@ -347,7 +346,7 @@ static __attribute__((noreturn)) void thd_spi1(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_spi1, 1024);
static THD_WORKING_AREA(wa_thd_spi1, 256);
void spi1_arch_init(void)
{
@@ -355,7 +354,7 @@ void spi1_arch_init(void)
spi1.init_struct = &spi1_init_s;
// Create thread
chThdCreateStatic(wa_thd_spi1, sizeof(wa_thd_spi1),
NORMALPRIO+1, thd_spi1, NULL);
NORMALPRIO + 1, thd_spi1, NULL);
}
#endif
@@ -386,7 +385,7 @@ static __attribute__((noreturn)) void thd_spi2(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_spi2, 1024);
static THD_WORKING_AREA(wa_thd_spi2, 256);
void spi2_arch_init(void)
{
@@ -394,7 +393,7 @@ void spi2_arch_init(void)
spi2.init_struct = &spi2_init_s;
// Create thread
chThdCreateStatic(wa_thd_spi2, sizeof(wa_thd_spi2),
NORMALPRIO+1, thd_spi2, NULL);
NORMALPRIO + 1, thd_spi2, NULL);
}
#endif
@@ -433,7 +432,7 @@ void spi3_arch_init(void)
spi3.init_struct = &spi3_init_s;
// Create thread
chThdCreateStatic(wa_thd_spi3, sizeof(wa_thd_spi3),
NORMALPRIO+1, thd_spi3, NULL);
NORMALPRIO + 1, thd_spi3, NULL);
}
#endif
@@ -477,7 +476,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
p->trans_insert_idx = idx;
chSysUnlock();
chSemSignal (((struct spi_init *)p->init_struct)->sem);
chSemSignal(((struct spi_init *)p->init_struct)->sem);
// transaction submitted
return TRUE;
}
+50 -51
View File
@@ -54,9 +54,9 @@ struct SerialInit {
static void handle_uart_rx(struct uart_periph *p)
{
// wait for next incoming byte
uint8_t c = sdGet((SerialDriver*)(p->reg_addr));
uint8_t c = sdGet((SerialDriver *)(p->reg_addr));
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
chMtxLock(init_struct->rx_mtx);
uint16_t temp = (p->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE;;
// insert new byte
@@ -75,8 +75,8 @@ static void handle_uart_rx(struct uart_periph *p)
static void handle_uart_tx(struct uart_periph *p)
{
// check if more data to send
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
chSemWait (init_struct->tx_sem);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
chSemWait(init_struct->tx_sem);
while (p->tx_insert_idx != p->tx_extract_idx) {
uint8_t data = p->tx_buf[p->tx_extract_idx];
p->tx_running = true;
@@ -128,7 +128,7 @@ static __attribute__((noreturn)) void thd_uart1_rx(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_uart1_rx, 1024);
static THD_WORKING_AREA(wa_thd_uart1_rx, 256);
#endif
#if USE_UART1_TX
@@ -144,7 +144,7 @@ static __attribute__((noreturn)) void thd_uart1_tx(void *arg)
handle_uart_tx(&uart1);
}
}
static THD_WORKING_AREA(wa_thd_uart1_tx, 1024);
static THD_WORKING_AREA(wa_thd_uart1_tx, 256);
#endif
void uart1_init(void)
@@ -170,13 +170,13 @@ void uart1_init(void)
uart1_init_struct.rx_mtx = &uart1_rx_mtx;
uart1_init_struct.rx_sem = &uart1_rx_sem;
chThdCreateStatic(wa_thd_uart1_rx, sizeof(wa_thd_uart1_rx),
NORMALPRIO+1, thd_uart1_rx, NULL);
NORMALPRIO + 1, thd_uart1_rx, NULL);
#endif
#if USE_UART1_TX
uart1_init_struct.tx_mtx = &uart1_tx_mtx;
uart1_init_struct.tx_sem = &uart1_tx_sem;
chThdCreateStatic(wa_thd_uart1_tx, sizeof(wa_thd_uart1_tx),
NORMALPRIO+1, thd_uart1_tx, NULL);
NORMALPRIO + 1, thd_uart1_tx, NULL);
#endif
}
@@ -230,7 +230,7 @@ static __attribute__((noreturn)) void thd_uart2_rx(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_uart2_rx, 1024);
static THD_WORKING_AREA(wa_thd_uart2_rx, 256);
#endif
#if USE_UART2_TX
@@ -246,7 +246,7 @@ static __attribute__((noreturn)) void thd_uart2_tx(void *arg)
handle_uart_tx(&uart2);
}
}
static THD_WORKING_AREA(wa_thd_uart2_tx, 1024);
static THD_WORKING_AREA(wa_thd_uart2_tx, 256);
#endif
void uart2_init(void)
@@ -272,13 +272,13 @@ void uart2_init(void)
uart2_init_struct.rx_mtx = &uart2_rx_mtx;
uart2_init_struct.rx_sem = &uart2_rx_sem;
chThdCreateStatic(wa_thd_uart2_rx, sizeof(wa_thd_uart2_rx),
NORMALPRIO, thd_uart2_rx, NULL);
NORMALPRIO, thd_uart2_rx, NULL);
#endif
#if USE_UART2_TX
uart2_init_struct.tx_mtx = &uart2_tx_mtx;
uart2_init_struct.tx_sem = &uart2_tx_sem;
chThdCreateStatic(wa_thd_uart2_tx, sizeof(wa_thd_uart2_tx),
NORMALPRIO, thd_uart2_tx, NULL);
NORMALPRIO, thd_uart2_tx, NULL);
#endif
}
@@ -322,7 +322,7 @@ static __attribute__((noreturn)) void thd_uart3_rx(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_uart3_rx, 1024);
static THD_WORKING_AREA(wa_thd_uart3_rx, 256);
#endif
#if USE_UART3_TX
@@ -338,7 +338,7 @@ static __attribute__((noreturn)) void thd_uart3_tx(void *arg)
handle_uart_tx(&uart3);
}
}
static THD_WORKING_AREA(wa_thd_uart3_tx, 1024);
static THD_WORKING_AREA(wa_thd_uart3_tx, 256);
#endif
void uart3_init(void)
@@ -364,13 +364,13 @@ void uart3_init(void)
uart3_init_struct.rx_mtx = &uart3_rx_mtx;
uart3_init_struct.rx_sem = &uart3_rx_sem;
chThdCreateStatic(wa_thd_uart3_rx, sizeof(wa_thd_uart3_rx),
NORMALPRIO, thd_uart3_rx, NULL);
NORMALPRIO, thd_uart3_rx, NULL);
#endif
#if USE_UART3_TX
uart3_init_struct.tx_mtx = &uart3_tx_mtx;
uart3_init_struct.tx_sem = &uart3_tx_sem;
chThdCreateStatic(wa_thd_uart3_tx, sizeof(wa_thd_uart3_tx),
NORMALPRIO, thd_uart3_tx, NULL);
NORMALPRIO, thd_uart3_tx, NULL);
#endif
}
@@ -414,7 +414,7 @@ static __attribute__((noreturn)) void thd_uart4_rx(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_uart4_rx, 1024);
static THD_WORKING_AREA(wa_thd_uart4_rx, 256);
#endif
#if USE_UART4_TX
@@ -430,7 +430,7 @@ static __attribute__((noreturn)) void thd_uart4_tx(void *arg)
handle_uart_tx(&uart4);
}
}
static THD_WORKING_AREA(wa_thd_uart4_tx, 1024);
static THD_WORKING_AREA(wa_thd_uart4_tx, 256);
#endif
void uart4_init(void)
@@ -456,13 +456,13 @@ void uart4_init(void)
uart4_init_struct.rx_mtx = &uart4_rx_mtx;
uart4_init_struct.rx_sem = &uart4_rx_sem;
chThdCreateStatic(wa_thd_uart4_rx, sizeof(wa_thd_uart4_rx),
NORMALPRIO, thd_uart4_rx, NULL);
NORMALPRIO, thd_uart4_rx, NULL);
#endif
#if USE_UART4_TX
uart4_init_struct.tx_mtx = &uart4_tx_mtx;
uart4_init_struct.tx_sem = &uart4_tx_sem;
chThdCreateStatic(wa_thd_uart4_tx, sizeof(wa_thd_uart4_tx),
NORMALPRIO, thd_uart4_tx, NULL);
NORMALPRIO, thd_uart4_tx, NULL);
#endif
}
@@ -506,7 +506,7 @@ static __attribute__((noreturn)) void thd_uart5_rx(void *arg)
}
}
static THD_WORKING_AREA(wa_thd_uart5_rx, 1024);
static THD_WORKING_AREA(wa_thd_uart5_rx, 256);
#endif
#if USE_UART5_TX
@@ -522,7 +522,7 @@ static __attribute__((noreturn)) void thd_uart5_tx(void *arg)
handle_uart_tx(&uart5);
}
}
static THD_WORKING_AREA(wa_thd_uart5_tx, 1024);
static THD_WORKING_AREA(wa_thd_uart5_tx, 256);
#endif
void uart5_init(void)
@@ -548,13 +548,13 @@ void uart5_init(void)
uart5_init_struct.rx_mtx = &uart5_rx_mtx;
uart5_init_struct.rx_sem = &uart5_rx_sem;
chThdCreateStatic(wa_thd_uart5_rx, sizeof(wa_thd_uart5_rx),
NORMALPRIO, thd_uart5_rx, NULL);
NORMALPRIO, thd_uart5_rx, NULL);
#endif
#if USE_UART5_TX
uart5_init_struct.tx_mtx = &uart5_tx_mtx;
uart5_init_struct.tx_sem = &uart5_tx_sem;
chThdCreateStatic(wa_thd_uart5_tx, sizeof(wa_thd_uart5_tx),
NORMALPRIO, thd_uart5_tx, NULL);
NORMALPRIO, thd_uart5_tx, NULL);
#endif
}
@@ -640,13 +640,13 @@ void uart6_init(void)
uart6_init_struct.rx_mtx = &uart6_rx_mtx;
uart6_init_struct.rx_sem = &uart6_rx_sem;
chThdCreateStatic(wa_thd_uart6_rx, sizeof(wa_thd_uart6_rx),
NORMALPRIO, thd_uart6_rx, NULL);
NORMALPRIO, thd_uart6_rx, NULL);
#endif
#if USE_UART6_TX
uart6_init_struct.tx_mtx = &uart6_tx_mtx;
uart6_init_struct.tx_sem = &uart6_tx_sem;
chThdCreateStatic(wa_thd_uart6_tx, sizeof(wa_thd_uart6_tx),
NORMALPRIO, thd_uart6_tx, NULL);
NORMALPRIO, thd_uart6_tx, NULL);
#endif
}
@@ -732,13 +732,13 @@ void uart7_init(void)
uart7_init_struct.rx_mtx = &uart7_rx_mtx;
uart7_init_struct.rx_sem = &uart7_rx_sem;
chThdCreateStatic(wa_thd_uart7_rx, sizeof(wa_thd_uart7_rx),
NORMALPRIO, thd_uart7_rx, NULL);
NORMALPRIO, thd_uart7_rx, NULL);
#endif
#if USE_UART7_TX
uart7_init_struct.tx_mtx = &uart7_tx_mtx;
uart7_init_struct.tx_sem = &uart7_tx_sem;
chThdCreateStatic(wa_thd_uart7_tx, sizeof(wa_thd_uart7_tx),
NORMALPRIO, thd_uart7_tx, NULL);
NORMALPRIO, thd_uart7_tx, NULL);
#endif
}
@@ -824,13 +824,13 @@ void uart8_init(void)
uart8_init_struct.rx_mtx = &uart8_rx_mtx;
uart8_init_struct.rx_sem = &uart8_rx_sem;
chThdCreateStatic(wa_thd_uart8_rx, sizeof(wa_thd_uart8_rx),
NORMALPRIO, thd_uart8_rx, NULL);
NORMALPRIO, thd_uart8_rx, NULL);
#endif
#if USE_UART8_TX
uart8_init_struct.tx_mtx = &uart8_tx_mtx;
uart8_init_struct.tx_sem = &uart8_tx_sem;
chThdCreateStatic(wa_thd_uart8_tx, sizeof(wa_thd_uart8_tx),
NORMALPRIO, thd_uart8_tx, NULL);
NORMALPRIO, thd_uart8_tx, NULL);
#endif
}
@@ -842,7 +842,7 @@ uint8_t uart_getch(struct uart_periph *p)
//to keep compatibility with loop oriented paparazzi architecture, read is not blocking
//struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
//chSemWait (init_struct->rx_sem);
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
chMtxLock(init_struct->rx_mtx);
uint8_t ret = p->rx_buf[p->rx_extract_idx];
p->rx_extract_idx = (p->rx_extract_idx + 1) % UART_RX_BUFFER_SIZE;
@@ -853,16 +853,16 @@ uint8_t uart_getch(struct uart_periph *p)
/**
* Set baudrate
*/
void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud )
void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
SerialConfig *conf = init_struct->conf;
// set new baudrate
conf->speed = baud;
p->baudrate = baud;
// restart periph
sdStop((SerialDriver*)(p->reg_addr));
sdStart((SerialDriver*)(p->reg_addr), conf);
sdStop((SerialDriver *)(p->reg_addr));
sdStart((SerialDriver *)(p->reg_addr), conf);
}
/**
@@ -873,7 +873,7 @@ void uart_periph_set_mode(struct uart_periph *p __attribute__((unused)), bool tx
#if defined STM32F7
#define __USART_CR1_M USART_CR1_M_0
#elif defined STM32F1 || defined STM32F4
#elif defined STM32F1 || defined STM32F4 || defined STM32F3
#define __USART_CR1_M USART_CR1_M
#else
#error unsupported board
@@ -885,7 +885,7 @@ void uart_periph_set_mode(struct uart_periph *p __attribute__((unused)), bool tx
void uart_periph_set_bits_stop_parity(struct uart_periph *p,
uint8_t bits, uint8_t stop, uint8_t parity)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
SerialConfig *conf = init_struct->conf;
/* Configure USART parity and data bits */
@@ -917,8 +917,8 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p,
conf-> cr2 |= USART_CR2_STOP1_BITS; // set bits for 1 stop
}
sdStop((SerialDriver*)(p->reg_addr));
sdStart((SerialDriver*)(p->reg_addr), conf);
sdStop((SerialDriver *)(p->reg_addr));
sdStart((SerialDriver *)(p->reg_addr), conf);
}
#ifdef STM32F7
@@ -927,7 +927,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p,
*/
void uart_periph_invert_data_logic(struct uart_periph *p, bool invert_rx, bool invert_tx)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
SerialConfig *conf = init_struct->conf;
if (invert_rx) {
conf->cr2 |= USART_CR2_RXINV; // set rxinv bit
@@ -939,8 +939,8 @@ void uart_periph_invert_data_logic(struct uart_periph *p, bool invert_rx, bool i
} else {
conf->cr2 &= ~USART_CR2_TXINV; // clear txinv bit
}
sdStop((SerialDriver*)(p->reg_addr));
sdStart((SerialDriver*)(p->reg_addr), conf);
sdStop((SerialDriver *)(p->reg_addr));
sdStart((SerialDriver *)(p->reg_addr), conf);
}
#endif
@@ -948,7 +948,7 @@ void uart_periph_invert_data_logic(struct uart_periph *p, bool invert_rx, bool i
// and lock driver with mutex
bool uart_check_free_space(struct uart_periph *p, long *fd, uint16_t len)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
int16_t space = p->tx_extract_idx - p->tx_insert_idx;
if (space <= 0) {
space += UART_TX_BUFFER_SIZE;
@@ -966,7 +966,7 @@ bool uart_check_free_space(struct uart_periph *p, long *fd, uint16_t len)
*/
void uart_put_byte(struct uart_periph *p, long fd, uint8_t data)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
if (fd == 0) {
// if fd is zero, assume the driver is not already locked
chMtxLock(init_struct->tx_mtx);
@@ -980,9 +980,8 @@ void uart_put_byte(struct uart_periph *p, long fd, uint8_t data)
chMtxUnlock(init_struct->tx_mtx);
// send signal to start transmission
chSemSignal (init_struct->tx_sem);
}
else {
chSemSignal(init_struct->tx_sem);
} else {
// assume driver is locked and available space have been checked
p->tx_buf[p->tx_insert_idx] = data;
p->tx_insert_idx = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE;
@@ -994,7 +993,7 @@ void uart_put_byte(struct uart_periph *p, long fd, uint8_t data)
*/
void uart_put_buffer(struct uart_periph *p, long fd, const uint8_t *data, uint16_t len)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
if (fd == 0) {
// if fd is zero, assume the driver is not already locked
// and available space should be checked
@@ -1018,18 +1017,18 @@ void uart_put_buffer(struct uart_periph *p, long fd, const uint8_t *data, uint16
if (fd == 0) {
chMtxUnlock(init_struct->tx_mtx);
// send signal to start transmission
chSemSignal (init_struct->tx_sem);
chSemSignal(init_struct->tx_sem);
}
}
void uart_send_message(struct uart_periph *p, long fd)
{
struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct);
struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct);
// unlock driver in case it is not done (fd > 0)
if (fd != 0) {
chMtxUnlock(init_struct->tx_mtx);
}
// send signal to start transmission
chSemSignal (init_struct->tx_sem);
chSemSignal(init_struct->tx_sem);
}
@@ -0,0 +1,130 @@
/*
* Copyright (C) Kevin van Hecke
*
* 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, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file actuators_xvert.c
* @author Kevin van Hecke
* Actuators driver for X-vert VTOL motor controllers. Contains two
* normal pwm servos, and two custom driven escs through a propriety uart
* protocol.
*/
#include "actuators_xvert.h"
#include "subsystems/actuators/actuators_pwm_arch.h"
#include "subsystems/actuators/actuators_pwm.h"
#include "mcu_periph/uart.h"
#define ESCS_PORT (&((ESCS_UART).device))
int32_t actuators_xvert_values[ACTUATORS_PWM_NB];
#define GP 0x107 /* x^8 + x^2 + x + 1 */
#define DI 0xE7
static unsigned char crc8_table[256]; /* 8-bit table */
static int made_table = 0;
static void init_crc8(void)
/*
* Should be called before any other crc function.
*/
{
int i, j;
unsigned char crc;
if (!made_table) {
for (i = 0; i < 256; i++) {
crc = i;
for (j = 0; j < 8; j++) {
crc = (crc << 1) ^ ((crc & 0x80) ? DI : 0);
}
crc8_table[i] = crc & 0xFF;
/* printf("table[%d] = %d (0x%X)\n", i, crc, crc); */
}
made_table = 1;
}
}
void crc8(unsigned char *crc, unsigned char m)
/*
* For a byte array whose accumulated crc value is stored in *crc, computes
* resultant crc obtained by appending m to the byte array
*/
{
if (!made_table) {
init_crc8();
}
*crc = crc8_table[(*crc) ^ m];
*crc &= 0xFF;
}
void actuators_xvert_init(void)
{
actuators_pwm_arch_init();
}
void actuators_xvert_commit(void)
{
if (ESCS_PORT->char_available(ESCS_PORT->periph)) {
//unsigned char b1 = ESCS_PORT->get_byte(ESCS_PORT->periph);
}
struct EscData package;
package.start = ESCS_START_BYTE;
package.len = 8;
package.id = 2;
package.d1 = actuators_xvert_values[XVERT_ESC_0];
package.d2 = actuators_xvert_values[XVERT_ESC_1];
//do some package magic:
static bool bitflipper = true;
if (bitflipper) {
package.d1 += ESCS_DATA_FLIPBIT;
} else {
package.d2 += ESCS_DATA_FLIPBIT;
}
package.d1 += ESCS_DATA_MYSTERYBIT;
bitflipper = !bitflipper;
unsigned char crc = 0;
unsigned char *data = (unsigned char *)&package;
for (unsigned char i = 1 ; i < sizeof(struct EscData) - 1; i++) {
crc8(&crc, data[i]);
}
package.crc = crc;
ESCS_PORT->put_buffer(ESCS_PORT->periph, 0, (unsigned char *) &package, sizeof(struct EscData));
//send the pwm signals for the two elerons to the pwm driver:
actuators_pwm_values[PWM_SERVO_2] = actuators_xvert_values[PWM_SERVO_2];
actuators_pwm_values[PWM_SERVO_3] = actuators_xvert_values[PWM_SERVO_3];
actuators_pwm_commit();
}
@@ -0,0 +1,61 @@
/*
* Copyright (C) Kevin van Hecke
*
* 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, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file actuators_xvert.h
* @author Kevin van Hecke
* Actuators driver for X-vert VTOL motor controllers. Contains two normal pwm servos, and two custom driven escs through a propriety uart protocol.
*/
#ifndef ACTUATORS_XVERT_H
#define ACTUATORS_XVERT_H
#include "subsystems/actuators/actuators_pwm_arch.h"
#define ESCS_START_BYTE 0xFE
#define ESCS_DATA_FLIPBIT 16384
#define ESCS_DATA_MYSTERYBIT 32768
struct EscData {
unsigned char start; //0xfe
unsigned char len; //8
unsigned char id; //2
//1200 - 1800, maybe 1100-1900
//1160 = off, max ~1880
//in both data ints, 2e byte toggles the 64 bit (15e bit in total). If on, its the first, if off its the other
//in d2 16e bit always on
uint32_t d1 ;
uint32_t d2 ;
unsigned char crc;
} __attribute__((__packed__));
extern int32_t actuators_xvert_values[ACTUATORS_PWM_NB];
extern void actuators_xvert_commit(void);
extern void actuators_xvert_init(void);
#define ActuatorsXvertInit actuators_xvert_init
#define ActuatorXvertSet(_i, _v) { actuators_xvert_values[_i] = _v; }
#define ActuatorsXvertCommit actuators_xvert_commit
#endif
@@ -0,0 +1,153 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/*
* This file has been automatically generated using ChibiStudio board
* generator plugin. Do not edit manually.
*/
#include "hal.h"
#if HAL_USE_PAL || defined(__DOXYGEN__)
/**
* @brief PAL setup.
* @details Digital I/O ports static configuration as defined in @p board.h.
* This variable is used by the HAL when initializing the PAL driver.
*/
const PALConfig pal_default_config = {
#if STM32_HAS_GPIOA
{
VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH
},
#endif
#if STM32_HAS_GPIOB
{
VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH
},
#endif
#if STM32_HAS_GPIOC
{
VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH
},
#endif
#if STM32_HAS_GPIOD
{
VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH
},
#endif
#if STM32_HAS_GPIOE
{
VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH
},
#endif
#if STM32_HAS_GPIOF
{
VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH
},
#endif
#if STM32_HAS_GPIOG
{
VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH
},
#endif
#if STM32_HAS_GPIOH
{
VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH
},
#endif
#if STM32_HAS_GPIOI
{
VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH
}
#endif
};
#endif
/**
* @brief Early initialization code.
* @details This initialization must be performed just after stack setup
* and before any other initialization.
*/
void __early_init(void)
{
stm32_clock_init();
}
#if HAL_USE_SDC || defined(__DOXYGEN__)
/**
* @brief SDC card detection.
*/
bool sdc_lld_is_card_inserted(SDCDriver *sdcp)
{
(void)sdcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief SDC card write protection detection.
*/
bool sdc_lld_is_write_protected(SDCDriver *sdcp)
{
(void)sdcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif /* HAL_USE_SDC */
#if HAL_USE_MMC_SPI || defined(__DOXYGEN__)
/**
* @brief MMC_SPI card detection.
*/
bool mmc_lld_is_card_inserted(MMCDriver *mmcp)
{
(void)mmcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief MMC_SPI card write protection detection.
*/
bool mmc_lld_is_write_protected(MMCDriver *mmcp)
{
(void)mmcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif
/**
* @brief Board-specific initialization code.
* @todo Add your board-specific code, if any.
*/
void boardInit(void)
{
}
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,20 @@
#
# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# Required include directories
BOARDINC = $(CHIBIOS_BOARD_DIR)
# List of all the board related files.
BOARDSRC = ${BOARDINC}/board.c
@@ -0,0 +1,301 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef MCUCONF_H
#define MCUCONF_H
/*
* STM32F3xx drivers configuration.
* The following settings override the default settings present in
* the various device driver implementation headers.
* Note that the settings for each driver only have effect if the whole
* driver is enabled in halconf.h.
*
* IRQ priorities:
* 15...0 Lowest...Highest.
*
* DMA priorities:
* 0...3 Lowest...Highest.
*/
#define STM32F3xx_MCUCONF
/*
* HAL driver system settings.
*/
#define STM32_NO_INIT FALSE
#define STM32_PVD_ENABLE FALSE
#define STM32_PLS STM32_PLS_LEV0
#define STM32_HSI_ENABLED TRUE
#define STM32_LSI_ENABLED TRUE
#define STM32_HSE_ENABLED TRUE
#define STM32_LSE_ENABLED FALSE
#define STM32_SW STM32_SW_PLL
#define STM32_PLLSRC STM32_PLLSRC_HSE
#define STM32_PREDIV_VALUE 1
#define STM32_PLLMUL_VALUE 9
#define STM32_HPRE STM32_HPRE_DIV1
#define STM32_PPRE1 STM32_PPRE1_DIV2
#define STM32_PPRE2 STM32_PPRE2_DIV2
#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
#define STM32_ADC12PRES STM32_ADC12PRES_DIV1
#define STM32_ADC34PRES STM32_ADC34PRES_DIV1
#define STM32_USART1SW STM32_USART1SW_PCLK
#define STM32_USART2SW STM32_USART2SW_PCLK
#define STM32_USART3SW STM32_USART3SW_PCLK
#define STM32_UART4SW STM32_UART4SW_PCLK
#define STM32_UART5SW STM32_UART5SW_PCLK
#define STM32_I2C1SW STM32_I2C1SW_SYSCLK
#define STM32_I2C2SW STM32_I2C2SW_SYSCLK
#define STM32_TIM1SW STM32_TIM1SW_PCLK2
#define STM32_TIM8SW STM32_TIM8SW_PCLK2
#define STM32_RTCSEL STM32_RTCSEL_LSI
#define STM32_USB_CLOCK_REQUIRED TRUE
#define STM32_USBPRE STM32_USBPRE_DIV1P5
/*
* ADC driver system settings.
*/
#define STM32_ADC_DUAL_MODE FALSE
#define STM32_ADC_COMPACT_SAMPLES FALSE
#define STM32_ADC_USE_ADC1 TRUE
#define STM32_ADC_USE_ADC2 FALSE
#define STM32_ADC_USE_ADC3 FALSE
#define STM32_ADC_USE_ADC4 FALSE
#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(1, 1)
#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 1)
#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 5)
#define STM32_ADC_ADC4_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
#define STM32_ADC_ADC1_DMA_PRIORITY 2
#define STM32_ADC_ADC2_DMA_PRIORITY 2
#define STM32_ADC_ADC3_DMA_PRIORITY 2
#define STM32_ADC_ADC4_DMA_PRIORITY 2
#define STM32_ADC_ADC12_IRQ_PRIORITY 5
#define STM32_ADC_ADC3_IRQ_PRIORITY 5
#define STM32_ADC_ADC4_IRQ_PRIORITY 5
#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 5
#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY 5
#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY 5
#define STM32_ADC_ADC4_DMA_IRQ_PRIORITY 5
#define STM32_ADC_ADC12_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV1
#define STM32_ADC_ADC34_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV1
/*
* CAN driver system settings.
*/
#if USE_CAN1
#define STM32_CAN_USE_CAN1 TRUE
#else
#define STM32_CAN_USE_CAN1 FALSE
#endif
#define STM32_CAN_CAN1_IRQ_PRIORITY 11
/*
* DAC driver system settings.
*/
#define STM32_DAC_DUAL_MODE FALSE
#define STM32_DAC_USE_DAC1_CH1 TRUE
#define STM32_DAC_USE_DAC1_CH2 TRUE
#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10
#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10
#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2
#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2
/*
* EXT driver system settings.
*/
#define STM32_EXT_EXTI0_IRQ_PRIORITY 6
#define STM32_EXT_EXTI1_IRQ_PRIORITY 6
#define STM32_EXT_EXTI2_IRQ_PRIORITY 6
#define STM32_EXT_EXTI3_IRQ_PRIORITY 6
#define STM32_EXT_EXTI4_IRQ_PRIORITY 6
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
#define STM32_EXT_EXTI16_IRQ_PRIORITY 6
#define STM32_EXT_EXTI17_IRQ_PRIORITY 6
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
#define STM32_EXT_EXTI20_IRQ_PRIORITY 6
#define STM32_EXT_EXTI21_22_29_IRQ_PRIORITY 6
#define STM32_EXT_EXTI30_32_IRQ_PRIORITY 6
#define STM32_EXT_EXTI33_IRQ_PRIORITY 6
/*
* GPT driver system settings.
*/
#define STM32_GPT_USE_TIM1 FALSE
#define STM32_GPT_USE_TIM2 FALSE
#define STM32_GPT_USE_TIM3 FALSE
#define STM32_GPT_USE_TIM4 FALSE
#define STM32_GPT_USE_TIM6 FALSE
#define STM32_GPT_USE_TIM7 FALSE
#define STM32_GPT_USE_TIM8 FALSE
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
#define STM32_GPT_TIM6_IRQ_PRIORITY 7
#define STM32_GPT_TIM7_IRQ_PRIORITY 7
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
/*
* I2C driver system settings.
*/
#if USE_I2C1
#define STM32_I2C_USE_I2C1 TRUE
#else
#define STM32_I2C_USE_I2C1 FALSE
#endif
#if USE_I2C2
#define STM32_I2C_USE_I2C2 TRUE
#else
#define STM32_I2C_USE_I2C2 FALSE
#endif
#define STM32_I2C_BUSY_TIMEOUT 50
#define STM32_I2C_I2C1_IRQ_PRIORITY 10
#define STM32_I2C_I2C2_IRQ_PRIORITY 10
#define STM32_I2C_USE_DMA TRUE
#define STM32_I2C_I2C1_DMA_PRIORITY 1
#define STM32_I2C_I2C2_DMA_PRIORITY 1
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
/*
* ICU driver system settings.
*/
#define STM32_ICU_USE_TIM1 FALSE
#define STM32_ICU_USE_TIM2 FALSE
#define STM32_ICU_USE_TIM3 FALSE
#define STM32_ICU_USE_TIM4 FALSE
#define STM32_ICU_USE_TIM8 FALSE
#define STM32_ICU_TIM1_IRQ_PRIORITY 7
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
#define STM32_ICU_TIM4_IRQ_PRIORITY 7
#define STM32_ICU_TIM8_IRQ_PRIORITY 7
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_ADVANCED FALSE
#define STM32_PWM_USE_TIM1 FALSE
#ifndef STM32_PWM_USE_TIM2
#define STM32_PWM_USE_TIM2 TRUE
#endif
#ifndef STM32_PWM_USE_TIM3
#define STM32_PWM_USE_TIM3 TRUE
#endif
#define STM32_PWM_USE_TIM4 FALSE
#define STM32_PWM_USE_TIM8 FALSE
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
#define STM32_PWM_TIM8_IRQ_PRIORITY 7
/*
* SERIAL driver system settings.
*/
#if USE_UART1
#define STM32_SERIAL_USE_USART1 TRUE
#else
#define STM32_SERIAL_USE_USART1 FALSE
#endif
#if USE_UART2
#define STM32_SERIAL_USE_USART2 TRUE
#else
#define STM32_SERIAL_USE_USART2 FALSE
#endif
#if USE_UART3
#define STM32_SERIAL_USE_USART3 TRUE
#else
#define STM32_SERIAL_USE_USART3 FALSE
#endif
#if USE_UART4
#define STM32_SERIAL_USE_UART4 TRUE
#else
#define STM32_SERIAL_USE_UART4 FALSE
#endif
#if USE_UART5
#define STM32_SERIAL_USE_UART5 TRUE
#else
#define STM32_SERIAL_USE_UART5 FALSE
#endif
#define STM32_SERIAL_USART1_PRIORITY 12
#define STM32_SERIAL_USART2_PRIORITY 12
#define STM32_SERIAL_USART3_PRIORITY 12
#define STM32_SERIAL_UART4_PRIORITY 12
#define STM32_SERIAL_UART5_PRIORITY 12
/*
* SPI driver system settings.
*/
#if USE_SPI1
#define STM32_SPI_USE_SPI1 TRUE
#else
#define STM32_SPI_USE_SPI1 FALSE
#endif
#if USE_SPI2
#define STM32_SPI_USE_SPI2 TRUE
#else
#define STM32_SPI_USE_SPI2 FALSE
#endif
#if USE_SPI3
#define STM32_SPI_USE_SPI3 TRUE
#else
#define STM32_SPI_USE_SPI3 FALSE
#endif
#define STM32_SPI_SPI1_DMA_PRIORITY 1
#define STM32_SPI_SPI2_DMA_PRIORITY 1
#define STM32_SPI_SPI3_DMA_PRIORITY 1
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
#define STM32_SPI_SPI3_IRQ_PRIORITY 10
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
/*
* ST driver system settings.
*/
#define STM32_ST_IRQ_PRIORITY 8
#define STM32_ST_USE_TIMER 2
/*
* UART driver system settings.
*/
#define STM32_UART_USE_USART1 FALSE
#define STM32_UART_USE_USART2 FALSE
#define STM32_UART_USE_USART3 FALSE
#define STM32_UART_USART1_IRQ_PRIORITY 12
#define STM32_UART_USART2_IRQ_PRIORITY 12
#define STM32_UART_USART3_IRQ_PRIORITY 12
#define STM32_UART_USART1_DMA_PRIORITY 0
#define STM32_UART_USART2_DMA_PRIORITY 0
#define STM32_UART_USART3_DMA_PRIORITY 0
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
/*
* USB driver system settings.
*/
#define STM32_USB_USE_USB1 TRUE
#define STM32_USB_LOW_POWER_ON_SUSPEND FALSE
#define STM32_USB_USB1_HP_IRQ_PRIORITY 13
#define STM32_USB_USB1_LP_IRQ_PRIORITY 14
/*
* WDG driver system settings.
*/
#define STM32_WDG_USE_IWDG FALSE
#endif /* MCUCONF_H */
+20
View File
@@ -0,0 +1,20 @@
/*
* board specific functions for the chimera board
*
*/
#ifndef BOARDS_CHIMERA_BARO_H
#define BOARDS_CHIMERA_BARO_H
// only for printing the baro type during compilation
#ifndef BARO_BOARD
#define BARO_BOARD BARO_MS5611_I2C
#endif
#define BB_MS5611_TYPE_MS5607 TRUE
extern void baro_event(void);
#define BaroEvent baro_event
#endif /* BOARDS_CHIMERA_BARO_H */
@@ -0,0 +1,153 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/*
* This file has been automatically generated using ChibiStudio board
* generator plugin. Do not edit manually.
*/
#include "hal.h"
#if HAL_USE_PAL || defined(__DOXYGEN__)
/**
* @brief PAL setup.
* @details Digital I/O ports static configuration as defined in @p board.h.
* This variable is used by the HAL when initializing the PAL driver.
*/
const PALConfig pal_default_config = {
#if STM32_HAS_GPIOA
{
VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH
},
#endif
#if STM32_HAS_GPIOB
{
VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH
},
#endif
#if STM32_HAS_GPIOC
{
VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH
},
#endif
#if STM32_HAS_GPIOD
{
VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH
},
#endif
#if STM32_HAS_GPIOE
{
VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH
},
#endif
#if STM32_HAS_GPIOF
{
VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH
},
#endif
#if STM32_HAS_GPIOG
{
VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH
},
#endif
#if STM32_HAS_GPIOH
{
VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH
},
#endif
#if STM32_HAS_GPIOI
{
VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH
}
#endif
};
#endif
/**
* @brief Early initialization code.
* @details This initialization must be performed just after stack setup
* and before any other initialization.
*/
void __early_init(void)
{
stm32_clock_init();
}
#if HAL_USE_SDC || defined(__DOXYGEN__)
/**
* @brief SDC card detection.
*/
bool sdc_lld_is_card_inserted(SDCDriver *sdcp)
{
(void)sdcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief SDC card write protection detection.
*/
bool sdc_lld_is_write_protected(SDCDriver *sdcp)
{
(void)sdcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif /* HAL_USE_SDC */
#if HAL_USE_MMC_SPI || defined(__DOXYGEN__)
/**
* @brief MMC_SPI card detection.
*/
bool mmc_lld_is_card_inserted(MMCDriver *mmcp)
{
(void)mmcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief MMC_SPI card write protection detection.
*/
bool mmc_lld_is_write_protected(MMCDriver *mmcp)
{
(void)mmcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif
/**
* @brief Board-specific initialization code.
* @todo Add your board-specific code, if any.
*/
void boardInit(void)
{
}
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,20 @@
#
# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# Required include directories
BOARDINC = $(CHIBIOS_BOARD_DIR)
# List of all the board related files.
BOARDSRC = ${BOARDINC}/board.c
@@ -0,0 +1,270 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef MCUCONF_H
#define MCUCONF_H
/*
* STM32F37x drivers configuration.
* The following settings override the default settings present in
* the various device driver implementation headers.
* Note that the settings for each driver only have effect if the whole
* driver is enabled in halconf.h.
*
* IRQ priorities:
* 15...0 Lowest...Highest.
*
* DMA priorities:
* 0...3 Lowest...Highest.
*/
#define STM32F37x_MCUCONF
/*
* HAL driver system settings.
*/
#define STM32_NO_INIT FALSE
#define STM32_PVD_ENABLE FALSE
#define STM32_PLS STM32_PLS_LEV0
#define STM32_HSI_ENABLED TRUE
#define STM32_LSI_ENABLED TRUE
#define STM32_HSE_ENABLED TRUE
#define STM32_LSE_ENABLED FALSE
#define STM32_SW STM32_SW_PLL
#define STM32_PLLSRC STM32_PLLSRC_HSE
#define STM32_PREDIV_VALUE 2
#define STM32_PLLMUL_VALUE 9
#define STM32_HPRE STM32_HPRE_DIV1
#define STM32_PPRE1 STM32_PPRE1_DIV2
#define STM32_PPRE2 STM32_PPRE2_DIV2
#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
#define STM32_ADCPRE STM32_ADCPRE_DIV4
#define STM32_SDPRE STM32_SDPRE_DIV12
#define STM32_USART1SW STM32_USART1SW_PCLK
#define STM32_USART2SW STM32_USART2SW_PCLK
#define STM32_USART3SW STM32_USART3SW_PCLK
#define STM32_I2C1SW STM32_I2C1SW_SYSCLK
#define STM32_I2C2SW STM32_I2C2SW_SYSCLK
#define STM32_RTCSEL STM32_RTCSEL_LSI
#define STM32_USB_CLOCK_REQUIRED TRUE
#define STM32_USBPRE STM32_USBPRE_DIV1P5
/*
* ADC driver system settings.
*/
#define STM32_ADC_USE_ADC1 TRUE
#define STM32_ADC_USE_SDADC1 FALSE
#define STM32_ADC_USE_SDADC2 FALSE
#define STM32_ADC_USE_SDADC3 FALSE
#define STM32_ADC_ADC1_DMA_PRIORITY 2
#define STM32_ADC_SDADC1_DMA_PRIORITY 2
#define STM32_ADC_SDADC2_DMA_PRIORITY 2
#define STM32_ADC_SDADC3_DMA_PRIORITY 2
#define STM32_ADC_ADC1_IRQ_PRIORITY 5
#define STM32_ADC_SDADC1_IRQ_PRIORITY 5
#define STM32_ADC_SDADC2_IRQ_PRIORITY 5
#define STM32_ADC_SDADC3_IRQ_PRIORITY 5
#define STM32_ADC_SDADC1_DMA_IRQ_PRIORITY 5
#define STM32_ADC_SDADC2_DMA_IRQ_PRIORITY 5
#define STM32_ADC_SDADC3_DMA_IRQ_PRIORITY 5
/*
* CAN driver system settings.
*/
#if USE_CAN1
#define STM32_CAN_USE_CAN1 TRUE
#else
#define STM32_CAN_USE_CAN1 FALSE
#endif
#define STM32_CAN_CAN1_IRQ_PRIORITY 11
/*
* EXT driver system settings.
*/
#define STM32_EXT_EXTI0_IRQ_PRIORITY 6
#define STM32_EXT_EXTI1_IRQ_PRIORITY 6
#define STM32_EXT_EXTI2_IRQ_PRIORITY 6
#define STM32_EXT_EXTI3_IRQ_PRIORITY 6
#define STM32_EXT_EXTI4_IRQ_PRIORITY 6
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
#define STM32_EXT_EXTI16_IRQ_PRIORITY 6
#define STM32_EXT_EXTI17_IRQ_PRIORITY 6
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
#define STM32_EXT_EXTI20_23_IRQ_PRIORITY 6
#define STM32_EXT_EXTI30_32_IRQ_PRIORITY 6
#define STM32_EXT_EXTI33_IRQ_PRIORITY 6
/*
* GPT driver system settings.
*/
#define STM32_GPT_USE_TIM2 FALSE
#define STM32_GPT_USE_TIM3 FALSE
#define STM32_GPT_USE_TIM4 FALSE
#define STM32_GPT_USE_TIM5 FALSE
#define STM32_GPT_USE_TIM6 FALSE
#define STM32_GPT_USE_TIM7 FALSE
#define STM32_GPT_USE_TIM12 FALSE
#define STM32_GPT_USE_TIM14 FALSE
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
#define STM32_GPT_TIM5_IRQ_PRIORITY 7
#define STM32_GPT_TIM6_IRQ_PRIORITY 7
#define STM32_GPT_TIM7_IRQ_PRIORITY 7
#define STM32_GPT_TIM12_IRQ_PRIORITY 7
#define STM32_GPT_TIM14_IRQ_PRIORITY 7
/*
* I2C driver system settings.
*/
#if USE_I2C1
#define STM32_I2C_USE_I2C1 TRUE
#else
#define STM32_I2C_USE_I2C1 FALSE
#endif
#if USE_I2C2
#define STM32_I2C_USE_I2C2 TRUE
#else
#define STM32_I2C_USE_I2C2 FALSE
#endif
#define STM32_I2C_BUSY_TIMEOUT 50
#define STM32_I2C_I2C1_IRQ_PRIORITY 10
#define STM32_I2C_I2C2_IRQ_PRIORITY 10
#define STM32_I2C_USE_DMA TRUE
#define STM32_I2C_I2C1_DMA_PRIORITY 1
#define STM32_I2C_I2C2_DMA_PRIORITY 1
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
/*
* ICU driver system settings.
*/
#define STM32_ICU_USE_TIM2 FALSE
#define STM32_ICU_USE_TIM3 FALSE
#define STM32_ICU_USE_TIM4 FALSE
#define STM32_ICU_USE_TIM5 FALSE
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
#define STM32_ICU_TIM4_IRQ_PRIORITY 7
#define STM32_ICU_TIM5_IRQ_PRIORITY 7
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_TIM2 FALSE
#define STM32_PWM_USE_TIM3 FALSE
#define STM32_PWM_USE_TIM4 FALSE
#define STM32_PWM_USE_TIM5 TRUE
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
#define STM32_PWM_TIM5_IRQ_PRIORITY 7
/*
* SERIAL driver system settings.
*/
#if USE_UART1
#define STM32_SERIAL_USE_USART1 TRUE
#else
#define STM32_SERIAL_USE_USART1 FALSE
#endif
#if USE_UART2
#define STM32_SERIAL_USE_USART2 TRUE
#else
#define STM32_SERIAL_USE_USART2 FALSE
#endif
#if USE_UART3
#define STM32_SERIAL_USE_USART3 TRUE
#else
#define STM32_SERIAL_USE_USART3 FALSE
#endif
#if USE_UART4
#define STM32_SERIAL_USE_UART4 TRUE
#else
#define STM32_SERIAL_USE_UART4 FALSE
#endif
#if USE_UART5
#define STM32_SERIAL_USE_UART5 TRUE
#else
#define STM32_SERIAL_USE_UART5 FALSE
#endif
#define STM32_SERIAL_USART1_PRIORITY 12
#define STM32_SERIAL_USART2_PRIORITY 12
#define STM32_SERIAL_USART3_PRIORITY 12
#define STM32_SERIAL_UART4_PRIORITY 12
#define STM32_SERIAL_UART5_PRIORITY 12
/*
* SPI driver system settings.
*/
#if USE_SPI1
#define STM32_SPI_USE_SPI1 TRUE
#else
#define STM32_SPI_USE_SPI1 FALSE
#endif
#if USE_SPI2
#define STM32_SPI_USE_SPI2 TRUE
#else
#define STM32_SPI_USE_SPI2 FALSE
#endif
#if USE_SPI3
#define STM32_SPI_USE_SPI3 TRUE
#else
#define STM32_SPI_USE_SPI3 FALSE
#endif
#define STM32_SPI_SPI1_DMA_PRIORITY 1
#define STM32_SPI_SPI2_DMA_PRIORITY 1
#define STM32_SPI_SPI3_DMA_PRIORITY 1
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
#define STM32_SPI_SPI3_IRQ_PRIORITY 10
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
/*
* ST driver system settings.
*/
#define STM32_ST_IRQ_PRIORITY 8
#define STM32_ST_USE_TIMER 2
/*
* UART driver system settings.
*/
#define STM32_UART_USE_USART1 TRUE
#define STM32_UART_USE_USART2 TRUE
#define STM32_UART_USE_USART3 FALSE
#define STM32_UART_USART1_IRQ_PRIORITY 12
#define STM32_UART_USART2_IRQ_PRIORITY 12
#define STM32_UART_USART3_IRQ_PRIORITY 12
#define STM32_UART_USART1_DMA_PRIORITY 0
#define STM32_UART_USART2_DMA_PRIORITY 0
#define STM32_UART_USART3_DMA_PRIORITY 0
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
/*
* USB driver system settings.
*/
#define STM32_USB_USE_USB1 FALSE
#define STM32_USB_LOW_POWER_ON_SUSPEND FALSE
#define STM32_USB_USB1_HP_IRQ_PRIORITY 13
#define STM32_USB_USB1_LP_IRQ_PRIORITY 14
/*
* WDG driver system settings.
*/
#define STM32_WDG_USE_IWDG FALSE
#endif /* MCUCONF_H */
@@ -37,12 +37,16 @@
#include "firmwares/rotorcraft/main_ap.h"
#ifndef THD_WORKING_AREA_MAIN
#define THD_WORKING_AREA_MAIN 8192
#endif
/*
* PPRZ/AP thread
* Also include FBW on single MCU
*/
static void thd_ap(void *arg);
static THD_WORKING_AREA(wa_thd_ap, 8192);
THD_WORKING_AREA(wa_thd_ap, THD_WORKING_AREA_MAIN);
static thread_t *apThdPtr = NULL;
/**
@@ -94,14 +94,16 @@ struct IndiVariables indi = {
STABILIZATION_INDI_REF_ERR_R,
STABILIZATION_INDI_REF_RATE_P,
STABILIZATION_INDI_REF_RATE_Q,
STABILIZATION_INDI_REF_RATE_R},
STABILIZATION_INDI_REF_RATE_R
},
/* Estimation parameters for adaptive INDI */
.est = {
.g1 = {
STABILIZATION_INDI_G1_P / INDI_EST_SCALE,
STABILIZATION_INDI_G1_Q / INDI_EST_SCALE,
STABILIZATION_INDI_G1_R / INDI_EST_SCALE},
STABILIZATION_INDI_G1_R / INDI_EST_SCALE
},
.g2 = STABILIZATION_INDI_G2_R / INDI_EST_SCALE,
.mu = STABILIZATION_INDI_ADAPTIVE_MU,
},
@@ -162,15 +164,16 @@ void stabilization_indi_init(void)
#endif
}
void indi_init_filters(void) {
void indi_init_filters(void)
{
// tau = 1/(2*pi*Fc)
float tau = 1.0/(2.0*M_PI*STABILIZATION_INDI_FILT_CUTOFF);
float tau_r = 1.0/(2.0*M_PI*STABILIZATION_INDI_FILT_CUTOFF_R);
float tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF);
float tau_r = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_R);
float tau_axis[3] = {tau, tau, tau_r};
float tau_est = 1.0/(2.0*M_PI*STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF);
float sample_time = 1.0/PERIODIC_FREQUENCY;
float tau_est = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF);
float sample_time = 1.0 / PERIODIC_FREQUENCY;
// Filtering of gyroscope and actuators
for(int8_t i=0; i<3; i++) {
for (int8_t i = 0; i < 3; i++) {
init_butterworth_2_low_pass(&indi.u[i], tau_axis[i], sample_time, 0.0);
init_butterworth_2_low_pass(&indi.rate[i], tau_axis[i], sample_time, 0.0);
init_butterworth_2_low_pass(&indi.est.u[i], tau_est, sample_time, 0.0);
@@ -243,7 +246,8 @@ void stabilization_indi_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading)
* @param filter The filter array to use
* @param new_values The new values
*/
static inline void filter_pqr(Butterworth2LowPass *filter, struct FloatRates *new_values) {
static inline void filter_pqr(Butterworth2LowPass *filter, struct FloatRates *new_values)
{
update_butterworth_2_low_pass(&filter[0], new_values->p);
update_butterworth_2_low_pass(&filter[1], new_values->q);
update_butterworth_2_low_pass(&filter[2], new_values->r);
@@ -256,9 +260,10 @@ static inline void filter_pqr(Butterworth2LowPass *filter, struct FloatRates *ne
* @param output The output array
* @param filter The filter array input
*/
static inline void finite_difference_from_filter(float *output, Butterworth2LowPass *filter) {
for(int8_t i=0; i<3; i++) {
output[i] = (filter[i].o[0] - filter[i].o[1])*PERIODIC_FREQUENCY;
static inline void finite_difference_from_filter(float *output, Butterworth2LowPass *filter)
{
for (int8_t i = 0; i < 3; i++) {
output[i] = (filter[i].o[0] - filter[i].o[1]) * PERIODIC_FREQUENCY;
}
}
@@ -269,8 +274,9 @@ static inline void finite_difference_from_filter(float *output, Butterworth2LowP
* @param new[3] The newest values
* @param old[3] The values of the previous timestep
*/
static inline void finite_difference(float output[3], float new[3], float old[3]) {
for(int8_t i=0; i<3; i++) {
static inline void finite_difference(float output[3], float new[3], float old[3])
{
for (int8_t i = 0; i < 3; i++) {
output[i] = (new[i] - old[i])*PERIODIC_FREQUENCY;
}
}
@@ -315,12 +321,12 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I
- indi.reference_acceleration.rate_q * rates_for_feedback.q;
//This separates the P and D controller and lets you impose a maximum yaw rate.
float rate_ref_r = indi.reference_acceleration.err_r * QUAT1_FLOAT_OF_BFP(att_err->qz)/indi.reference_acceleration.rate_r;
float rate_ref_r = indi.reference_acceleration.err_r * QUAT1_FLOAT_OF_BFP(att_err->qz) / indi.reference_acceleration.rate_r;
BoundAbs(rate_ref_r, indi.attitude_max_yaw_rate);
indi.angular_accel_ref.r = indi.reference_acceleration.rate_r * (rate_ref_r - rates_for_feedback.r);
/* Check if we are running the rate controller and overwrite */
if(rate_control) {
if (rate_control) {
indi.angular_accel_ref.p = indi.reference_acceleration.rate_p * ((float)radio_control.values[RADIO_ROLL] / MAX_PPRZ * indi.max_rate - body_rates->p);
indi.angular_accel_ref.q = indi.reference_acceleration.rate_q * ((float)radio_control.values[RADIO_PITCH] / MAX_PPRZ * indi.max_rate - body_rates->q);
indi.angular_accel_ref.r = indi.reference_acceleration.rate_r * ((float)radio_control.values[RADIO_YAW] / MAX_PPRZ * indi.max_rate - body_rates->r);
@@ -340,9 +346,17 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I
indi.u_in.r = indi.u[2].o[0] + indi.du.r;
//bound the total control input
#if STABILIZATION_INDI_FULL_AUTHORITY
Bound(indi.u_in.p, -9600, 9600);
Bound(indi.u_in.q, -9600, 9600);
float rlim = 9600 - fabs(indi.u_in.q);
Bound(indi.u_in.r, -rlim, rlim);
Bound(indi.u_in.r, -9600, 9600);
#else
Bound(indi.u_in.p, -4500, 4500);
Bound(indi.u_in.q, -4500, 4500);
Bound(indi.u_in.r, -4500, 4500);
#endif
//Propagate input filters
//first order actuator dynamics
+10 -2
View File
@@ -26,7 +26,7 @@
#include "pprz_trig_int.h"
#include "pprz_algebra_int.h"
#if !defined(PPRZ_TRIG_INT_USE_FLOAT)
#if !defined(PPRZ_TRIG_INT_COMPR_FLASH) || defined(PPRZ_TRIG_INT_TEST)
PPRZ_TRIG_CONST int16_t pprz_trig_int[6434] = { 0,
3, 7, 11, 15, 19, 23, 27, 31, 35, 39, 43, 47, 51, 55, 59, 63,
@@ -581,7 +581,7 @@ const uint8_t pprz_trig_int_compr[TRIG_INT_COMPR_LEN] = {
0x10, 0x1F, 0x10, 0x3F, 0x10, 0x8F, 0x10, 0xFF, 0xA8, 0x00
};
#endif
#endif
#if defined(PPRZ_TRIG_INT_COMPR_FLASH)
@@ -858,6 +858,13 @@ inline int16_t pprz_trig_int_f(int32_t angle)
int32_t pprz_itrig_sin(int32_t angle)
{
#if defined(PPRZ_TRIG_INT_USE_FLOAT)
float tmp;
tmp = ANGLE_FLOAT_OF_BFP(angle);
tmp = sinf(tmp);
angle = ANGLE_BFP_OF_REAL(tmp);
return angle;
#else
INT32_ANGLE_NORMALIZE(angle);
if (angle > INT32_ANGLE_PI_2) {
angle = INT32_ANGLE_PI - angle;
@@ -875,6 +882,7 @@ int32_t pprz_itrig_sin(int32_t angle)
return -pprz_trig_int[-angle];
#endif
}
#endif
}
int32_t pprz_itrig_cos(int32_t angle)
+10 -4
View File
@@ -28,7 +28,7 @@
#include "peripherals/mpu9250_i2c.h"
bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unused)),
void *mpu __attribute__((unused)));
void *mpu __attribute__((unused)));
void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t addr)
{
@@ -47,8 +47,10 @@ void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t
mpu->config.initialized = false;
mpu->config.init_status = MPU9250_CONF_UNINIT;
#if IMU_MPU9250_READ_MAG
/* "internal" ak8963 magnetometer */
ak8963_init(&mpu->akm, i2c_p, MPU9250_MAG_ADDR);
/* mag is declared as slave to call the configure function,
* regardless if it is an actual MPU slave or passthrough
*/
@@ -59,6 +61,7 @@ void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t
mpu->config.i2c_bypass = true;
mpu->slave_init_status = MPU9250_I2C_CONF_UNINIT;
#endif
}
@@ -88,10 +91,12 @@ void mpu9250_i2c_read(struct Mpu9250_I2c *mpu)
mpu->i2c_trans.buf[0] = MPU9250_REG_INT_STATUS;
i2c_transceive(mpu->i2c_p, &(mpu->i2c_trans), mpu->i2c_trans.slave_addr, 1, mpu->config.nb_bytes);
/* read mag */
#if IMU_MPU9250_READ_MAG
#ifdef MPU9250_MAG_PRESCALER
RunOnceEvery(MPU9250_MAG_PRESCALER, ak8963_read(&mpu->akm));
#else
ak8963_read(&mpu->akm);
#endif
#endif
}
}
@@ -144,8 +149,10 @@ void mpu9250_i2c_event(struct Mpu9250_I2c *mpu)
break;
}
}
#if IMU_MPU9250_READ_MAG
// Ak8963 event function
ak8963_event(&mpu->akm);
#endif
}
/** callback function to configure ak8963 mag
@@ -185,12 +192,11 @@ bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu)
case MPU9250_I2C_CONF_SLAVES_CONFIGURE:
/* configure each slave until all nb_slaves are done */
if (mpu_i2c->config.nb_slave_init < mpu_i2c->config.nb_slaves && mpu_i2c->config.nb_slave_init < MPU9250_I2C_NB_SLAVES) {
// proceed to next slave if configure for current one returns true
// proceed to next slave if configure for current one returns true
if (mpu_i2c->config.slaves[mpu_i2c->config.nb_slave_init].configure(mpu_set, mpu)) {
mpu_i2c->config.nb_slave_init++;
}
}
else {
} else {
/* all slave devies configured, continue MPU side configuration of I2C slave stuff */
mpu_i2c->slave_init_status++;
}
+6
View File
@@ -36,6 +36,10 @@
#include "peripherals/mpu9250.h"
#include "peripherals/ak8963.h"
#ifndef IMU_MPU9250_READ_MAG
#define IMU_MPU9250_READ_MAG TRUE
//the MPU6500 is the same as the 9250, except for that its lacking a magneto
#endif
#define MPU9250_BUFFER_EXT_LEN 16
@@ -67,7 +71,9 @@ struct Mpu9250_I2c {
uint8_t data_ext[MPU9250_BUFFER_EXT_LEN];
struct Mpu9250Config config;
enum Mpu9250I2cSlaveInitStatus slave_init_status;
#ifdef IMU_MPU9250_READ_MAG
struct Ak8963 akm; ///< "internal" magnetometer
#endif
};
// Functions
@@ -116,7 +116,7 @@ void ahrs_fc_init(void)
}
bool ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag)
struct FloatVect3 *lp_mag __attribute__((unused)))
{
#if USE_MAGNETOMETER
@@ -276,7 +276,7 @@ void ahrs_fc_update_accel(struct FloatVect3 *accel, float dt)
}
void ahrs_fc_update_mag(struct FloatVect3 *mag, float dt)
void ahrs_fc_update_mag(struct FloatVect3 *mag __attribute__((unused)), float dt __attribute__((unused)))
{
#if USE_MAGNETOMETER
// check if we had at least one propagation since last update
+12 -11
View File
@@ -126,14 +126,14 @@ void imu_mpu9250_event(void)
if (imu_mpu9250.mpu.data_available) {
// set channel order
struct Int32Vect3 accel = {
IMU_MPU9250_X_SIGN * (int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_X]),
IMU_MPU9250_Y_SIGN * (int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Y]),
IMU_MPU9250_Z_SIGN * (int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Z])
IMU_MPU9250_X_SIGN *(int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_X]),
IMU_MPU9250_Y_SIGN *(int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Y]),
IMU_MPU9250_Z_SIGN *(int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Z])
};
struct Int32Rates rates = {
IMU_MPU9250_X_SIGN * (int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_X]),
IMU_MPU9250_Y_SIGN * (int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Y]),
IMU_MPU9250_Z_SIGN * (int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Z])
IMU_MPU9250_X_SIGN *(int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_X]),
IMU_MPU9250_Y_SIGN *(int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Y]),
IMU_MPU9250_Z_SIGN *(int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Z])
};
// unscaled vector
VECT3_COPY(imu.accel_unscaled, accel);
@@ -146,19 +146,20 @@ void imu_mpu9250_event(void)
AbiSendMsgIMU_GYRO_INT32(IMU_MPU9250_ID, now_ts, &imu.gyro);
AbiSendMsgIMU_ACCEL_INT32(IMU_MPU9250_ID, now_ts, &imu.accel);
}
#if IMU_MPU9250_READ_MAG
// Test if mag data are updated
if (imu_mpu9250.mpu.akm.data_available) {
struct Int32Vect3 mag = {
IMU_MPU9250_X_SIGN * (int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Y]),
IMU_MPU9250_Y_SIGN * (int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_X]),
-IMU_MPU9250_Z_SIGN * (int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Z])
IMU_MPU9250_X_SIGN *(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Y]),
IMU_MPU9250_Y_SIGN *(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_X]),
-IMU_MPU9250_Z_SIGN *(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Z])
};
VECT3_COPY(imu.mag_unscaled, mag);
imu_mpu9250.mpu.akm.data_available = false;
imu_scale_mag(&imu);
AbiSendMsgIMU_MAG_INT32(IMU_MPU9250_ID, now_ts, &imu.mag);
}
}
#endif
}
+61 -45
View File
@@ -3,55 +3,71 @@
#It finds the correct VPATH to each source file from make, and then feeds all info to gcc -MM.
import sys
import os
from os import path, getenv
from os import path, getenv, environ
# first argument is the gcc compiler
# thereafter are the vpaths closed by a '+'
# thereafter are the srcs closed by a '+'
# thereafter are the cflags
pprzswdir = os.environ['PAPARAZZI_SRC']
pprzswdir = path.join(pprzswdir, "sw/airborne")
#parse the input arguments into seperate lists
cc = sys.argv[1]
vpaths = list()
srcs = list()
cflags = list()
mode = 0
for i in range(2,len(sys.argv)):
vpath = sys.argv[i]
if vpath == '+':
mode = mode + 1
else:
if mode == 0:
vpaths.append(vpath)
elif mode == 1:
srcs.append(sys.argv[i])
elif mode == 2:
cflags.append(sys.argv[i])
#create the command for gcc -MM cflags srcs
cmd = cc + ' -MM '
for flg in cflags:
qflg = "" # append all quotes with escape char
for i in range(0,len(flg)):
if flg[i] == "\"":
qflg = qflg + "\\\""
else:
qflg = qflg + flg[i]
cmd = cmd + qflg + ' '
with open(sys.argv[2]) as fp:
vpathsl = fp.readline()
srcsl = fp.readline()
cflagsl = fp.readline()
includesl = fp.readline()
toptl = fp.readline()
for i in range(0,len(srcs)):
f = srcs[i]
found = 0
for vpath in vpaths:
if os.path.isfile(path.join(vpath, f)) :
cmd = cmd + path.join(vpath, f) + ' '
found = found +1
break
if found == 0:
print("ERROR, could not find: " + f)
if found > 1:
print("ERROR, found more than once: " + f)
vpaths = vpathsl.strip().split(" ")
srcs = srcsl.strip().split(" ")
cflags = cflagsl.strip().split(" ")
includes = includesl.strip().split(" ")
#call gcc
os.system(cmd)
cflagsn = "" #" -I" + pprzswdir + " -I" + pprzvardir + " "
for i in range(0,len(cflags)):
f = cflags[i]
nf = "" # append all quotes with escape char
for j in range(0,len(f)):
if f[j] == "\"":
nf = nf + "\\\""
else:
nf = nf + f[j]
f = nf
if f.startswith("-I"): #for whatever reason, these includes miss the pprz path. Which gives issues with gcc
f = "-I" + path.join(pprzswdir, f[2:])
elif f.startswith ("-M"):
break;
f = " "
cflagsn = cflagsn + f + " "
topt = toptl.strip().split(" ")
vpaths.append(pprzswdir)
#create the command for gcc -MM cflags srcs
cmd = cc + ' -MM ' + includesl.strip() + " " + cflagsn.strip() + " " + toptl.strip()
#print("****************************************************")
for i in range(0,len(srcs)):
f = srcs[i]
found = 0
for vpath in vpaths:
if os.path.isfile(path.join(vpath, f)) :
cmd = cmd + path.join(vpath, f) + ' '
found = found +1
# break
if found == 0:
tmps = "ERROR: could not find src: " + f
cmd = cmd + tmps #hack to make the error known
print(tmps)
if found > 1:
tmps = "ERROR: found src more than once: " + f
cmd = cmd + tmps #hack to make the error known
print(tmps)
#print(cmd)
#call gcc
os.system(cmd)
+1 -2
View File
@@ -96,8 +96,7 @@ for src in srcs:
# Parse the header files
headers_all = ""
line = "1"
while line:
line=ap_srcs_list.readline()
for line in ap_srcs_list:
line = line.strip()
if ":" in line:
line = line.split(":")[-1]
+7 -9
View File
@@ -1,10 +1,10 @@
<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 4.1.0, 2017-01-23T23:23:44. -->
<!-- Written by QtCreator 4.4.0, 2017-09-08T21:31:25. -->
<qtcreator>
<data>
<variable>EnvironmentId</variable>
<value type="QByteArray">{3799acf3-eb9e-4a06-886d-992bd0f8d07a}</value>
<value type="QByteArray">{67a68b0c-7516-47dc-923e-e0da33c1f7ec}</value>
</data>
<data>
<variable>ProjectExplorer.Project.ActiveTarget</variable>
@@ -19,7 +19,7 @@
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
<value type="QString" key="language">Cpp</value>
<valuemap type="QVariantMap" key="value">
<value type="QByteArray" key="CurrentPreferences">qt3</value>
<value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
</valuemap>
</valuemap>
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
@@ -54,16 +54,14 @@
</data>
<data>
<variable>ProjectExplorer.Project.PluginSettings</variable>
<valuemap type="QVariantMap">
<valuelist type="QVariantList" key="ClangStaticAnalyzer.SuppressedDiagnostics"/>
</valuemap>
<valuemap type="QVariantMap"/>
</data>
<data>
<variable>ProjectExplorer.Project.Target.0</variable>
<valuemap type="QVariantMap">
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop Qt 5.7.0 GCC 64bit</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop Qt 5.7.0 GCC 64bit</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">qt.57.gcc_64_kit</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop Qt 5.9.1 GCC 64bit</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop Qt 5.9.1 GCC 64bit</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">qt.591.gcc_64_kit</value>
<value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
<value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
<value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>