Merge branch 'master' into telemetry

fix ahrs_gx3 and stabilization_attitude_euler_float
This commit is contained in:
Felix Ruess
2013-10-23 13:05:35 +02:00
59 changed files with 1156 additions and 1371 deletions
+3
View File
@@ -31,6 +31,9 @@
/build.properties
/META-INF
# JetBrains (PyCharm, etc) IDE project files
.idea
/var
/dox
+3 -93
View File
@@ -227,101 +227,11 @@ $(AOBJ) : $(OBJDIR)/%.o : %.S
$(Q)test -d $(dir $@) || mkdir -p $(dir $@)
$(Q)$(CC) -c $(AFLAGS) $< -o $@
#
# check which flash mode is configured
#
ifeq ($(FLASH_MODE),DFU)
ifeq ($(DFU_UTIL),y)
#
# DFU flash mode using dfu-util
DFU_ADDR ?= 0x08000000
upload: $(OBJDIR)/$(TARGET).bin
@echo "Using dfu-util at $(DFU_ADDR)"
$(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR) -D $^
else
#
# DFU flash mode paparazzi stm32_mem
ifdef DFU_ADDR
DFU_ADDR_CMD = --addr=$(DFU_ADDR)
endif
ifdef DFU_PRODUCT
DFU_PRODUCT_CMD = --product=$(DFU_PRODUCT)
endif
upload: $(OBJDIR)/$(TARGET).bin
@echo "Using stm32 mem dfu loader"
$(PYTHON) $(PAPARAZZI_SRC)/sw/tools/dfu/stm32_mem.py $(DFU_PRODUCT_CMD) $(DFU_ADDR_CMD) $^
endif
#
# serial flash mode
else ifeq ($(FLASH_MODE),SERIAL)
upload: $(OBJDIR)/$(TARGET).bin
$(LOADER) -p /dev/ttyUSB0 -b 115200 -e -w -v $^
#
# JTAG flash mode
else ifeq ($(FLASH_MODE),JTAG)
# either via normal jtag or BlackMagicProbe
ifeq ($(BMP_PORT),)
# normal jtag via OpenOCD
upload: $(OBJDIR)/$(TARGET).hex
@echo "Assuming luftboot bootloader: $(ASSUMING_LUFTBOOT)"
@echo "Using OOCD = $(OOCD)"
@echo " OOCD\t$<"
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg $(OOCD_OPTIONS) \
-c init \
-c "reset halt" \
-c "reset init" \
-c "flash erase_sector 0 $(OOCD_START_SECTOR) last" \
-c "flash write_image $<" \
-c reset \
-c shutdown
else
# jtag via BMP
BMP_UPLOAD_SCRIPT ?= $(PAPARAZZI_SRC)/sw/tools/flash_scripts/bmp_jtag_flash.scr
upload: $(OBJDIR)/$(TARGET).elf
@echo "Assuming luftboot bootloader: $(ASSUMING_LUFTBOOT)"
@echo "Using Black Magic Probe with JTAG on BMP_PORT $(BMP_PORT)"
@echo "Using GDB = $(GDB)"
@echo " BMP\t$<"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(BMP_UPLOAD_SCRIPT) \
$<
endif
#
# SWD flash mode
else ifeq ($(FLASH_MODE),SWD)
# only works if BMP_PORT is defined
ifeq ($(STLINK),y)
STLINK_ADDR ?= 0x08000000
upload: $(OBJDIR)/$(TARGET).bin
@echo "Using ST-LINK with SWD at $(STLINK_ADDR)"
$(Q)st-flash write $^ $(STLINK_ADDR)
else
BMP_PORT ?= /dev/ttyACM0
BMP_UPLOAD_SCRIPT ?= $(PAPARAZZI_SRC)/sw/tools/flash_scripts/bmp_swd_flash.scr
upload: $(OBJDIR)/$(TARGET).elf
@echo "Assuming luftboot bootloader: $(ASSUMING_LUFTBOOT)"
@echo "Using Black Magic Probe with SWD on BMP_PORT $(BMP_PORT)"
@echo "Using GDB = $(GDB)"
@echo " BMP\t$<"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(BMP_UPLOAD_SCRIPT) \
$<
endif
#
# no known flash mode
else
upload:
@echo unknown flash_mode $(FLASH_MODE)
endif
# Load upload rules
include $(PAPARAZZI_SRC)/conf/Makefile.stm32-upload
# Listing of phony targets.
.PHONY : all build elf bin lss sym upload start_gdb start_telnet
.PHONY : all build elf bin lss sym start_gdb start_telnet
#
# Dependencies
+119
View File
@@ -0,0 +1,119 @@
# Hey Emacs, this is a -*- makefile -*-
#
# Copyright (C) 2013 Gautier Hattenberger
#
# 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/>.
#
#
# This is the common Makefile for STM32 upload rules
#
#
# check which flash mode is configured
#
ifeq ($(FLASH_MODE),DFU)
ifeq ($(DFU_UTIL),y)
#
# DFU flash mode using dfu-util
DFU_ADDR ?= 0x08000000
upload: $(OBJDIR)/$(TARGET).bin
@echo "Using dfu-util at $(DFU_ADDR)"
$(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR) -D $^
else
#
# DFU flash mode paparazzi stm32_mem
ifdef DFU_ADDR
DFU_ADDR_CMD = --addr=$(DFU_ADDR)
endif
ifdef DFU_PRODUCT
DFU_PRODUCT_CMD = --product=$(DFU_PRODUCT)
endif
upload: $(OBJDIR)/$(TARGET).bin
@echo "Using stm32 mem dfu loader"
$(PYTHON) $(PAPARAZZI_SRC)/sw/tools/dfu/stm32_mem.py $(DFU_PRODUCT_CMD) $(DFU_ADDR_CMD) $^
endif
#
# serial flash mode
else ifeq ($(FLASH_MODE),SERIAL)
upload: $(OBJDIR)/$(TARGET).bin
$(LOADER) -p /dev/ttyUSB0 -b 115200 -e -w -v $^
#
# JTAG flash mode
else ifeq ($(FLASH_MODE),JTAG)
# either via normal jtag or BlackMagicProbe
ifeq ($(BMP_PORT),)
# normal jtag via OpenOCD
upload: $(OBJDIR)/$(TARGET).hex
@echo "Assuming luftboot bootloader: $(ASSUMING_LUFTBOOT)"
@echo "Using OOCD = $(OOCD)"
@echo " OOCD\t$<"
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg $(OOCD_OPTIONS) \
-c init \
-c "reset halt" \
-c "reset init" \
-c "flash erase_sector 0 $(OOCD_START_SECTOR) last" \
-c "flash write_image $<" \
-c reset \
-c shutdown
else
# jtag via BMP
BMP_UPLOAD_SCRIPT ?= $(PAPARAZZI_SRC)/sw/tools/flash_scripts/bmp_jtag_flash.scr
upload: $(OBJDIR)/$(TARGET).elf
@echo "Assuming luftboot bootloader: $(ASSUMING_LUFTBOOT)"
@echo "Using Black Magic Probe with JTAG on BMP_PORT $(BMP_PORT)"
@echo "Using GDB = $(GDB)"
@echo " BMP\t$<"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(BMP_UPLOAD_SCRIPT) \
$<
endif
#
# SWD flash mode
else ifeq ($(FLASH_MODE),SWD)
# only works if BMP_PORT is defined
ifeq ($(STLINK),y)
STLINK_ADDR ?= 0x08000000
upload: $(OBJDIR)/$(TARGET).bin
@echo "Using ST-LINK with SWD at $(STLINK_ADDR)"
$(Q)st-flash write $^ $(STLINK_ADDR)
else
BMP_PORT ?= /dev/ttyACM0
BMP_UPLOAD_SCRIPT ?= $(PAPARAZZI_SRC)/sw/tools/flash_scripts/bmp_swd_flash.scr
upload: $(OBJDIR)/$(TARGET).elf
@echo "Assuming luftboot bootloader: $(ASSUMING_LUFTBOOT)"
@echo "Using Black Magic Probe with SWD on BMP_PORT $(BMP_PORT)"
@echo "Using GDB = $(GDB)"
@echo " BMP\t$<"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(BMP_UPLOAD_SCRIPT) \
$<
endif
#
# no known flash mode
else
upload:
@echo unknown flash_mode $(FLASH_MODE)
endif
.PHONY : upload
+1
View File
@@ -216,6 +216,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
+258
View File
@@ -0,0 +1,258 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!-- Funjet Multiplex (http://www.multiplex-rc.de/)
Umarim Lite
Radiotronix modem
UBX GPS
Airspeed sensor
Digital camera
-->
<airframe name="Funjet II">
<modules>
<!--load name="light.xml">
<define name="LIGHT_LED_STROBE" value="5"/>
<define name="LIGHT_LED_NAV" value="3"/>
</load-->
<!--load name="baro_board.xml">
<define name="BARO_ABS_EVENT" value="BaroPbnUpdate"/>
</load-->
<load name="pbn.xml"/>
</modules>
<firmware name="fixedwing">
<define name="USE_I2C0"/>
<define name="USE_I2C1"/>
<define name="AGR_CLIMB"/>
<!--define name="ALT_KALMAN"/-->
<define name="LOITER_TRIM"/>
<define name="USE_AIRSPEED"/>
<target name="sim" board="pc">
<subsystem name="imu" type="umarim"/>
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="crrcsim"/>
<subsystem name="imu" type="nps"/>
</target>
<target name="ap" board="umarim_lite_2.0">
<subsystem name="imu" type="umarim"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" type="transparent"/>
<!-- Actuators are automatically chosen according to board-->
<subsystem name="ahrs" type="float_dcm"/>
<subsystem name="ins" type="alt_float"/>
<subsystem name="control" type="new">
<define name="USE_GYRO_PITCH_RATE"/>
</subsystem>
<!-- Sensors -->
<subsystem name="gps" type="ublox"/>
<subsystem name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_0"/>
</subsystem>
<subsystem name="navigation"/>
</firmware>
<servos>
<servo name="MOTOR" no="0" min="1040" neutral="1040" max="2000"/>
<servo name="AILEVON_LEFT" no="2" min="1900" neutral="1500" max="1050"/>
<servo name="AILEVON_RIGHT" no="1" min="1120" neutral="1540" max="1980"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>
<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>
<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator - $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator + $aileron"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="-1"/>
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="5"/>
<define name="GYRO_Q_NEUTRAL" value="17"/>
<define name="GYRO_R_NEUTRAL" value="-5 "/>
<define name="GYRO_P_SENS" value="1." integer="16"/>
<define name="GYRO_Q_SENS" value="1." integer="16"/>
<define name="GYRO_R_SENS" value="1." integer="16"/>
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="ACCEL_X_NEUTRAL" value="6"/>
<define name="ACCEL_Y_NEUTRAL" value="-3"/>
<define name="ACCEL_Z_NEUTRAL" value="-8"/>
<define name="ACCEL_X_SENS" value="38.273044006" integer="16"/>
<define name="ACCEL_Y_SENS" value="39.3799642589" integer="16"/>
<define name="ACCEL_Z_SENS" value="39.6142126316" integer="16"/>
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="-1"/>
<define name="MAG_Z_SIGN" value="-1"/>
<define name="MAG_X_NEUTRAL" value="6"/>
<define name="MAG_Y_NEUTRAL" value="-3"/>
<define name="MAG_Z_NEUTRAL" value="-8"/>
<define name="MAG_X_SENS" value="38.273044006" integer="16"/>
<define name="MAG_Y_SENS" value="39.3799642589" integer="16"/>
<define name="MAG_Z_SENS" value="39.6142126316" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="8." unit="deg"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-100)*26.9"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="ALT_KALMAN_ENABLED" value="FALSE"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.1"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="4."/>
<!-- disable climb rate limiter -->
<define name="AUTO_CLIMB_LIMIT" value="2*V_CTL_ALTITUDE_MAX_CLIMB"/>
<!-- auto throttle inner loop -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
<!--define name="AUTO_THROTTLE_LOITER_TRIM" value="1000"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000"/-->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.005"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.003"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.02"/>
<!-- auto pitch inner loop -->
<define name="AUTO_PITCH_PGAIN" value="0.03"/>
<define name="AUTO_PITCH_DGAIN" value="0.03"/>
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
<!--define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.14"/-->
<define name="AUTO_PITCH_MAX_PITCH" value="20" unit="deg"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-20" unit="deg"/>
<!-- airspeed control -->
<define name="AUTO_AIRSPEED_SETPOINT" value="16."/>
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.1"/>
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.12"/>
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.06"/>
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.042"/>
<define name="AIRSPEED_MAX" value="30"/>
<define name="AIRSPEED_MIN" value="10"/>
<!-- groundspeed control -->
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
<!-- pitch trim -->
<define name="PITCH_LOITER_TRIM" value="0." unit="deg"/>
<define name="PITCH_DASH_TRIM" value="0." unit="deg"/>
<define name="THROTTLE_SLEW" value="0.1"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.6"/>
<define name="ROLL_MAX_SETPOINT" value="0.8" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
<define name="ROLL_ATTITUDE_GAIN" value="9000."/>
<define name="ROLL_RATE_GAIN" value="1000."/>
<define name="ROLL_IGAIN" value="150."/>
<define name="PITCH_PGAIN" value="18000."/>
<define name="PITCH_DGAIN" value="500"/>
<define name="PITCH_IGAIN" value="250."/>
<define name="PITCH_OF_ROLL" value="1." unit="deg"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
<!--define name="ELEVATOR_OF_ROLL" value="1400"/-->
</section>
<section name="NAV">
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="2" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
</section>
<section name="SIMU">
<define name="YAW_RESPONSE_FACTOR" value="0.6"/>
</section>
<section name="NPS" prefix="NPS_">
<define name="BYPASS_AHRS" value="TRUE"/>
<define name="CRRCSIM_COMMAND_ROLL" value="1"/>
<define name="CRRCSIM_COMMAND_PITCH" value="2"/>
<define name="CRRCSIM_COMMAND_THROTTLE" value="0"/>
<define name="CRRCSIM_ROLL_NEUTRAL" value="0." unit="deg"/>
<define name="CRRCSIM_PITCH_NEUTRAL" value="12." unit="deg"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
</airframe>
@@ -257,6 +257,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<!--define name="JSBSIM_INIT" value="&quot;reset_enac&quot;"/-->
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
@@ -92,10 +92,6 @@
<define name="H_Z" value="0.858336"/>
</section>
<section name="INS" prefix="INS_">
<define name="BARO_SENS" value="22.4" integer="16"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
@@ -249,6 +249,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
@@ -249,6 +249,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
+1 -4
View File
@@ -189,10 +189,6 @@
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="13"/>
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
<define name="RC_CLIMB_COEF" value="163"/>
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
@@ -210,6 +206,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;top_left_motor&quot;, &quot;top_right_motor&quot;, &quot;bottom_right_motor&quot;, &quot;bottom_left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
+1
View File
@@ -190,6 +190,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
@@ -214,6 +214,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
@@ -212,6 +212,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
+1
View File
@@ -175,6 +175,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
@@ -199,6 +199,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<define name="JS_AXIS_MODE" value="4"/>
@@ -200,6 +200,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
@@ -189,6 +189,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
@@ -180,6 +180,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
@@ -198,6 +198,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<define name="JS_AXIS_MODE" value="4"/>
@@ -264,6 +264,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
@@ -194,6 +194,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
</section>
@@ -235,6 +235,7 @@
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="JSBSIM_MODEL" value="&quot;simple_quad_ccw&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_default.h&quot;"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<define name="JS_AXIS_MODE" value="4"/>
@@ -0,0 +1,52 @@
# Hey Emacs, this is a -*- makefile -*-
#
# SITL Simulator based on CRRCSIM (MNAV inputdev)
#
SRC_FIRMWARE=firmwares/fixedwing
SRC_BOARD=boards/$(BOARD)
NPSDIR = $(SIMDIR)/nps
nps.ARCHDIR = sim
# include Makefile.nps instead of Makefile.sim
nps.MAKEFILE = nps
# add normal ap and fbw sources define in autopilot.makefile
nps.CFLAGS += $(fbw_CFLAGS) $(ap_CFLAGS)
nps.srcs += $(fbw_srcs) $(ap_srcs)
nps.CFLAGS += -DSITL -DUSE_NPS
nps.CFLAGS += $(shell pkg-config glib-2.0 --cflags)
nps.LDFLAGS += $(shell pkg-config glib-2.0 --libs) -lm -lglibivy -lpcre -lgsl -lgslcblas
nps.CFLAGS += -I$(NPSDIR) -I$(SRC_FIRMWARE) -I$(SRC_BOARD) -I../simulator -I$(PAPARAZZI_HOME)/conf/simulator/nps
nps.LDFLAGS += $(shell sdl-config --libs)
nps.srcs += $(NPSDIR)/nps_main.c \
$(NPSDIR)/nps_fdm_crrcsim.c \
$(NPSDIR)/nps_random.c \
$(NPSDIR)/nps_sensors.c \
$(NPSDIR)/nps_sensors_utils.c \
$(NPSDIR)/nps_sensor_gyro.c \
$(NPSDIR)/nps_sensor_accel.c \
$(NPSDIR)/nps_sensor_mag.c \
$(NPSDIR)/nps_sensor_baro.c \
$(NPSDIR)/nps_sensor_gps.c \
$(NPSDIR)/nps_electrical.c \
$(NPSDIR)/nps_atmosphere.c \
$(NPSDIR)/nps_radio_control.c \
$(NPSDIR)/nps_radio_control_joystick.c \
$(NPSDIR)/nps_radio_control_spektrum.c \
$(NPSDIR)/nps_autopilot_fixedwing.c \
$(NPSDIR)/nps_ivy_common.c \
$(NPSDIR)/nps_ivy_fixedwing.c \
$(NPSDIR)/nps_flightgear.c \
nps.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport
nps.srcs += subsystems/datalink/downlink.c $(SRC_FIRMWARE)/datalink.c $(SRC_ARCH)/ivy_transport.c
@@ -6,6 +6,7 @@ GX3_BAUD ?= B921600
AHRS_ALIGNER_LED ?= none
AHRS_CFLAGS = -DUSE_AHRS
AHRS_CFLAGS += -DAHRS_FLOAT
AHRS_CFLAGS += -DUSE_IMU
AHRS_CFLAGS += -DUSE_IMU_FLOAT
AHRS_CFLAGS += -DUSE_GX3
@@ -59,9 +59,11 @@ else ifeq ($(ARCH), stm32)
DROTEK_2_I2C_DEV ?= i2c2
endif
ifeq ($(TARGET), ap)
ifndef DROTEK_2_I2C_DEV
$(error Error: DROTEK_2_I2C_DEV not configured!)
endif
endif
# convert i2cx to upper/lower case
DROTEK_2_I2C_DEV_UPPER=$(shell echo $(DROTEK_2_I2C_DEV) | tr a-z A-Z)
@@ -28,9 +28,11 @@ else ifeq ($(ARCH), stm32)
GL1_I2C_DEV ?= i2c2
endif
ifeq ($(TARGET), ap)
ifndef GL1_I2C_DEV
$(error Error: GL1_I2C_DEV not configured!)
endif
endif
# convert i2cx to upper/lower case
GL1_I2C_DEV_UPPER=$(shell echo $(GL1_I2C_DEV) | tr a-z A-Z)
@@ -0,0 +1,27 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">
<settings>
<dl_settings>
<dl_settings NAME="Att Loop">
<dl_setting var="stabilization_gains.p.x" min="1" step="1" max="8000" module="stabilization/stabilization_attitude" shortname="pgain phi" param="STABILIZATION_ATTITUDE_PHI_PGAIN"/>
<dl_setting var="stabilization_gains.i.x" min="0" step="1" max="800" module="stabilization/stabilization_attitude" shortname="igain phi" param="STABILIZATION_ATTITUDE_PHI_IGAIN" />
<dl_setting var="stabilization_gains.d.x" min="1" step="1" max="4000" module="stabilization/stabilization_attitude" shortname="dgain p" param="STABILIZATION_ATTITUDE_PHI_DGAIN"/>
<dl_setting var="stabilization_gains.rates_d.x" min="0" step="1" max="500" module="stabilization/stabilization_attitude" shortname="dgaind p" param="STABILIZATION_ATTITUDE_PHI_DGAIN_D"/>
<dl_setting var="stabilization_gains.dd.x" min="0" step="1" max="1000" module="stabilization/stabilization_attitude" shortname="ddgain p" param="STABILIZATION_ATTITUDE_PHI_DDGAIN"/>
<dl_setting var="stabilization_gains.p.y" min="1" step="1" max="8000" module="stabilization/stabilization_attitude" shortname="pgain theta" param="STABILIZATION_ATTITUDE_THETA_PGAIN"/>
<dl_setting var="stabilization_gains.i.y" min="0" step="1" max="800" module="stabilization/stabilization_attitude" shortname="igain theta" param="STABILIZATION_ATTITUDE_THETA_IGAIN"/>
<dl_setting var="stabilization_gains.d.y" min="1" step="1" max="4000" module="stabilization/stabilization_attitude" shortname="dgain q" param="STABILIZATION_ATTITUDE_THETA_DGAIN"/>
<dl_setting var="stabilization_gains.rates_d.y" min="0" step="1" max="500" module="stabilization/stabilization_attitude" shortname="dgaind q" param="STABILIZATION_ATTITUDE_THETA_DGAIN_D"/>
<dl_setting var="stabilization_gains.dd.y" min="0" step="1" max="1000" module="stabilization/stabilization_attitude" shortname="ddgain q" param="STABILIZATION_ATTITUDE_THETA_DDGAIN"/>
<dl_setting var="stabilization_gains.p.z" min="1" step="1" max="4000" module="stabilization/stabilization_attitude" shortname="pgain psi" param="STABILIZATION_ATTITUDE_PSI_PGAIN"/>
<dl_setting var="stabilization_gains.i.z" min="0" step="1" max="400" module="stabilization/stabilization_attitude" shortname="igain psi" param="STABILIZATION_ATTITUDE_PSI_IGAIN"/>
<dl_setting var="stabilization_gains.d.z" min="1" step="1" max="4000" module="stabilization/stabilization_attitude" shortname="dgain r" param="STABILIZATION_ATTITUDE_PSI_DGAIN"/>
<dl_setting var="stabilization_gains.rates_d.z" min="0" step="1" max="500" module="stabilization/stabilization_attitude" shortname="dgaind r" param="STABILIZATION_ATTITUDE_PHI_DGAIN_D"/>
<dl_setting var="stabilization_gains.dd.z" min="0" step="1" max="1000" module="stabilization/stabilization_attitude" shortname="ddgain r" param="STABILIZATION_ATTITUDE_PSI_DDGAIN"/>
</dl_settings>
</dl_settings>
</settings>
-396
View File
@@ -1,396 +0,0 @@
<?xml version="1.0"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sourceforge.net/JSBSim.xsl"?>
<fdm_config name="QUAD COMPLETE EXT" version="2.0" release="BETA" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> Gustavo Violato &amp; Antoine Drouin</author>
<filecreationdate> 24-02-2009 </filecreationdate>
<version> Version 0.9 - beta</version>
<description> Simple Quadrotor without rotor dynamic </description>
</fileheader>
<metrics>
<wingarea unit="IN2"> 78.53 </wingarea>
<wingspan unit="IN"> 10 </wingspan>
<chord unit="IN"> 6.89 </chord>
<htailarea unit="FT2"> 0 </htailarea>
<htailarm unit="FT"> 0 </htailarm>
<vtailarea unit="FT2"> 0 </vtailarea>
<vtailarm unit="FT"> 0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="VRP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</metrics>
<mass_balance>
<ixx unit="SLUG*FT2"> 0.005 </ixx>
<iyy unit="SLUG*FT2"> 0.005 </iyy>
<izz unit="SLUG*FT2"> 0.010 </izz>
<ixy unit="SLUG*FT2"> 0. </ixy>
<ixz unit="SLUG*FT2"> 0. </ixz>
<iyz unit="SLUG*FT2"> 0. </iyz>
<emptywt unit="LBS"> 0.84 </emptywt>
<location name="CG" unit="M">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</mass_balance>
<ground_reactions>
<contact type="STRUCTURE" name="CONTACT_FRONT">
<location unit="M">
<x>-0.15 </x>
<y> 0 </y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_BACK">
<location unit="M">
<x> 0.15</x>
<y> 0 </y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_RIGHT">
<location unit="M">
<x> 0. </x>
<y> 0.15</y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_LEFT">
<location unit="M">
<x> 0. </x>
<y>-0.15</y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
</ground_reactions>
<external_reactions>
<property>fcs/front_motor</property>
<property>fcs/back_motor</property>
<property>fcs/right_motor</property>
<property>fcs/left_motor</property>
<!-- First the lift forces produced by each propeller -->
<force name="front_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<y>0</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="back_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>0</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="right_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>0</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="left_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>0</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<!-- Then the Moment Couples -->
<!-- Front Engine -->
<force name="front_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<!-- Necessary arm in IN to produce a moment ten times
"weaker" then the force when both are measured in the SI.
front and back motors turning clockwise, left and right motors
turning anti-clockwise when view from up-->
<y>1.9685</y>
<z>0</z>
</location>
<direction>
<x>1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<force name="front_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<y>-1.9685</y>
<z>0</z>
</location>
<direction>
<x>-1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<!-- Back Engine -->
<force name="back_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>1.9685</y>
<z>0</z>
</location>
<direction>
<x>1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<force name="back_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>-1.9685</y>
<z>0</z>
</location>
<direction>
<x>-1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<!-- Right Engine -->
<force name="right_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-1.9685</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>1</y>
<z>0</z>
</direction>
</force>
<force name="right_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>1.9685</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>-1</y>
<z>0</z>
</direction>
</force>
<!-- Left Engine -->
<force name="left_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-1.9685</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>1</y>
<z>0</z>
</direction>
</force>
<force name="left_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>1.9685</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>-1</y>
<z>0</z>
</direction>
</force>
</external_reactions>
<propulsion/>
<flight_control name="FGFCS"/>
<aerodynamics>
<axis name="DRAG">
<function name="aero/coefficient/CD">
<description>Drag</description>
<product>
<property>aero/qbar-psf</property>
<value>47.9</value> <!-- Conversion to pascals -->
<value>0.0151</value> <!-- CD x Area (m^2) -->
<value>0.224808943</value> <!-- N to LBS -->
</product>
</function>
</axis>
</aerodynamics>
</fdm_config>
@@ -1,396 +0,0 @@
<?xml version="1.0"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sourceforge.net/JSBSim.xsl"?>
<fdm_config name="QUAD COMPLETE EXT" version="2.0" release="BETA" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> Gustavo Violato &amp; Antoine Drouin</author>
<filecreationdate> 24-02-2009 </filecreationdate>
<version> Version 0.9 - beta</version>
<description> Simple Quadrotor without rotor dynamic </description>
</fileheader>
<metrics>
<wingarea unit="IN2"> 78.53 </wingarea>
<wingspan unit="IN"> 10 </wingspan>
<chord unit="IN"> 6.89 </chord>
<htailarea unit="FT2"> 0 </htailarea>
<htailarm unit="FT"> 0 </htailarm>
<vtailarea unit="FT2"> 0 </vtailarea>
<vtailarm unit="FT"> 0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="VRP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</metrics>
<mass_balance>
<ixx unit="SLUG*FT2"> 0.005 </ixx>
<iyy unit="SLUG*FT2"> 0.005 </iyy>
<izz unit="SLUG*FT2"> 0.010 </izz>
<ixy unit="SLUG*FT2"> 0. </ixy>
<ixz unit="SLUG*FT2"> 0. </ixz>
<iyz unit="SLUG*FT2"> 0. </iyz>
<emptywt unit="LBS"> 0.84 </emptywt>
<location name="CG" unit="M">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</mass_balance>
<ground_reactions>
<contact type="STRUCTURE" name="CONTACT_FRONT">
<location unit="M">
<x>-0.15 </x>
<y> 0 </y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_BACK">
<location unit="M">
<x> 0.15</x>
<y> 0 </y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_RIGHT">
<location unit="M">
<x> 0. </x>
<y> 0.15</y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_LEFT">
<location unit="M">
<x> 0. </x>
<y>-0.15</y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
</ground_reactions>
<external_reactions>
<property>fcs/front_motor</property>
<property>fcs/back_motor</property>
<property>fcs/right_motor</property>
<property>fcs/left_motor</property>
<!-- First the lift forces produced by each propeller -->
<force name="front_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<y>0</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="back_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>0</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="right_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>0</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="left_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>0</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<!-- Then the Moment Couples -->
<!-- Front Engine -->
<force name="front_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<!-- Necessary arm in IN to produce a moment ten times
"weaker" then the force when both are measured in the SI.
front and back motors turning clockwise, left and right motors
turning anti-clockwise when view from up-->
<y>1.9685</y>
<z>0</z>
</location>
<direction>
<x>1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<force name="front_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<y>-1.9685</y>
<z>0</z>
</location>
<direction>
<x>-1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<!-- Back Engine -->
<force name="back_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>1.9685</y>
<z>0</z>
</location>
<direction>
<x>1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<force name="back_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>-1.9685</y>
<z>0</z>
</location>
<direction>
<x>-1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<!-- Right Engine -->
<force name="right_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-1.9685</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>1</y>
<z>0</z>
</direction>
</force>
<force name="right_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>1.9685</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>-1</y>
<z>0</z>
</direction>
</force>
<!-- Left Engine -->
<force name="left_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-1.9685</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>1</y>
<z>0</z>
</direction>
</force>
<force name="left_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>1.9685</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>-1</y>
<z>0</z>
</direction>
</force>
</external_reactions>
<propulsion/>
<flight_control name="FGFCS"/>
<aerodynamics>
<axis name="DRAG">
<function name="aero/coefficient/CD">
<description>Drag</description>
<product>
<property>aero/qbar-psf</property>
<value>47.9</value> <!-- Conversion to pascals -->
<value>0.0151</value> <!-- CD x Area (m^2) -->
<value>0.224808943</value> <!-- N to LBS -->
</product>
</function>
</axis>
</aerodynamics>
</fdm_config>
-396
View File
@@ -1,396 +0,0 @@
<?xml version="1.0"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sourceforge.net/JSBSim.xsl"?>
<fdm_config name="QUAD COMPLETE EXT" version="2.0" release="BETA" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> Gustavo Violato &amp; Antoine Drouin </author>
<filecreationdate> 24-02-2009 </filecreationdate>
<version> Version 0.9 - beta</version>
<description> Simple Quadrotor without rotor dynamic </description>
</fileheader>
<metrics>
<wingarea unit="IN2"> 78.53 </wingarea>
<wingspan unit="IN"> 10 </wingspan>
<chord unit="IN"> 6.89 </chord>
<htailarea unit="FT2"> 0 </htailarea>
<htailarm unit="FT"> 0 </htailarm>
<vtailarea unit="FT2"> 0 </vtailarea>
<vtailarm unit="FT"> 0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="VRP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</metrics>
<mass_balance>
<ixx unit="SLUG*FT2"> 0.005 </ixx>
<iyy unit="SLUG*FT2"> 0.005 </iyy>
<izz unit="SLUG*FT2"> 0.010 </izz>
<ixy unit="SLUG*FT2"> 0. </ixy>
<ixz unit="SLUG*FT2"> 0. </ixz>
<iyz unit="SLUG*FT2"> 0. </iyz>
<emptywt unit="LBS"> 0.84 </emptywt>
<location name="CG" unit="M">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</mass_balance>
<ground_reactions>
<contact type="STRUCTURE" name="CONTACT_FRONT">
<location unit="M">
<x>-0.15 </x>
<y> 0 </y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_BACK">
<location unit="M">
<x> 0.15</x>
<y> 0 </y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_RIGHT">
<location unit="M">
<x> 0. </x>
<y> 0.15</y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="STRUCTURE" name="CONTACT_LEFT">
<location unit="M">
<x> 0. </x>
<y>-0.15</y>
<z>-0.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<spring_coeff unit="N/M"> 500 </spring_coeff>
<damping_coeff unit="N/M/SEC"> 100 </damping_coeff>
<damping_coeff_rebound type="SQUARE" unit="N/M2/SEC2"> 1000 </damping_coeff_rebound>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
</ground_reactions>
<external_reactions>
<property>fcs/front_motor</property>
<property>fcs/back_motor</property>
<property>fcs/right_motor</property>
<property>fcs/left_motor</property>
<!-- First the lift forces produced by each propeller -->
<force name="front_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<y>0</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="back_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>0</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="right_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>0</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<force name="left_motor" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>0</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>0</y>
<z>-1</z>
</direction>
</force>
<!-- Then the Moment Couples -->
<!-- Front Engine -->
<force name="front_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<!-- Necessary arm in IN to produce a moment ten times
"weaker" then the force when both are measured in the SI.
front and back motors turning clockwise, left and right motors
turning anti-clockwise when view from up-->
<y>1.9685</y>
<z>0</z>
</location>
<direction>
<x>-1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<force name="front_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/front_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-6.89</x>
<y>-1.9685</y>
<z>0</z>
</location>
<direction>
<x>1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<!-- Back Engine -->
<force name="back_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>1.9685</y>
<z>0</z>
</location>
<direction>
<x>-1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<force name="back_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/back_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>6.89</x>
<y>-1.9685</y>
<z>0</z>
</location>
<direction>
<x>1</x>
<y>0</y>
<z>0</z>
</direction>
</force>
<!-- Right Engine -->
<force name="right_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-1.9685</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>-1</y>
<z>0</z>
</direction>
</force>
<force name="right_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/right_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>1.9685</x>
<y>6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>1</y>
<z>0</z>
</direction>
</force>
<!-- Left Engine -->
<force name="left_couple1" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>-1.9685</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>-1</y>
<z>0</z>
</direction>
</force>
<force name="left_couple2" frame="BODY" unit="LBS">
<function>
<product>
<property>fcs/left_motor</property>
<value> 0.84 </value>
</product>
</function>
<location unit="IN">
<x>1.9685</x>
<y>-6.89</y>
<z>0</z>
</location>
<direction>
<x>0</x>
<y>1</y>
<z>0</z>
</direction>
</force>
</external_reactions>
<propulsion/>
<flight_control name="FGFCS"/>
<aerodynamics>
<axis name="DRAG">
<function name="aero/coefficient/CD">
<description>Drag</description>
<product>
<property>aero/qbar-psf</property>
<value>47.9</value> <!-- Conversion to pascals -->
<value>0.0151</value> <!-- CD x Area (m^2) -->
<value>0.224808943</value> <!-- N to LBS -->
</product>
</function>
</axis>
</aerodynamics>
</fdm_config>
@@ -67,7 +67,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph* p, uint8_t bits, uint8
else // 8 data bits by default
usart_set_databits((uint32_t)p->reg_addr, 9);
}
else if (parity == USART_PARITY_ODD) {
else if (parity == UPARITY_ODD) {
usart_set_parity((uint32_t)p->reg_addr, USART_PARITY_ODD);
if (bits == UBITS_7)
usart_set_databits((uint32_t)p->reg_addr, 8);
+28 -7
View File
@@ -36,8 +36,31 @@
#include "subsystems/abi.h"
#include "led.h"
/** Normal frequency with the default settings
*
* the baro read function should be called at 5 Hz
*/
#ifndef BARO_BOARD_APOGEE_FREQ
#define BARO_BOARD_APOGEE_FREQ 5
#endif
/** Baro periodic prescaler
*
* different for fixedwing and rotorcraft...
*/
#ifdef BARO_PERIODIC_FREQUENCY
#define MPL_PRESCALER ((BARO_PERIODIC_FREQUENCY)/BARO_BOARD_APOGEE_FREQ)
#else
#ifdef PERIODIC_FREQUENCY
#define MPL_PRESCALER ((PERIODIC_FREQUENCY)/BARO_BOARD_APOGEE_FREQ)
#else
// default: assuming 60Hz for a 5Hz baro update
#define MPL_PRESCALER 12
#endif
#endif
/** Counter to init ads1114 at startup */
#define BARO_STARTUP_COUNTER 200
#define BARO_STARTUP_COUNTER (200/(MPL_PRESCALER))
uint16_t startup_cnt;
struct Mpl3115 apogee_baro;
@@ -67,17 +90,15 @@ void baro_periodic( void ) {
#endif
}
// Read the sensor
mpl3115_periodic(&apogee_baro);
RunOnceEvery(MPL_PRESCALER, mpl3115_periodic(&apogee_baro));
}
}
void apogee_baro_event(void) {
mpl3115_event(&apogee_baro);
if (apogee_baro.data_available) {
if (startup_cnt == 0) {
float pressure = ((float)apogee_baro.pressure/(1<<2));
AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, &pressure);
}
if (apogee_baro.data_available && startup_cnt == 0) {
float pressure = ((float)apogee_baro.pressure/(1<<2));
AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, &pressure);
apogee_baro.data_available = FALSE;
}
}
+2 -2
View File
@@ -81,12 +81,12 @@ void baro_periodic(void) {
&bb_ms5611.data.c[4],
&bb_ms5611.data.c[5],
&bb_ms5611.data.c[6],
&bb_ms5611.data.c[7]);
&bb_ms5611.data.c[7]));
#endif
}
}
void baro_event(void){
void baro_event(void) {
if (sys_time.nb_sec > 1) {
ms5611_i2c_event(&bb_ms5611);
+2 -2
View File
@@ -70,12 +70,12 @@ void baro_periodic(void) {
&bb_ms5611.data.c[4],
&bb_ms5611.data.c[5],
&bb_ms5611.data.c[6],
&bb_ms5611.data.c[7]);
&bb_ms5611.data.c[7]));
#endif
}
}
void baro_event(){
void baro_event(void) {
if (sys_time.nb_sec > 1) {
ms5611_spi_event(&bb_ms5611);
+4 -4
View File
@@ -65,8 +65,8 @@
* PD9 = UART3 RX
* PD10 = FREE
* PD11 = FREE
* PD12 = LED_3
* PD13 = LED_4
* PD12 = LED_4
* PD13 = LED_3
* PD14 = LED_5
* PD15 = LED_6
*
@@ -110,7 +110,7 @@
#endif
#define LED_3_GPIO GPIOD
#define LED_3_GPIO_CLK RCC_AHB1ENR_IOPDEN
#define LED_3_GPIO_PIN GPIO12
#define LED_3_GPIO_PIN GPIO13
#define LED_3_AFIO_REMAP ((void)0)
#define LED_3_GPIO_ON gpio_set
#define LED_3_GPIO_OFF gpio_clear
@@ -121,7 +121,7 @@
#endif
#define LED_4_GPIO GPIOD
#define LED_4_GPIO_CLK RCC_AHB1ENR_IOPDEN
#define LED_4_GPIO_PIN GPIO13
#define LED_4_GPIO_PIN GPIO12
#define LED_4_AFIO_REMAP ((void)0)
#define LED_4_GPIO_ON gpio_set
#define LED_4_GPIO_OFF gpio_clear
@@ -57,6 +57,7 @@
#endif
PRINT_CONFIG_VAR(GUIDANCE_H_USE_REF)
PRINT_CONFIG_VAR(GUIDANCE_H_USE_SPEED_REF)
#ifndef GUIDANCE_H_APPROX_FORCE_BY_THRUST
#define GUIDANCE_H_APPROX_FORCE_BY_THRUST FALSE
@@ -41,6 +41,14 @@
#define GUIDANCE_H_USE_REF TRUE
#endif
/** Use horizontal guidance speed reference.
* This also allows to give velocity commands via RC in GUIDANCE_H_MODE_HOVER.
* Default is TRUE, define to FALSE to always disable it.
*/
#ifndef GUIDANCE_H_USE_SPEED_REF
#define GUIDANCE_H_USE_SPEED_REF TRUE
#endif
#define GUIDANCE_H_MODE_KILL 0
#define GUIDANCE_H_MODE_RATE 1
#define GUIDANCE_H_MODE_ATTITUDE 2
@@ -46,7 +46,7 @@ struct FloatAttitudeGains {
struct FloatVect3 surface_i;
};
extern struct FloatEulers stabilization_att_sum_err_eulers;
extern struct FloatEulers stabilization_att_sum_err;
extern float stabilization_att_fb_cmd[COMMANDS_NB];
extern float stabilization_att_ff_cmd[COMMANDS_NB];
@@ -48,9 +48,9 @@ static void send_att(void) {
&stab_att_sp_euler.phi,
&stab_att_sp_euler.theta,
&stab_att_sp_euler.psi,
&stabilization_att_sum_err_eulers.phi,
&stabilization_att_sum_err_eulers.theta,
&stabilization_att_sum_err_eulers.psi,
&stabilization_att_sum_err.phi,
&stabilization_att_sum_err.theta,
&stabilization_att_sum_err.psi,
&stabilization_att_fb_cmd[COMMAND_ROLL],
&stabilization_att_fb_cmd[COMMAND_PITCH],
&stabilization_att_fb_cmd[COMMAND_YAW],
@@ -36,7 +36,7 @@
struct FloatAttitudeGains stabilization_gains[STABILIZATION_ATTITUDE_GAIN_NB];
struct FloatQuat stabilization_att_sum_err_quat;
struct FloatEulers stabilization_att_sum_err_eulers;
struct FloatEulers stabilization_att_sum_err;
struct FloatRates last_body_rate;
@@ -109,7 +109,7 @@ void stabilization_attitude_init(void) {
}
FLOAT_QUAT_ZERO( stabilization_att_sum_err_quat );
FLOAT_EULERS_ZERO( stabilization_att_sum_err_eulers );
FLOAT_EULERS_ZERO( stabilization_att_sum_err );
FLOAT_RATES_ZERO( last_body_rate );
}
@@ -131,7 +131,7 @@ void stabilization_attitude_enter(void) {
stabilization_attitude_ref_enter();
FLOAT_QUAT_ZERO( stabilization_att_sum_err_quat );
FLOAT_EULERS_ZERO( stabilization_att_sum_err_eulers );
FLOAT_EULERS_ZERO( stabilization_att_sum_err );
}
void stabilization_attitude_set_failsafe_setpoint(void) {
@@ -264,11 +264,11 @@ void stabilization_attitude_run(bool_t enable_integrator) {
FLOAT_QUAT_COMP(new_sum_err, stabilization_att_sum_err_quat, scaled_att_err);
FLOAT_QUAT_NORMALIZE(new_sum_err);
FLOAT_QUAT_COPY(stabilization_att_sum_err_quat, new_sum_err);
FLOAT_EULERS_OF_QUAT(stabilization_att_sum_err_eulers, stabilization_att_sum_err_quat);
FLOAT_EULERS_OF_QUAT(stabilization_att_sum_err, stabilization_att_sum_err_quat);
} else {
/* reset accumulator */
FLOAT_QUAT_ZERO( stabilization_att_sum_err_quat );
FLOAT_EULERS_ZERO( stabilization_att_sum_err_eulers );
FLOAT_EULERS_ZERO( stabilization_att_sum_err );
}
attitude_run_ff(stabilization_att_ff_cmd, &stabilization_gains[gain_idx], &stab_att_ref_accel);
@@ -82,8 +82,8 @@ void stabilization_attitude_ref_update() {
stab_att_ref_accel.r = -2.*ZETA_R*OMEGA_P*stab_att_ref_rate.r - OMEGA_R*OMEGA_R*ref_err.psi;
/* saturate acceleration */
const struct Int32Rates MIN_ACCEL = { -REF_ACCEL_MAX_P, -REF_ACCEL_MAX_Q, -REF_ACCEL_MAX_R };
const struct Int32Rates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R }; \
const struct FloatRates MIN_ACCEL = { -REF_ACCEL_MAX_P, -REF_ACCEL_MAX_Q, -REF_ACCEL_MAX_R };
const struct FloatRates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R };
RATES_BOUND_BOX(stab_att_ref_accel, MIN_ACCEL, MAX_ACCEL);
/* saturate speed and trim accel accordingly */
+1 -1
View File
@@ -99,7 +99,7 @@ void mpl3115_read(struct Mpl3115 *mpl)
mpl->req_trans.buf[0] = MPL3115_REG_CTRL_REG1;
mpl->req_trans.buf[1] = ((MPL3115_OVERSAMPLING<<3) | (mpl->raw_mode<<6) |
(mpl->alt_mode<<7) | MPL3115_OST_BIT);
i2c_transmit(mpl->i2c_p, &mpl->trans, mpl->trans.slave_addr, 2);
i2c_transmit(mpl->i2c_p, &mpl->req_trans, mpl->trans.slave_addr, 2);
}
}
}
+11 -7
View File
@@ -744,8 +744,9 @@ void stateCalcHorizontalSpeedNorm_i(void) {
state.h_speed_norm_i = SPEED_BFP_OF_REAL(state.h_speed_norm_f);
}
else if (bit_is_set(state.speed_status, SPEED_NED_I)) {
/// @todo consider INT32_SPEED_FRAC
INT32_VECT2_NORM(state.h_speed_norm_i, state.ned_speed_i);
int32_t n2 = (state.ned_speed_i.x*state.ned_speed_i.x +
state.ned_speed_i.y*state.ned_speed_i.y) >> INT32_SPEED_FRAC;
INT32_SQRT(state.h_speed_norm_i, n2);
}
else if (bit_is_set(state.speed_status, SPEED_NED_F)) {
FLOAT_VECT2_NORM(state.h_speed_norm_f, state.ned_speed_f);
@@ -753,8 +754,9 @@ void stateCalcHorizontalSpeedNorm_i(void) {
state.h_speed_norm_i = SPEED_BFP_OF_REAL(state.h_speed_norm_f);
}
else if (bit_is_set(state.speed_status, SPEED_ENU_I)) {
/// @todo consider INT32_SPEED_FRAC
INT32_VECT2_NORM(state.h_speed_norm_i, state.enu_speed_i);
int32_t n2 = (state.enu_speed_i.x*state.enu_speed_i.x +
state.enu_speed_i.y*state.enu_speed_i.y) >> INT32_SPEED_FRAC;
INT32_SQRT(state.h_speed_norm_i, n2);
}
else if (bit_is_set(state.speed_status, SPEED_ENU_F)) {
FLOAT_VECT2_NORM(state.h_speed_norm_f, state.enu_speed_f);
@@ -763,9 +765,11 @@ void stateCalcHorizontalSpeedNorm_i(void) {
}
else if (bit_is_set(state.speed_status, SPEED_ECEF_I)) {
/* transform ecef speed to ned, set status bit, then compute norm */
//foo
/// @todo consider INT32_SPEED_FRAC
//INT32_VECT2_NORM(state.h_speed_norm_i, state.ned_speed_i);
ned_of_ecef_vect_i(&state.ned_speed_i, &state.ned_origin_i, &state.ecef_speed_i);
SetBit(state.speed_status, SPEED_NED_I);
int32_t n2 = (state.ned_speed_i.x*state.ned_speed_i.x +
state.ned_speed_i.y*state.ned_speed_i.y) >> INT32_SPEED_FRAC;
INT32_SQRT(state.h_speed_norm_i, n2);
}
else if (bit_is_set(state.speed_status, SPEED_ECEF_F)) {
ned_of_ecef_vect_f(&state.ned_speed_f, &state.ned_origin_f, &state.ecef_speed_f);
+4 -4
View File
@@ -96,10 +96,10 @@ void ahrs_align(void) {
static send_gx3(void) {
DOWNLINK_SEND_GX3_INFO(DefaultChannel, DefaultDevice,
&ahrs_impl.GX3_freq,
&ahrs_impl.GX3_packet.chksm_error,
&ahrs_impl.GX3_packet.hdr_error,
&ahrs_impl.GX3_chksm);
&ahrs_impl.gx3_freq,
&ahrs_impl.gx3_packet.chksm_error,
&ahrs_impl.gx3_packet.hdr_error,
&ahrs_impl.gx3_chksm);
}
#endif
@@ -140,6 +140,9 @@ void ins_update_gps(void) {
#if !USE_BAROMETER
float falt = gps.hmsl / 1000.;
EstimatorSetAlt(falt);
if (!alt_kalman_enabled) {
ins_alt_dot = -gps.ned_vel.z / 100.;
}
#endif
utm.alt = ins_alt;
// set position
+1 -1
View File
@@ -707,7 +707,7 @@ let create_ac = fun alert (geomap:G.widget) (acs_notebook:GPack.notebook) (ac_id
strip_connect (fun x -> dl_setting_callback id x)
with Not_found ->
if warning then
fprintf stderr "Warning: %s not setable from GCS strip (i.e. not listed in the xml settings file)" setting_name in
fprintf stderr "Warning: %s not setable from GCS strip (i.e. not listed in the xml settings file)\n" setting_name in
connect "flight_altitude" (fun f -> ac.strip#connect_shift_alt (fun x -> f (ac.target_alt+.x)));
connect "launch" ac.strip#connect_launch;
+1 -1
View File
@@ -222,7 +222,7 @@ let one_setting = fun (i:int) (do_change:int -> float -> unit) packing dl_settin
let same_tag_for_all = function
[] -> failwith "Page_settings: unreachable, empty dl_settings element"
[] -> failwith "Page_settings: unreachable, empty dl_settings element"
| x::xs ->
let tag_first = Xml.tag x in
List.iter (fun y -> assert(ExtXml.tag_is y tag_first)) xs;
@@ -9,7 +9,6 @@ import sys
sys.path.append(os.getenv("PAPARAZZI_HOME") + "/sw/lib/python")
import settings_xml_parse
DEFAULT_AC_IDS = [ 11 ] # biwhirly
def Usage(scmd):
lpathitem = scmd.split('/')
@@ -40,11 +39,10 @@ def GetOptions():
class SettingsApp(wx.App):
def OnInit(self):
options = GetOptions()
if len(options['ac_id']) > 0:
ac_ids = options['ac_id']
else:
ac_ids = DEFAULT_AC_IDS
self.main = settingsframe.create(None, ac_ids)
if not options['ac_id']:
Usage(sys.argv[0])
sys.exit("Error: Please specify at least one aircraft ID.")
self.main = settingsframe.create(None, options['ac_id'])
self.main.Show()
self.SetTopWindow(self.main)

Some files were not shown because too many files have changed in this diff Show More