mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 22:49:53 +08:00
[cleaning] drop support of LPC21 boards and related conf (#2695)
This commit is contained in:
committed by
GitHub
parent
b721c6f57b
commit
4c1785d00b
@@ -108,7 +108,7 @@ MAVLINK_PROTOCOL_H=$(MAVLINK_DIR)protocol.h
|
||||
|
||||
GEN_HEADERS = $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(XSENS_PROTOCOL_H) $(ABI_MESSAGES_H) $(MAVLINK_PROTOCOL_H)
|
||||
|
||||
all: ground_segment ext subdirs_extra lpctools
|
||||
all: ground_segment ext subdirs_extra
|
||||
|
||||
_print_building:
|
||||
@echo "------------------------------------------------------------"
|
||||
@@ -253,11 +253,6 @@ ac_h ac fbw ap: static conf generators ext
|
||||
sim: sim_static
|
||||
|
||||
|
||||
# stuff to build and upload the lpc bootloader ...
|
||||
include Makefile.lpctools
|
||||
lpctools: lpc21iap
|
||||
|
||||
|
||||
#
|
||||
# doxygen html documentation
|
||||
#
|
||||
@@ -350,6 +345,6 @@ test_sim: all
|
||||
|
||||
.PHONY: all print_build_version _print_building _save_build_version update_google_version init dox ground_segment ground_segment.opt \
|
||||
subdirs $(SUBDIRS) conf ext libpprz libpprzlink.update libpprzlink.install cockpit cockpit.opt tmtc tmtc.opt generators\
|
||||
static sim_static lpctools opencv_bebop\
|
||||
static sim_static opencv_bebop\
|
||||
clean cleanspaces ab_clean dist_clean distclean dist_clean_irreversible \
|
||||
test test_examples test_math test_sim test_all_confs
|
||||
|
||||
@@ -1,31 +0,0 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
|
||||
bl:
|
||||
cd $(AIRBORNE)/arch/lpc21/test/bootloader; $(MAKE) clean; $(MAKE)
|
||||
|
||||
BOOTLOADER_DEV ?= /dev/ttyUSB0
|
||||
upload_bl bl.upload: bl
|
||||
lpc21isp -control $(AIRBORNE)/arch/lpc21/test/bootloader/bl.hex $(BOOTLOADER_DEV) 38400 12000
|
||||
|
||||
JTAG_INTERFACE ?= olimex-jtag-tiny.cfg
|
||||
#JTAG_INTERFACE = olimex-arm-usb-ocd.cfg
|
||||
|
||||
upload_jtag: bl
|
||||
openocd -f interface/$(JTAG_INTERFACE) -f board/olimex_lpc_h2148.cfg -c init -c halt -c "flash write_image erase $(AIRBORNE)/arch/lpc21/test/bootloader/bl.hex" -c reset -c shutdown
|
||||
|
||||
|
||||
lpc21iap:
|
||||
$(MAKE) -C sw/ground_segment/lpc21iap
|
||||
|
||||
upgrade_bl bl.upgrade: bl lpc21iap
|
||||
$(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap $(AIRBORNE)/arch/lpc21/test/bootloader/bl_ram.elf
|
||||
$(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap $(AIRBORNE)/arch/lpc21/test/bootloader/bl.elf
|
||||
|
||||
ms:
|
||||
$(MAKE) -C $(AIRBORNE)/arch/lpc21/lpcusb
|
||||
$(MAKE) -C $(AIRBORNE)/arch/lpc21/lpcusb/examples
|
||||
|
||||
upload_ms ms.upload: ms
|
||||
$(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap $(AIRBORNE)/arch/lpc21/lpcusb/examples/msc.elf
|
||||
|
||||
.PHONY: bl upload_bl upload_jtag ms upload_ms lpc21iap upgrade_bl
|
||||
@@ -1,290 +0,0 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# Copyright (C) 2003-2005 Pascal Brisset, Antoine Drouin
|
||||
#
|
||||
# This file is part of paparazzi.
|
||||
#
|
||||
# paparazzi is free software; you can redistribute it and/or modify
|
||||
# it under the terms of the GNU General Public License as published by
|
||||
# the Free Software Foundation; either version 2, or (at your option)
|
||||
# any later version.
|
||||
#
|
||||
# paparazzi is distributed in the hope that it will be useful,
|
||||
# but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
# GNU General Public License for more details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License
|
||||
# along with paparazzi; see the file COPYING. If not, write to
|
||||
# the Free Software Foundation, 59 Temple Place - Suite 330,
|
||||
# Boston, MA 02111-1307, USA.
|
||||
#
|
||||
|
||||
|
||||
#
|
||||
# This is the common Makefile for the arm7-target.
|
||||
#
|
||||
|
||||
#TODO: this is not needed in some cases (e.g. ap target as it is defined there already)
|
||||
# but it is needed for other targets like tunnel
|
||||
# only define here or elsewhere?
|
||||
SRC_ARCH = arch/lpc21
|
||||
|
||||
# Launch with "make Q=''" to get full command display
|
||||
Q=@
|
||||
|
||||
|
||||
#
|
||||
# find compiler toolchain
|
||||
#
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-embedded-toolchain
|
||||
|
||||
#
|
||||
# if the new arm-none-eabi multilib compiler was not found try the old arm-elf one
|
||||
#
|
||||
ifeq ($(CC),)
|
||||
CC = $(shell which arm-elf-gcc)
|
||||
LD = $(shell which arm-elf-gcc)
|
||||
CP = $(shell which arm-elf-objcopy)
|
||||
DMP = $(shell which arm-elf-objdump)
|
||||
NM = $(shell which arm-elf-nm)
|
||||
SIZE = $(shell which arm-elf-size)
|
||||
endif
|
||||
|
||||
|
||||
# MCU name and submodel
|
||||
MCU = arm7tdmi
|
||||
THUMB = -mthumb
|
||||
THUMB_IW = -mthumb-interwork
|
||||
|
||||
# Output format. (can be srec, ihex, binary)
|
||||
FORMAT = ihex
|
||||
|
||||
#FLASH_MODE=ISP
|
||||
|
||||
SRCARM = $($(TARGET).srcs)
|
||||
|
||||
ASRCARM = crt0.S
|
||||
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# 0 = turn off optimization. s = optimize for size.
|
||||
OPT ?= s
|
||||
# Slightly bigger .elf files but gains the ability to decode macros
|
||||
DEBUG_FLAGS ?= -ggdb3
|
||||
|
||||
CSTANDARD = -std=gnu99
|
||||
|
||||
CINCS = $(INCLUDES) -I$(SRC_ARCH)/include
|
||||
|
||||
# Compiler flags.
|
||||
CFLAGS = $(CINCS)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += $(DEBUG_FLAGS)
|
||||
|
||||
# CFLAGS += -malignment-traps
|
||||
CFLAGS += -Wa,-adhlns=$(OBJDIR)/$(notdir $(subst $(suffix $<),.lst,$<))
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
CFLAGS += -ffunction-sections -fdata-sections
|
||||
CFLAGS += -finline-limit=1200 --param inline-unit-growth=100
|
||||
|
||||
# flags for warnings
|
||||
CFLAGS += -Wall -Wextra -Wunused
|
||||
CFLAGS += -Wcast-qual
|
||||
CFLAGS += -Wcast-align
|
||||
CFLAGS += -Wpointer-arith
|
||||
CFLAGS += -Wswitch-default
|
||||
CFLAGS += -Wredundant-decls -Wmissing-declarations
|
||||
CFLAGS += -Wstrict-prototypes -Wmissing-prototypes
|
||||
CFLAGS += -Wshadow
|
||||
CFLAGS += -Wnested-externs
|
||||
|
||||
CFLAGS += $(CSTANDARD)
|
||||
CFLAGS += $($(TARGET).CFLAGS) $(USER_CFLAGS) $(BOARD_CFLAGS)
|
||||
# on old lpc, avoid using double precision in some geodetic functions
|
||||
CFLAGS += -DUSE_SINGLE_PRECISION_LLA_ECEF
|
||||
|
||||
# LPC21 doesn't support unaligned data access
|
||||
CFLAGS += -DPPRZLINK_UNALIGNED_ACCESS=0
|
||||
|
||||
# Assembler flags.
|
||||
ASFLAGS = -Wa,-adhlns=$(OBJDIR)/$(notdir $(<:.S=.lst))
|
||||
|
||||
#Additional libraries.
|
||||
MATH_LIB = -lm
|
||||
|
||||
# Linker flags.
|
||||
LDFLAGS = -n -nostartfiles -Wl,-Map=$(OBJDIR)/$(TARGET).map,--cref
|
||||
LDFLAGS += -lc
|
||||
LDFLAGS += $(MATH_LIB)
|
||||
LDFLAGS += -lc -lgcc
|
||||
LDFLAGS += $(CPLUSPLUS_LIB)
|
||||
LDFLAGS += -Wl,--gc-sections
|
||||
LDFLAGS += $(BOARD_LDFLAGS)
|
||||
|
||||
ifndef LDSCRIPT
|
||||
ifeq ($(FLASH_MODE),ISP)
|
||||
LDSCRIPT = $(SRC_ARCH)/LPC2148-ROM.ld
|
||||
else
|
||||
LDSCRIPT = $(SRC_ARCH)/LPC2148-ROM-bl.ld
|
||||
endif
|
||||
endif
|
||||
LDFLAGS +=-T$(LDSCRIPT)
|
||||
|
||||
|
||||
|
||||
# ---------------------------------------------------------------------------
|
||||
# Flash-Programming support using lpc21isp by Martin Maurer
|
||||
|
||||
# Settings and variables:
|
||||
LPC21ISP = lpc21isp
|
||||
LPC21ISP_PORT ?= /dev/ttyS0
|
||||
LPC21ISP_FLASHFILE = $(OBJDIR)/$(TARGET).hex
|
||||
# verbose output:
|
||||
#LPC21ISP_DEBUG = -debug
|
||||
# enter bootloader via RS232 DTR/RTS (only if hardware supports this
|
||||
# feature - see Philips AppNote):
|
||||
ifndef LPC21ISP_CONTROL
|
||||
LPC21ISP_CONTROL =
|
||||
# -control
|
||||
endif
|
||||
|
||||
# ---------------------------------------------------------------------------
|
||||
# Flash-Programming support using lpc21iap by Martin Muller (usb bootloader)
|
||||
|
||||
LPC21IAP = $(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap
|
||||
|
||||
# ---------------------------------------------------------------------------
|
||||
# Flash-Programming support using openocd
|
||||
OOCD ?= openocd
|
||||
OOCD_INTERFACE = ftdi/olimex-arm-usb-ocd
|
||||
OOCD_TARGET = csc
|
||||
|
||||
|
||||
# Define all object files.
|
||||
COBJ = $(SRC:%.c=$(OBJDIR)/%.o)
|
||||
AOBJ = $(ASRC:%.S=$(OBJDIR)/%.o)
|
||||
COBJARM = $(SRCARM:%.c=$(OBJDIR)/%.o)
|
||||
AOBJARM = $(ASRCARM:%.S=$(OBJDIR)/%.o)
|
||||
|
||||
# Define all listing files.
|
||||
LST = $(ASRC:.S=.lst) $(ASRCARM:.S=.lst) $(SRC:.c=.lst) $(SRCARM:.c=.lst)
|
||||
|
||||
# Compiler flags to generate dependency files.
|
||||
GENDEPFLAGS = -MD -MP -MF .dep/$(@F).d
|
||||
|
||||
# Combine all necessary flags and optional flags.
|
||||
# Add target processor to flags.
|
||||
ALL_CFLAGS = -mcpu=$(MCU) $(THUMB_IW) -I. $(CFLAGS)
|
||||
ALL_ASFLAGS = -mcpu=$(MCU) $(THUMB_IW) -I. -x assembler-with-cpp $(ASFLAGS)
|
||||
|
||||
# some common informative targets
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-embedded-common
|
||||
|
||||
# Default target.
|
||||
all: printcommands sizebefore build sizeafter
|
||||
|
||||
# depend order only for parallel make
|
||||
sizebefore: | printcommands
|
||||
build: | printcommands sizebefore
|
||||
sizeafter: | build
|
||||
|
||||
build: $(OBJDIR) elf hex lss sym
|
||||
|
||||
$(OBJDIR):
|
||||
@echo CREATING object dir $(OBJDIR)
|
||||
@test -d $(OBJDIR) || mkdir -p $(OBJDIR)
|
||||
|
||||
elf: $(OBJDIR)/$(TARGET).elf
|
||||
hex: $(OBJDIR)/$(TARGET).hex
|
||||
lss: $(OBJDIR)/$(TARGET).lss
|
||||
sym: $(OBJDIR)/$(TARGET).sym
|
||||
|
||||
|
||||
# Program the device.
|
||||
upload program: $(OBJDIR)/$(TARGET).hex
|
||||
ifeq ($(FLASH_MODE),IAP)
|
||||
$(SUDO) $(LPC21IAP) $(OBJDIR)/$(TARGET).elf
|
||||
else ifeq ($(FLASH_MODE),JTAG)
|
||||
@echo "Using OOCD = $(OOCD)"
|
||||
@echo -e " OOCD\t$<"
|
||||
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
|
||||
-f board/$(OOCD_TARGET).cfg \
|
||||
-c init \
|
||||
-c "reset halt" \
|
||||
-c "flash write_image erase $(OBJDIR)/$(TARGET).bin 0x08000000" \
|
||||
-c reset \
|
||||
-c shutdown
|
||||
else
|
||||
@echo
|
||||
$(LPC21ISP) $(LPC21ISP_CONTROL) $(LPC21ISP_DEBUG) $(LPC21ISP_FLASHFILE) $(LPC21ISP_PORT) $(LPC21ISP_BAUD) $(LPC21ISP_XTAL)
|
||||
endif
|
||||
|
||||
# Create final output files (.hex, .eep) from ELF output file.
|
||||
# TODO: handling the .eeprom-section should be redundant
|
||||
%.hex: %.elf
|
||||
@echo OBJC $@
|
||||
$(Q)$(CP) -O $(FORMAT) $< $@
|
||||
|
||||
|
||||
# Create extended listing file from ELF output file.
|
||||
# testing: option -C
|
||||
%.lss: %.elf
|
||||
@echo OBJD $@
|
||||
$(Q)$(DMP) -h -S -C $< > $@
|
||||
|
||||
|
||||
# Create a symbol table from ELF output file.
|
||||
%.sym: %.elf
|
||||
@echo NM $@
|
||||
$(Q)$(NM) -n $< > $@
|
||||
|
||||
|
||||
# Link: create ELF output file from object files.
|
||||
.SECONDARY : $(OBJDIR)/$(TARGET).elf
|
||||
.PRECIOUS : $(AOBJARM) $(AOBJ) $(COBJARM) $(COBJ)
|
||||
%.elf: $(AOBJARM) $(AOBJ) $(COBJARM) $(COBJ)
|
||||
@echo LD $@
|
||||
$(Q)$(CC) $(THUMB) $(ALL_CFLAGS) $(AOBJARM) $(AOBJ) $(COBJARM) $(COBJ) --output $@ $(LDFLAGS) $($(TARGET).LDFLAGS)
|
||||
|
||||
|
||||
# Compile: create object files from C source files. ARM-only
|
||||
$(OBJDIR)/%.o : %.c $(OBJDIR)/../Makefile.ac
|
||||
@echo CC $@
|
||||
$(Q)test -d $(dir $@) || mkdir -p $(dir $@)
|
||||
$(Q)$(CC) -MMD -c $(ALL_CFLAGS) $(CONLYFLAGS) $< -o $@
|
||||
|
||||
$(OBJDIR)/%.o : $(SRC_ARCH)/lpcusb/%.c $(OBJDIR)/../Makefile.ac
|
||||
@echo CC $@
|
||||
$(Q)$(CC) -MMD -c $(ALL_CFLAGS) $(CONLYFLAGS) $< -o $@
|
||||
|
||||
|
||||
# grab files in var/aircrafts/$(AIRCRAFT)/$(TARGET) aka $(OBJDIR)
|
||||
#$(OBJDIR)/%.o : $(OBJDIR)/%.c
|
||||
# @echo CC $@
|
||||
# $(Q)$(CC) -c $(ALL_CFLAGS) $(CONLYFLAGS) $< -o $@
|
||||
|
||||
# Assemble: create object files from assembler source files. ARM/Thumb
|
||||
$(AOBJ) : $(OBJDIR)/%.o : %.S
|
||||
@echo AS $@
|
||||
$(Q)$(CC) -c $(THUMB) $(ALL_ASFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Assemble: create object files from assembler source files. ARM-only
|
||||
$(AOBJARM) : $(OBJDIR)/%.o : $(SRC_ARCH)/%.S
|
||||
@echo AS $@
|
||||
$(Q)$(CC) -c $(ALL_ASFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all build elf hex lss sym upload program
|
||||
|
||||
|
||||
#
|
||||
# Dependencies
|
||||
#
|
||||
|
||||
DEPS = $(addprefix $(OBJDIR)/,$($(TARGET).srcs:.c=.d))
|
||||
|
||||
ifneq ($(MAKECMDGOALS),clean)
|
||||
-include $(DEPS)
|
||||
endif
|
||||
@@ -76,17 +76,6 @@
|
||||
settings_modules="modules/guidance_indi.xml modules/stabilization_indi.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/air_data.xml modules/imu_common.xml modules/airspeed_ms45xx_i2c.xml"
|
||||
gui_color="#ffff7f7f0000"
|
||||
/>
|
||||
<aircraft
|
||||
name="G1"
|
||||
ac_id="9"
|
||||
airframe="airframes/ENAC/quadrotor/booz2_g1.xml"
|
||||
radio="radios/cockpitSX.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/rotorcraft_cam.xml modules/switch_servo.xml modules/ins_extended.xml modules/ahrs_int_cmpl_euler.xml modules/stabilization_int_euler.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="JP"
|
||||
ac_id="12"
|
||||
@@ -153,15 +142,4 @@
|
||||
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/ahrs_float_dcm.xml modules/air_data.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="WEASEL"
|
||||
ac_id="19"
|
||||
airframe="airframes/ENAC/fixed-wing/weasel.xml"
|
||||
radio="radios/R617FS_5ch_neg.xml"
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/gps.xml modules/nav_basic_fw.xml modules/guidance_full_pid_fw.xml modules/stabilization_adaptive_fw.xml modules/ahrs_float_dcm.xml modules/imu_common.xml"
|
||||
gui_color="#f08d1ff61ff6"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
@@ -1,8 +1,6 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!-- Funjet Multiplex (http://www.multiplex-rc.de/)
|
||||
Umarim Lite
|
||||
Radiotronix modem
|
||||
UBX GPS
|
||||
Airspeed sensor
|
||||
Digital camera
|
||||
|
||||
@@ -1,188 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Eternity 1
|
||||
designed by Murat Bronz
|
||||
Umarim-Lite
|
||||
Radiotronix modem
|
||||
LEA 6H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Eternity 1">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="umarim_lite_2.0"/>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="USE_I2C0"/>
|
||||
<define name="USE_I2C1"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="imu" type="umarim"/>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="control"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="current_sensor">
|
||||
<configure name="ADC_CURRENT_SENSOR" value="ADC_0"/>
|
||||
</module>
|
||||
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="5" min="1100" neutral="1100" max="1900"/>
|
||||
<servo name="ELEVATOR" no="0" min="1200" neutral="1430" max="1800"/>
|
||||
<servo name="RUDDER" no="1" min="1200" neutral="1619" max="2000"/>
|
||||
<servo name="AILERON_RIGHT" no="3" max="1800" neutral="1521" min="1200"/>
|
||||
<servo name="AILERON_LEFT" no="2" max="1800" neutral="1480" min="1200"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="MIXER">
|
||||
<define name="AILERON_DIFF" value="0.3"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="MOTOR" value="@THROTTLE"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
<let var="roll" value="@ROLL"/>
|
||||
<set servo="AILERON_LEFT" value="($roll < 0 ? 1 : AILERON_DIFF) * $roll"/>
|
||||
<set servo="AILERON_RIGHT" value="($roll < 0 ? AILERON_DIFF : 1) * $roll"/>
|
||||
<set servo="RUDDER" value="@YAW"/>
|
||||
</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_">
|
||||
<!-- Calibration Neutral -->
|
||||
<define name="GYRO_P_NEUTRAL" value="21"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="21"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="5"/>
|
||||
|
||||
<define name="GYRO_P_SENS" value="5.072800" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="5.080519" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.993218" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-1"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="-6"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-18"/>
|
||||
|
||||
<define name="ACCEL_X_SENS" value="38.8426913974" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="38.743860704" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="39.5046247859" 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.0959929972887" unit="rad"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="rad"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-156)*18.2"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="MAXIMUM_AIRSPEED" value="19." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.06"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
|
||||
<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="-1200"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.116999998689" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.0109999999404"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.119000002742"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.082999996841"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<!--define name="AUTO_PITCH_PGAIN" value="-0.06"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/-->
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.878000020981"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.60" unit="radians"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="11359.2226562"/>
|
||||
<define name="ROLL_RATE_GAIN" value="2000."/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="9587.37890625"/>
|
||||
<define name="PITCH_DGAIN" value="0.4"/>
|
||||
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.35"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="100" unit="m"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,223 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!-- Fire Storm
|
||||
Umarim
|
||||
Radiotronix modem
|
||||
-->
|
||||
|
||||
<airframe name="FireStorm">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
<!--define name="PITCH_TRIM"/-->
|
||||
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="umarim_1.0">
|
||||
<configure name="FLASH_MODE" value="IAP"/>
|
||||
<define name="USE_I2C0"/>
|
||||
<define name="USE_I2C1"/>
|
||||
</target>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_BAUD" value="B57600"/>
|
||||
</module>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<module name="imu" type="umarim"/>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="control" type="adaptive"/>
|
||||
<module name="navigation"/>
|
||||
<module name="nav" type="poles"/>
|
||||
<!-- Sensors -->
|
||||
<module name="gps" type="ublox"/>
|
||||
|
||||
<module name="current_sensor">
|
||||
<configure name="ADC_CURRENT_SENSOR" value="ADC_0"/>
|
||||
</module>
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="2" min="1250" neutral="1250" max="1800"/>
|
||||
<servo name="AILEVON_LEFT" no="0" min="1850" neutral="1370" max="1000"/>
|
||||
<servo name="AILEVON_RIGHT" no="1" min="1000" neutral="1515" max="1870"/>
|
||||
</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"/>
|
||||
<define name="AILERON_DIFF" value="0.5"/>
|
||||
</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 > 0 ? 1 : AILERON_DIFF) * $aileron"/>
|
||||
<set servo="AILEVON_RIGHT" value="$elevator - ($aileron > 0 ? AILERON_DIFF : 1) * $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="-53"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="33"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="-16"/>
|
||||
|
||||
<!-- SENS ITG3200 1/14.375 (deg/s)/LSB, rate frac 12bit => 1/14.375 * pi / 180 * 2^12 -->
|
||||
<define name="GYRO_P_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.97312" 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="-2"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="1"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-43"/>
|
||||
|
||||
<define name="ACCEL_X_SENS" value="38.9923420841" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="39.2011913001" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="39.4148057033" integer="16"/>
|
||||
|
||||
<!-- Just to compile -->
|
||||
<define name="MAG_X_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<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.0640000030398" unit="rad"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0.0670000016689" unit="rad"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="2000"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-162)*17.4"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="MINIMUM_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="16." unit="m/s"/>
|
||||
<define name="MAXIMUM_AIRSPEED" value="24." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
|
||||
<define name="TELEMETRY_MODE_AP" value="1"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
|
||||
<!-- define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/ -->
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.04"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.80"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-2500"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.05" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.007"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.067"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.11"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.05"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.075"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.5"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.9"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.805000007153" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="14255.3193359"/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="2000."/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="2600"/>
|
||||
<define name="ROLL_RATE_GAIN" value="850"/>
|
||||
|
||||
<define name="ROLL_KFF" value="-500"/>
|
||||
<define name="ROLL_IGAIN" value="00"/>
|
||||
<define name="PITCH_IGAIN" value="500"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.75"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.20"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.15"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
|
||||
<!--section name="GYRO_GAINS">
|
||||
<define name="GYRO_MAX_RATE" value="200."/>
|
||||
<define name="ROLLRATESUM_NB_SAMPLES" value="64"/>
|
||||
<define name="ALT_ROLL__PGAIN" value="1.0"/>
|
||||
<define name="ROLL_RATE_PGAIN" value="1000.0"/>
|
||||
<define name="ROLL_RATE_IGAIN" value="0.0"/>
|
||||
<define name="ROLL_RATE_DGAIN" value="0.0"/>
|
||||
</section-->
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="1" 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>
|
||||
|
||||
</airframe>
|
||||
@@ -1,228 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!-- Twinjet Multiplex (http://www.multiplex-rc.de/)
|
||||
Tiny 2.12 board (http://wiki.paparazziuav.org/wiki/index.php/Tiny_v2)
|
||||
MPU9250 Drotek Breakout Board
|
||||
-->
|
||||
|
||||
<airframe name="Black Cat">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<define name="PITCH_TRIM"/>
|
||||
|
||||
<target name="ap" board="tiny_2.11"/>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="xbee_api"/>
|
||||
<module name="control" type="adaptive"/>
|
||||
<module name="imu" type="mpu9250_i2c">
|
||||
<configure name="IMU_MPU9250_I2C_DEV" value="i2c0"/>
|
||||
</module>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="light"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="tiny_2.11"/>
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR_LEFT" no="3" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="MOTOR_RIGHT" no="4" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="6" min="1900" neutral="1515" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="7" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="MIXER">
|
||||
<define name="AILEVON_AILERON_RATE" value="0.75"/>
|
||||
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
|
||||
<define name="MOTOR_YAW_RATE" value="0.0"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
|
||||
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
|
||||
<let var="yaw" value="@YAW * MOTOR_YAW_RATE"/>
|
||||
<set servo="MOTOR_LEFT" value="@THROTTLE - $yaw"/>
|
||||
<set servo="MOTOR_RIGHT" value="@THROTTLE + $yaw"/>
|
||||
<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_">
|
||||
<!-- Calibration Neutral -->
|
||||
<define name="GYRO_P_SIGN" value="1"/>
|
||||
<define name="GYRO_Q_SIGN" value="-1"/>
|
||||
<define name="GYRO_R_SIGN" value="-1"/>
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
|
||||
<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="109"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="13"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-404"/>
|
||||
<define name="ACCEL_X_SENS" value="2.45045342816" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="2.44747844234" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="2.42689216106" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<!--section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="1."/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1."/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.25"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR1_SIGN" value="-1"/>
|
||||
<define name="IR2_SIGN" value="1"/>
|
||||
<define name="TOP_SIGN" value="1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="-1.146" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0.15" unit="deg"/>
|
||||
|
||||
<define name="I2C_DEFAULT_CONF" value="1"/>
|
||||
</section-->
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8600"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="MAXIMUM_AIRSPEED" value="20." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<!-- <define name="XBEE_INIT" value="ATPL2\rATRN1\rATTT80\r" type="string"/> -->
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
<define name="LIGHT_LED_NAV" value="3"/>
|
||||
<define name="LIGHT_LED_STROBE" value="4"/>
|
||||
<define name="USE_LED_4" value="1"/> <!-- CAM_SWITCH is a gpio not a led -->
|
||||
<define name="LED_4_BANK" value="1"/>
|
||||
<define name="LED_4_PIN" value="22"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.0450000017881"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.319999992847"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.80"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.07" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.027"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.14"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.035000000149"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.01"/>
|
||||
<define name="AUTO_PITCH_DGAIN" value="0"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
<define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.15"/>
|
||||
|
||||
<!-- pitch trim -->
|
||||
<define name="PITCH_LOITER_TRIM" value="RadOfDeg(5.)"/>
|
||||
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-5.)"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.3"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.995000004768"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.715585" 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="7276"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1284"/>
|
||||
<define name="ROLL_IGAIN" value="500"/>
|
||||
<define name="ROLL_KFFA" value="500"/>
|
||||
<define name="ROLL_KFFD" value="500"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="11187"/>
|
||||
<define name="PITCH_DGAIN" value="0."/>
|
||||
<define name="PITCH_IGAIN" value="500"/>
|
||||
<define name="PITCH_KFFA" value="0."/>
|
||||
<define name="PITCH_KFFD" value="0."/>
|
||||
|
||||
<!--define name="ELEVATOR_OF_ROLL" value="1541."/-->
|
||||
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.2)"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.7"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.25"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.15"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="1" 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="1."/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,232 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!-- Weasel by Murat
|
||||
Umarim
|
||||
XBee modem
|
||||
LEA 5H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Weasel">
|
||||
|
||||
<!--autopilot name="fixedwing_autopilot.xml"/-->
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<define name="USE_I2C0"/>
|
||||
<define name="USE_I2C1"/>
|
||||
<!--define name="AGR_CLIMB"/-->
|
||||
<!--define name="USE_AIRSPEED"/-->
|
||||
<!--define name="USE_BAROMETER"/-->
|
||||
<!--define name="LOITER_TRIM"/-->
|
||||
<!--define name="PITCH_TRIM"/-->
|
||||
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="umarim_1.0"/>
|
||||
|
||||
<module name="radio_control" type="ppm">
|
||||
<define name="USE_PPM_RSSI_GPIO"/>
|
||||
<define name="PPM_RSSI_IOPIN" value="IO0PIN"/>
|
||||
<define name="PPM_RSSI_PIN" value="17"/>
|
||||
<define name="PPM_RSSI_VALID_LEVEL" value="0"/>
|
||||
</module>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="xbee_api"/>
|
||||
|
||||
<!--module name="airspeed" type="ads1114"/-->
|
||||
<!--module name="mcp355x"/-->
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<module name="imu" type="umarim"/>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="control" type="new"/>
|
||||
<module name="navigation"/>
|
||||
<!-- Sensors -->
|
||||
<module name="gps" type="ublox"/>
|
||||
|
||||
<!--module name="spi"/-->
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="7" min="1040" neutral="1040" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="6" min="1750" neutral="1543" max="1250"/>
|
||||
<servo name="AILEVON_RIGHT" no="3" min="1250" neutral="1561" max="1750"/>
|
||||
</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="45" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="30" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- Calibration Neutral -->
|
||||
<define name="GYRO_P_NEUTRAL" value="-15"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="94"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="-7"/>
|
||||
|
||||
<!-- SENS ITG3200 1/14.375 (deg/s)/LSB, rate frac 12bit => 1/14.375 * pi / 180 * 2^12 -->
|
||||
<define name="GYRO_P_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.97312" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<!-- SENS ADXL345 16G 31.2 mg/LSB, accel frac 10bit => 31.2 * 2^10 / 1000 -->
|
||||
<define name="ACCEL_X_SENS" value="31.9488" integer="10"/>
|
||||
<define name="ACCEL_Y_SENS" value="31.9488" integer="10"/>
|
||||
<define name="ACCEL_Z_SENS" value="31.9488" integer="10"/>
|
||||
|
||||
<!-- Just to compile -->
|
||||
<define name="MAG_X_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<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="3." unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</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="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<!--define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/-->
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.159999996424"/> <!-- -0.024 -->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="5." unit="m/s"/>
|
||||
|
||||
<!-- Cruise throttle + limits -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="20." unit="deg"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-20." unit="deg"/>
|
||||
|
||||
<!-- Climb loop (throttle) -->
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.003"/> <!-- -0.005 -->
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0.007"/> <!-- 0.005 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.002"/> <!-- 0.005 -->
|
||||
|
||||
<!-- Climb loop (pitch) -->
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.02"/>
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.006"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_DGAIN" value="0.0"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.002"/>
|
||||
|
||||
<!-- 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" unit="m/s"/>
|
||||
<define name="AIRSPEED_MIN" value="10" unit="m/s"/>
|
||||
|
||||
<!-- groundspeed control -->
|
||||
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15" unit="m/s"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
|
||||
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
|
||||
|
||||
<!-- pitch trim --> <!-- 5 deg -->
|
||||
<define name="PITCH_LOITER_TRIM" value="RadOfDeg(0.)"/>
|
||||
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-0.)"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.7"/>
|
||||
<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="3800."/>
|
||||
<define name="ROLL_RATE_GAIN" value="500."/>
|
||||
<define name="ROLL_IGAIN" value="150."/>
|
||||
<define name="ROLL_KFFA" value="0"/>
|
||||
<define name="ROLL_KFFD" value="0"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="8000"/>
|
||||
<define name="PITCH_DGAIN" value="500"/>
|
||||
<define name="PITCH_IGAIN" value="250."/>
|
||||
<define name="PITCH_KFFA" value="0."/>
|
||||
<define name="PITCH_KFFD" value="0."/>
|
||||
|
||||
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.0)"/>
|
||||
<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="ROLL_RESPONSE_FACTOR" value="10"/>
|
||||
<define name="MAX_ROLL_DOT" value="20" unit="rad/s"/-->
|
||||
<define name="JSBSIM_MODEL" value="Malolo1" type="string"/>
|
||||
<!--define name="JSBSIM_INIT" value="Malolo1-IC"/-->
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15.0"/>
|
||||
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="0." unit="deg"/>
|
||||
<define name="JSBSIM_IR_PITCH_NEUTRAL" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,249 +0,0 @@
|
||||
<airframe name="BOOZ2_G1">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<define name="DEBUG_VFF_EXTENDED"/>
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
<!--define name="GUIDANCE_H_USE_REF"/-->
|
||||
|
||||
<target name="ap" board="booz_1.0">
|
||||
<define name="FAILSAFE_GROUND_DETECT"/>
|
||||
<define name="USE_GPS_ACC4R"/>
|
||||
<define name="ACTUATORS_START_DELAY" value="3"/>
|
||||
</target>
|
||||
<!--target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
</target-->
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="actuators" type="asctec"/>
|
||||
<module name="actuators" type="pwm">
|
||||
<define name="USE_PWM0"/>
|
||||
<define name="USE_PWM1"/>
|
||||
</module>
|
||||
<module name="imu" type="b2_v1.1"/>
|
||||
<module name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</module>
|
||||
<module name="stabilization" type="int_euler"/>
|
||||
<module name="ahrs" type="int_cmpl_euler"/>
|
||||
<module name="ins" type="extended"/>
|
||||
|
||||
<module name="switch" type="servo"/>
|
||||
<module name="rotorcraft_cam"/>
|
||||
<module name="sonar_adc">
|
||||
<configure name="ADC_SONAR" value="ADC_0"/>
|
||||
<define name="USE_SONAR"/>
|
||||
<!--define name="SENSOR_SYNC_SEND_SONAR"/-->
|
||||
</module>
|
||||
<!--module name="baro_mpl3115">
|
||||
<configure name="MPL3115_I2C_DEV" value="i2c1"/>
|
||||
<define name="SENSOR_SYNC_SEND"/>
|
||||
</module-->
|
||||
<!--module name="mavlink_decoder">
|
||||
<configure name="MAVLINK_PORT" value="UART0"/>
|
||||
<configure name="MAVLINK_BAUD" value="B115200"/>
|
||||
</module>
|
||||
<module name="px4flow"/-->
|
||||
<!--module name="adc_generic">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_0"/>
|
||||
</module-->
|
||||
<!--module name="sys_mon"/-->
|
||||
</firmware>
|
||||
|
||||
<servos driver="Asctec">
|
||||
<servo name="PITCH" no="0" min="-100" neutral="0" max="100"/>
|
||||
<servo name="ROLL" no="1" min="-100" neutral="0" max="100"/>
|
||||
<servo name="YAW" no="2" min="-100" neutral="0" max="100"/>
|
||||
<servo name="THRUST" no="3" min="0" neutral="0" max="200"/>
|
||||
</servos>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="SWITCH" no="0" min="1060" neutral="1500" max="2120"/>
|
||||
<servo name="CAM" no="1" min="1000" neutral="1500" max="2300"/>
|
||||
</servos>
|
||||
|
||||
<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>
|
||||
|
||||
<section name="TRIM">
|
||||
<define name="TRIM_ROLL" value="0"/>
|
||||
<define name="TRIM_PITCH" value="6"/>
|
||||
<define name="TRIM_YAW" value="0"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="PITCH" value="@PITCH - TRIM_PITCH"/>
|
||||
<set servo="ROLL" value="@ROLL - TRIM_ROLL"/>
|
||||
<set servo="YAW" value="@YAW - TRIM_YAW"/>
|
||||
<set servo="THRUST" value="@THRUST"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<define name="GYRO_P_NEUTRAL" value="32238"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="32391"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="32853"/>
|
||||
|
||||
<define name="GYRO_P_SENS" value="1.00" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="1.00" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="1.00" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="32508"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="32565"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="32147"/>
|
||||
|
||||
<define name="ACCEL_X_SENS" value="2.56787679957" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="2.55480391706" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="2.57076132924" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="19"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-91"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="-40"/>
|
||||
|
||||
<define name="MAG_X_SENS" value="4.93239693731" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.91905188125" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.3560174578" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="1.3" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="-2.6" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.85"/>
|
||||
<define name="REF_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="6000"/>
|
||||
<define name="PHI_DGAIN" value="800"/>
|
||||
<define name="PHI_IGAIN" value="500"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="6000"/>
|
||||
<define name="THETA_DGAIN" value="800"/>
|
||||
<define name="THETA_IGAIN" value="500"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="3000"/>
|
||||
<define name="PSI_DGAIN" value="600"/>
|
||||
<define name="PSI_IGAIN" value="100"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value=" 300"/>
|
||||
<define name="THETA_DDGAIN" value=" 300"/>
|
||||
<define name="PSI_DDGAIN" value=" 300"/>
|
||||
|
||||
<define name="PHI_AGAIN" value="0"/>
|
||||
<define name="THETA_AGAIN" value="0"/>
|
||||
<define name="PSI_AGAIN" value="0"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="SONAR_MAX_RANGE" value="5.0"/>
|
||||
<define name="SONAR_MIN_RANGE" value="0.25"/>
|
||||
</section>
|
||||
|
||||
<section name="SONAR">
|
||||
<!--define name="SONAR_SCALE" value="0.00650498" integer="16"/--> <!-- XL-MaxSonar-EZ4 5V supply -->
|
||||
<define name="SONAR_SCALE" value="0.016775" integer="16"/> <!-- XL-MaxSonar-EZ4 5V supply scaled to 3.3V -->
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="REF_MIN_ZDD" value="-0.8*9.81"/>
|
||||
<define name="REF_MAX_ZDD" value=" 0.5*9.81"/>
|
||||
<define name="REF_MIN_ZD" value="-1.5"/>
|
||||
<define name="REF_MAX_ZD" value=" 1.5"/>
|
||||
<define name="HOVER_KP" value="150"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="0"/>
|
||||
<!-- 1.5m/s for full stick : SPEED_BFP_OF_REAL(1.5) / (MAX_PPRZ/2) -->
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) * 20% -->
|
||||
</section>
|
||||
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="USE_REF" value="FALSE"/>
|
||||
<define name="MAX_BANK" value="30" unit="deg"/>
|
||||
<define name="PGAIN" value="40"/>
|
||||
<define name="DGAIN" value="70"/>
|
||||
<define name="IGAIN" value="15"/>
|
||||
<define name="NGAIN" value="0"/>
|
||||
<!-- feedforward -->
|
||||
<define name="AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
<define name="BOOZ_FMS_TIMEOUT" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="SWITCH_GPIO" value="CAM_SWITCH_GPIO"/>
|
||||
<define name="TILT_SERVO" value="CAM"/>
|
||||
<define name="TILT_ANGLE_MAX" value="-90." unit="deg"/>
|
||||
<define name="TILT_ANGLE_MIN" value=" 10." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="SWITCH_SERVO">
|
||||
<define name="SWITCH_SERVO_ON_VALUE" value="SERVO_SWITCH_MIN"/>
|
||||
<define name="SWITCH_SERVO_OFF_VALUE" value="SERVO_SWITCH_MAX"/>
|
||||
<define name="DropOpen()" value="SwitchServoOn()"/>
|
||||
<define name="DropClose()" value="SwitchServoOff()"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="BOOZ_ANALOG_BARO_THRESHOLD" value="800"/>
|
||||
<define name="FACE_REINJ_1" value="1024"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="10."/>
|
||||
<!--define name="IMU_MAG_OFFSET" value="RadOfDeg(-5.8)"/-->
|
||||
</section>
|
||||
|
||||
<section name="GCS">
|
||||
<define name="ALT_SHIFT_PLUS_PLUS" value="5"/>
|
||||
<define name="ALT_SHIFT_PLUS" value="1"/>
|
||||
<define name="ALT_SHIFT_MINUS" value="-1"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
|
||||
<!--define name="JSBSIM_INIT" value="reset_enac"/-->
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_booz2_a1.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,395 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
<!-- Graupner Taxi III electro (http://www.graupner.de/)
|
||||
TINY (http://paparazzi.enac.fr/wiki/index.php/)
|
||||
* Aligned Infrared sensor for X,Y,Z
|
||||
* Various options to connect XBee XSC 900Mhz or RFD900A or RFD868+
|
||||
* GPS uBlox LEA5H
|
||||
* 35Mhz CPPM receiver
|
||||
|
||||
Notes:
|
||||
* The two aileron servos are connected via a Y-split cable and on
|
||||
one actuator out connection on the board, no differential aileron possible :(
|
||||
-->
|
||||
|
||||
<airframe name="TaxiIII">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<target name="ap" board="tiny_2.11"/>
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="TUNE_AGRESSIVE_CLIMB"/>
|
||||
|
||||
<define name="PITCH_TRIM"/>
|
||||
|
||||
<define name="USE_I2C0"/>
|
||||
<module name="radio_control" type="ppm">
|
||||
<!-- for debugging PPM value the one below -->
|
||||
<!-- <define name="TELEMETRY_MODE_FBW" value="1"/> -->
|
||||
</module>
|
||||
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_BAUD" value="B57600"/>
|
||||
<configure name="MODEM_PORT" value="UART1"/>
|
||||
</module>
|
||||
|
||||
<module name="control"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<!-- for setting values e.g. IR tuning via RC Tranmitter -->
|
||||
<!-- <module name="settings" type="rc"/>-->
|
||||
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
|
||||
<module name="digital_cam">
|
||||
<!-- <define name="DC_SHUTTER_GPIO" value="CAM_SWITCH_GPIO"/>--><!-- Not compiling ATM -->
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO22"/>
|
||||
</module>
|
||||
<!--
|
||||
<module name="sys_mon"/>
|
||||
-->
|
||||
|
||||
<!--
|
||||
<module name="adc_generic">
|
||||
-->
|
||||
<!-- Voltage measuring sensor -->
|
||||
<!--
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_3"/>
|
||||
-->
|
||||
<!-- RPM measuring sensor -->
|
||||
<!--
|
||||
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_4"/>
|
||||
-->
|
||||
<!-- Current measuring sensor -->
|
||||
<!--
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_7"/>
|
||||
</module>
|
||||
-->
|
||||
<module name="nav" type="line"/>
|
||||
<module name="nav" type="line_border"/>
|
||||
<module name="nav" type="line_osam"/>
|
||||
<module name="nav" type="survey_polygon"/>
|
||||
<module name="nav" type="survey_poly_osam"/>
|
||||
<module name="nav" type="smooth"/>
|
||||
<module name="nav" type="vertical_raster"/>
|
||||
<module name="nav" type="flower"/>
|
||||
<module name="nav" type="bungee_takeoff"/>
|
||||
<module name="nav" type="catapult"/>
|
||||
|
||||
</modules>
|
||||
|
||||
<!-- Define here to which CONNECTOR NUMBER the servo is connected to, on the autopilot cicuit board -->
|
||||
<servos>
|
||||
<!-- Make sure esc is set to fixed endpoints, e.g.CastleCreastions range fixed is 1250ms - 1800ms -->
|
||||
<servo name="MOTOR" no="0" min="1250" neutral="1300" max="1850"/>
|
||||
<servo name="AILERON" no="2" min="1900" neutral="1500" max="1100"/>
|
||||
<servo name="ELEVATOR" no="3" min="1100" neutral="1500" max="1900"/>
|
||||
<servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<!-- commands section -->
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<!-- for tuning via RC these ones below -->
|
||||
<!--
|
||||
<axis name="GAIN1" failsafe_value="0"/>
|
||||
<axis name="CALIB" failsafe_value="0"/>
|
||||
-->
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<!-- for tuning via RC these ones below -->
|
||||
<!--
|
||||
<set command="GAIN1" value="@GAIN1"/>
|
||||
<set command="CALIB" value="@CALIB"/>
|
||||
-->
|
||||
</rc_commands>
|
||||
|
||||
<auto_rc_commands>
|
||||
<!-- To still be able to use rudder, which is needed with sidewind landing in auto1 stabilization mode only YAW -->
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<!-- for tuning via RC these ones below -->
|
||||
<!--
|
||||
<set command="GAIN1" value="@GAIN1"/>
|
||||
<set command="CALIB" value="@CALIB"/> -->
|
||||
</auto_rc_commands>
|
||||
|
||||
<!--For mixed controlflaps -->
|
||||
<section name="MIXER">
|
||||
<!-- just a tiny bit works well-->
|
||||
<define name="ASSIST_ROLL_WITH_RUDDER" value="0.09"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="MOTOR" value="@THROTTLE"/>
|
||||
<set servo="AILERON" value="@ROLL"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
<set servo="RUDDER" value="@YAW - @ROLL*ASSIST_ROLL_WITH_RUDDER"/>
|
||||
</command_laws>
|
||||
|
||||
<!-- Do not set MAX_ROLL, MAX_PITCH to small of a value, otherwise one can NOT control the plane very well manually -->
|
||||
<!-- If you have dual rate swith it of with same swtch as mode switch thus auto1 means dualrate is switched off also -->
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.95"/> <!-- radians -->
|
||||
<define name="MAX_PITCH" value="0.95"/> <!-- radians -->
|
||||
<!-- Or use as below -->
|
||||
<!-- <define name="MAX_ROLL" value="RadOfDeg(95)"/> -->
|
||||
<!-- <define name="MAX_PITCH" value="RadOfDeg(95)"/> -->
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<!-- NEUTRAL value below set via caliberation with all sensors covert and intill set to 0 the read via telemetry data and in this case 515 etc filled in later and reuploaded -->
|
||||
<!-- In this plane IR1 points to side to side, the latereal axis -->
|
||||
<!-- In this plane IR2 points to front and back, the longitudinal axis -->
|
||||
|
||||
<!--Reminder: reads X if value=0 is uploaded in airframe -->
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<!--Reminder: reads X if value=0 is uploaded in airframe -->
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<!--Reminder: reads X if value=0 is uploaded in airframe -->
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<!-- old way
|
||||
<define name="CORRECTION_UP" value="1.0"/>
|
||||
<define name="CORRECTION_DOWN" value="1.0"/>
|
||||
<define name="CORRECTION_LEFT" value="1.0"/>
|
||||
<define name="CORRECTION_RIGHT" value="1.0"/>
|
||||
-->
|
||||
|
||||
<!-- =============== possible new values ========================= -->
|
||||
<!-- <define name="DEFAULT_CONTRAST" value="200"/> -->
|
||||
<!-- <define name="RAD_OF_IR_CONTRAST" value="0.75"/> -->
|
||||
<!-- <linear name="RollOfIrs" arity="2" coeff1="0.7" coeff2="-0.7"/> -->
|
||||
<!-- <linear name="PitchOfIrs" arity="2" coeff1="0.7" coeff2="0.7"/> -->
|
||||
<!-- <linear name="TopOfIr" arity="1" coeff1="-1"/> -->
|
||||
<!-- <define name="RAD_OF_IR_MAX_VALUE" value="0.0045"/> -->
|
||||
<!-- <define name="RAD_OF_IR_MIN_VALUE" value="0.00075"/> -->
|
||||
<!-- ============== possible new values end ===================== -->
|
||||
|
||||
<!-- The three axis must give similar values for similar air to ground contrasts. -->
|
||||
<!-- If you e.g. have a different brand of IR piles for straight up n down sensors. -->
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="0.8"/> <!-- was in the past 360_LATERAL_CORRECTION -->
|
||||
<define name="LONGITUDINAL_CORRECTION" value="0.8"/> <!-- was in the past 360_LONGITUDINAL_CORRECTION -->
|
||||
<!-- One can set the top down correction a little lower so leftrightfrontback is more accurate n faster -->
|
||||
<define name="VERTICAL_CORRECTION" value="1.1"/> <!-- was in the past 360_VERTICAL_CORRECTION -->
|
||||
|
||||
<!-- ONLY enable the line below if the sensor is ALIGENED front to back, side to side. Thus not 45deg rotated, and Disable the TILTED LINE -->
|
||||
<define name="HORIZ_SENSOR_ALIGNED" value="1"/>
|
||||
<!-- ONLY enable the line below if the sensor is TILTED, and Disable the ALIGENED LINE -->
|
||||
<!-- <define name="HORIZ_SENSOR_TILTED" value="1"/> -->
|
||||
|
||||
<!-- Ground(=Hotter than sky) on right side of airframe as seen from back -->
|
||||
<!-- The Hotter side must give a positive value maybe -->
|
||||
|
||||
<!-- In this airframe IR1 points to front and side, the latereal AND longitudinal axis -->
|
||||
<define name="IR1_SIGN" value="-1"/>
|
||||
<!-- In this airframe IR2 points to front and side, the latereal AND longitudinal axis -->
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="1"/>
|
||||
|
||||
<!-- below is very important per individual airframe, first set to 0,
|
||||
then adjusted after testflight data is analyzed.
|
||||
Setting also can be adjusted realtime via tuning config
|
||||
or tuning_via?_transmitter config.
|
||||
-->
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<!-- If current-volts sensor is installed use line below-->
|
||||
<!-- <define name="ADC_CHANNEL_CURRENT" value="ADC_3" /> -->
|
||||
<!-- <define name="MilliAmpereOfAdc(adc)" value="(adc*88)"/> -->
|
||||
|
||||
<!-- <define name="ADC_CHANNEL_VOLTAGE" value="ADC_4" /> -->
|
||||
<!-- The real multiplier is unknown we take 2 as test example -->
|
||||
<!-- <define name="VoltageOfAdc(adc)" value ="(adc*2)"/> -->
|
||||
|
||||
<!-- If NO current-volts sensor installed uncomment below -->
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="18000" unit="mA"/>
|
||||
|
||||
<!--
|
||||
<define name="VOLTAGE_ADC_A" value="0.0177531"/>
|
||||
<define name="VOLTAGE_ADC_B" value="0.173626"/>
|
||||
<define name="VoltageOfAdc(adc)" value ="(VOLTAGE_ADC_A * adc + VOLTAGE_ADC_B)"/>
|
||||
-->
|
||||
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/> <!-- 3S lipo 3.1*3=9.3 -->
|
||||
<define name="CRITIC_BAT_LEVEL" value="10.0" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="10.6" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/> <!-- 3S lipo 4.2*3=12.6 -->
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="14." unit="m/s"/>
|
||||
<define name="MAXIMUM_AIRSPEED" value="20." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<!-- <define name="XBEE_INIT" value="ATPL2\rATRN1\rATTT80\r" type="string"/> -->
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
<!-- <define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>-->
|
||||
|
||||
<!--UNLOCKED_HOME_MODE if set to TRUE means that HOME mode does not get stuck.
|
||||
If not set before when you would enter home mode you had to flip a bit via the GCS to get out. -->
|
||||
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
|
||||
<!-- RC_LOST_MODE means that if your RC Transmitter signal is not received anymore in the autopilot, e.g. you switch it off
|
||||
or fly a long range mission you define the wanted mode behaviour here.
|
||||
If you do not define it, it defaults to flying to the flightplan HOME -->
|
||||
<define name="RC_LOST_MODE" value="AP_MODE_AUTO2"/>
|
||||
|
||||
<!-- OLD <define name="ALT_KALMAN_ENABLED" value="TRUE"/>-->
|
||||
<define name="TRIGGER_DELAY" value="1.0"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="70.0"/>
|
||||
<define name="MIN_CIRCLE_RADIUS" value="50.0"/><!-- needed for some nav modules like spiral-->
|
||||
|
||||
<!-- The Glide definitions are used for calculating the touch down point during auto landing -->
|
||||
<!-- <define name="GLIDE_AIRSPEED" value="11."/>
|
||||
<define name="GLIDE_VSPEED" value="1." unit="m/s"/>
|
||||
<define name="GLIDE_PITCH" value="7." unit="deg"/>-->
|
||||
</section>
|
||||
|
||||
<!-- ******************* VERTICAL CONTROL ******************************** -->
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.06"/> <!--unit="(m/s)/m"-->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2." unit="m/s"/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.85" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.65" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.99" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1000" unit="pprz_t"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-2000" unit="pprz_t"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.0007" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.002"/>
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0.0"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.2" unit="rad/(m/s)"/>
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="0.8" unit="s"/>
|
||||
|
||||
<!-- NOT YET USED auto airspeed and altitude inner loop -->
|
||||
<!-- <define name="AIRSPEED_ETS_OFFSET" value="1542"/> -->
|
||||
|
||||
<!-- NEVER set AUTO_AIRSPEED_SETPOINT lower than airframe stall speed -->
|
||||
|
||||
<!--
|
||||
<define name="AUTO_AIRSPEED_SETPOINT" value="19.0" unit="m/s"/>
|
||||
<define name="AUTO_AIRSPEED_PGAIN" value="0.1"/>
|
||||
<define name="AUTO_AIRSPEED_IGAIN" value="0.05"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0" unit="degree/(m/s)"/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0" unit="%/(m/s)"/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0"/>
|
||||
-->
|
||||
|
||||
<!-- investigate: if higher _AIRSPEED_SETPOINT then airframe tries to maintain a constand ground speed UNKNOWN -->
|
||||
|
||||
<!--
|
||||
<define name="AUTO_GROUNDSPEED_SETPOINT" value="14.0" unit="m/s"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="0.75"/>
|
||||
<define name="AUTO_GROUNDSPEED_IGAIN" value="0.25"/>
|
||||
-->
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.052"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.065"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.45"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.40"/>
|
||||
<!-- <define name="THROTTLE_SLEW" value="0.3"/> --> <!-- limiter for powerfull engines -->
|
||||
|
||||
<!-- pitch trim -->
|
||||
<!-- not used for now -->
|
||||
<!-- <define name="PITCH_LOITER_TRIM" value="RadOfDeg(5.)"/>
|
||||
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-5.)"/>-->
|
||||
|
||||
</section>
|
||||
|
||||
<!-- ******************* HORIZONTAL CONTROL ******************************** -->
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.0"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.60" 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="5900"/>
|
||||
<define name="ROLL_RATE_GAIN" value="2900"/>
|
||||
<define name="ROLL_IGAIN" value="500"/>
|
||||
<define name="ROLL_KFFA" value="500"/>
|
||||
<define name="ROLL_KFFD" value="500"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="9000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
<define name="PITCH_IGAIN" value="500"/>
|
||||
<define name="PITCH_KFFA" value="0."/>
|
||||
<define name="PITCH_KFFD" value="0."/>
|
||||
|
||||
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.2)"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<!-- <define name="NAV_PITCH" value="0."/>-->
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<!-- ***************************** AGGRESIVE ******************************* -->
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/> <!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="8"/> <!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.90"/> <!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="RadOfDeg(45)"/> <!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.4"/> <!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="RadOfDeg(-30)"/> <!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/> <!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="0.99"/>
|
||||
</section>
|
||||
|
||||
<!-- ****************************** FAILSAFE ******************************* -->
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.15" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="-0.1" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="70" unit="m"/>
|
||||
</section>
|
||||
|
||||
<!-- ****************************** DATALINK ******************************* -->
|
||||
<section name="DATALINK" prefix="DATALINK_">
|
||||
<define name="DEVICE_TYPE" value="PPRZ"/>
|
||||
<define name="DEVICE_ADDRESS" value="...."/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_PERIOD" value="3" unit="sec"/>
|
||||
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="70" unit="meter"/>
|
||||
</section>
|
||||
|
||||
<!-- ******************************** SIMU ********************************* -->
|
||||
<section name="SIMU">
|
||||
<define name="YAW_RESPONSE_FACTOR" value="0.5"/> <!-- a to low of a value gives bad simulation results -->
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -1,238 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!--
|
||||
YAPA + PPZIMU + XBee
|
||||
-->
|
||||
|
||||
<airframe name="Yapa v1">
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILERON_LEFT" no="1" min="1000" neutral="1500" max="2000"/>
|
||||
<servo name="AILERON_RIGHT" no="2" min="2000" neutral="1500" max="1000"/>
|
||||
<servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/>
|
||||
<servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="BRAKE" failsafe_value="0"/> <!-- both elerons up as butterfly brake ? -->
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="BRAKE" value="@YAW"/>
|
||||
</rc_commands>
|
||||
|
||||
<command_laws>
|
||||
<set servo="AILERON_LEFT" value="@ROLL"/>
|
||||
<set servo="AILERON_RIGHT" value="@ROLL"/>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<!-- Local magnetic field -->
|
||||
<section name="AHRS" prefix="AHRS_" >
|
||||
<define name="H_X" value="0.51562740288882" />
|
||||
<define name="H_Y" value="-0.05707735220832" />
|
||||
<define name="H_Z" value="0.85490967783446" />
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- Calibration Neutral -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
|
||||
<!-- SENS = 14.375 LSB/(deg/sec) * 57.6 deg/rad = 828 LSB/rad/sec / 12bit FRAC: 4096 / 828 -->
|
||||
<define name="GYRO_P_SENS" value="4.947" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="4.947" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.947" integer="16"/>
|
||||
|
||||
<define name="GYRO_P_Q" value="0."/>
|
||||
<define name="GYRO_P_R" value="0"/>
|
||||
<define name="GYRO_Q_P" value="0."/>
|
||||
<define name="GYRO_Q_R" value="0."/>
|
||||
<define name="GYRO_R_P" value="0."/>
|
||||
<define name="GYRO_R_Q" value="0."/>
|
||||
|
||||
<define name="GYRO_P_SIGN" value="1"/>
|
||||
<define name="GYRO_Q_SIGN" value="1"/>
|
||||
<define name="GYRO_R_SIGN" value="1"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-14"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<!-- SENS = 256 LSB/g @ 2.5V [X&Y: 265 LSB/g @ 3.3V] / 9.81 ms2/g = 26.095 LSB/ms2 / 10bit FRAC: 1024 / 26.095 for z and 1024 / 27.01 for X&Y -->
|
||||
<define name="ACCEL_X_SENS" value="37.9" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="37.9" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="39.24" 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="MAG_X_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<define name="MAG_X_SENS" value="1" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="1" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="1" 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="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="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.7"/>
|
||||
<define name="MAX_PITCH" value="0.7"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/>
|
||||
|
||||
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="XBEE_INIT" value="ATPL2\rATRN5\rATTT80\r" type="string"/>
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.20000004768"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
<define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.75" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="12000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1000."/>
|
||||
|
||||
<define name="ROLL_SLEW" value="1."/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="0."/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
|
||||
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
</section>
|
||||
|
||||
|
||||
<firmware name="fixedwing">
|
||||
|
||||
<target name="ap" board="lisa_l_1.1"> <!-- board="tiny_2.11"> -->
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
|
||||
<configure name="PERIODIC_FREQUENCY" value="120"/>
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
|
||||
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
|
||||
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP" />
|
||||
|
||||
<configure name="AHRS_ALIGNER_LED" value="3"/>
|
||||
</target>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
|
||||
<!-- Sensors -->
|
||||
<!--
|
||||
<module name="ahrs" type="int_cmpl_quat">
|
||||
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" />
|
||||
</module>
|
||||
<module name="imu" type="aspirin_i2c"/>
|
||||
-->
|
||||
<module name="imu" type="pprzuav"/>
|
||||
<module name="ahrs" type="float_dcm">
|
||||
<!-- <configure name="USE_MAGNETOMETER" /> -->
|
||||
</module>
|
||||
<module name="ins" type="alt_float"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="xbee_api">
|
||||
<configure name="MODEM_BAUD" value="B9600"/>
|
||||
</module>
|
||||
|
||||
<!-- Actuators -->
|
||||
<module name="control"/>
|
||||
<!-- Sensors -->
|
||||
<module name="navigation"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
|
||||
|
||||
</firmware>
|
||||
|
||||
|
||||
</airframe>
|
||||
@@ -1,264 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
<!--
|
||||
Tobias Muench 2012
|
||||
|
||||
example airframe for energyadaptive ctl
|
||||
aircraft:
|
||||
Twinstar II
|
||||
hardware:
|
||||
twog_1.0 + aspirin + ETS baro + ETS speed
|
||||
-->
|
||||
|
||||
<airframe name="Tob_energyadaptive">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="twog_1.0">
|
||||
<configure name="PERIODIC_FREQUENCY" value="120"/>
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
|
||||
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
|
||||
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP" />
|
||||
|
||||
<define name="USE_I2C0"/>
|
||||
<define name="USE_BARO_ETS"/>
|
||||
</target>
|
||||
<target name="sim" board="pc">
|
||||
<define name="INS_BARO_ID" value="BARO_SIM_SENDER_ID"/>
|
||||
</target>
|
||||
|
||||
<define name="USE_AIRSPEED"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/> <!-- Radio -->
|
||||
<module name="gps" type="ublox"/> <!-- GPS -->
|
||||
<module name="telemetry" type="transparent"/> <!-- Communication -->
|
||||
<module name="imu" type="aspirin_i2c_v1.5"> <!-- IMU -->
|
||||
<configure name="ASPIRIN_I2C_DEV" value="i2c0"/>
|
||||
</module>
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins" type="alt_float">
|
||||
<define name="USE_BAROMETER"/>
|
||||
</module>
|
||||
<module name="control" type="energyadaptive"/>
|
||||
<module name="navigation"/>
|
||||
|
||||
<module name="airspeed_ets">
|
||||
<define name="AIRSPEED_ETS_SYNC_SEND"/>
|
||||
<define name="AIRSPEED_ETS_SCALE" value="1.44"/> <!-- default 1.8-->
|
||||
<!-- <define name="AIRSPEED_ETS_OFFSET" value="50"/> --> <!-- default 0 -->
|
||||
<!-- <configure name="AIRSPEED_ETS_I2C_DEV" value="i2c1"/> -->
|
||||
</module>
|
||||
<module name="baro_ets">
|
||||
<define name="BARO_ETS_SCALE" value="40.0"/>
|
||||
<define name="BARO_ETS_ALT_SCALE" value="0.3"/>
|
||||
<define name="BARO_ETS_SYNC_SEND"/>
|
||||
</module>
|
||||
<module name="baro_sim"/>
|
||||
<module name="air_data"/>
|
||||
<module name="digital_cam">
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO22"/><!-- 18:aux 22:camsw-->
|
||||
</module>
|
||||
<module name="nav" type="survey_polygon"/>
|
||||
</firmware>
|
||||
|
||||
|
||||
<!-- ################################################## -->
|
||||
<servos> <!-- Actuators -->
|
||||
<servo name="MOTOR_LEFT" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<!-- <servo name="MOTOR_RIGHT" no="1" min="1000" neutral="1000" max="2000"/> -->
|
||||
<servo name="AILERON_LEFT" no="7" min="900" neutral="1300" max="1700"/>
|
||||
<servo name="AILERON_RIGHT" no="3" min="1140" neutral="1540" max="1940"/>
|
||||
<servo name="ELEVATOR" no="2" min="1700" neutral="1400" max="1000"/>
|
||||
<servo name="RUDDER" no="6" min="1810" neutral="1410" max="1010"/>
|
||||
<servo name="HATCH" no="4" min="1300" neutral="1300" max="800"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="HATCH" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands> <!-- commands section -->
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="HATCH" value="@GAIN2"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="MIXER">
|
||||
<define name="AILERON_DIFF" value="0.66"/>
|
||||
<define name="COMBI_SWITCH" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="MOTOR_LEFT" value="@THROTTLE"/>
|
||||
<!-- <set servo="MOTOR_RIGHT" value="@THROTTLE"/> -->
|
||||
<set servo="RUDDER" value="@YAW + @ROLL*COMBI_SWITCH"/>
|
||||
<let var="roll" value="@ROLL"/>
|
||||
<set servo="AILERON_LEFT" value="($roll > 0 ? AILERON_DIFF : 1) * $roll"/>
|
||||
<set servo="AILERON_RIGHT" value="($roll > 0 ? 1 : AILERON_DIFF) * $roll"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
<set servo="HATCH" value="@HATCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="40" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="40" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="TRIM" prefix="COMMAND_">
|
||||
<define name="ROLL_TRIM" value="0"/>
|
||||
<define name="PITCH_TRIM" value="0."/> <!--788 -->
|
||||
</section>
|
||||
|
||||
<!--
|
||||
######################################################################################
|
||||
-->
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="MAG_X_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="0"/>
|
||||
<define name="MAG_X_SENS" value="1." integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="1." integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="1." integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="-2" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="2" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="34000" unit="mA"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/> <!--10.5-->
|
||||
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/><!--11.-->
|
||||
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/><!--11.5-->
|
||||
<define name="MAX_BAT_LEVEL" value="12.5" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="CLIMB_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="14." unit="m/s"/>
|
||||
<define name="GLIDE_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="RACE_AIRSPEED" value="25." unit="m/s"/>
|
||||
<define name="STALL_AIRSPEED" value="8." unit="m/s"/>
|
||||
<define name="AIRSPEED_SETPOINT_SLEW" value="0.2" unit="m/s/s"/> <!--default is 1-->
|
||||
|
||||
<define name="CARROT" value="4." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/> <!-- default is 60Hz -->
|
||||
<define name="NO_XBEE_API_INIT" value="TRUE"/>
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="70."/>
|
||||
</section>
|
||||
|
||||
<section name="GLS_APPROACH" prefix="APP_">
|
||||
<define name="ANGLE" value="10" unit="deg"/>
|
||||
<define name="INTERCEPT_AF_SD" value="100" unit="m"/>
|
||||
<define name="TARGET_SPEED" value="13" unit="m/s"/>
|
||||
</section>
|
||||
|
||||
<!-- ########################################################################################### -->
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.1049"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="5."/> <!--default 2-->
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.3"/>
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_PITCH" value="0."/> <!-- default 0 -->
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.15"/>
|
||||
|
||||
<define name="AIRSPEED_PGAIN" value="0."/>
|
||||
|
||||
<define name="AUTO_THROTTLE_OF_AIRSPEED_PGAIN" value="0.069"/>
|
||||
<define name="AUTO_THROTTLE_OF_AIRSPEED_IGAIN" value="0.01"/>
|
||||
|
||||
<define name="AUTO_PITCH_OF_AIRSPEED_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_PITCH_OF_AIRSPEED_IGAIN" value="0.003"/>
|
||||
<define name="AUTO_PITCH_OF_AIRSPEED_DGAIN" value="0.03"/>
|
||||
|
||||
<define name="ENERGY_TOT_PGAIN" value="0."/>
|
||||
<define name="ENERGY_TOT_IGAIN" value="0."/>
|
||||
<define name="ENERGY_DIFF_PGAIN" value="0."/>
|
||||
<define name="ENERGY_DIFF_IGAIN" value="0."/>
|
||||
|
||||
<define name="AUTO_GROUNDSPEED_SETPOINT" value="6.0" unit="m/s"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="0.75"/>
|
||||
<define name="AUTO_GROUNDSPEED_IGAIN" value="0.25"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.8"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="50" unit="deg"/>
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7400."/>
|
||||
<define name="ROLL_RATE_GAIN" value="200."/>
|
||||
<define name="ROLL_IGAIN" value="100."/>
|
||||
<define name="ROLL_KFFA" value="0"/>
|
||||
<define name="ROLL_KFFD" value="0"/>
|
||||
|
||||
<define name="PITCH_MAX_SETPOINT" value="25" unit="deg"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-25" unit="deg"/>
|
||||
<define name="PITCH_PGAIN" value="7200."/>
|
||||
<define name="PITCH_DGAIN" value="6."/>
|
||||
<define name="PITCH_IGAIN" value="100."/>
|
||||
<define name="PITCH_KFFA" value="0."/>
|
||||
<define name="PITCH_KFFD" value="0."/>
|
||||
|
||||
<define name="PITCH_OF_ROLL" value="RadOfDeg(1.0)"/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.60"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="RadOfDeg(12)"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="RadOfDeg(-20)"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/> <!-- -->
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_PITCH" value="0."/>
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_PERIOD" value="3.0" unit="sec"/>
|
||||
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="50" unit="meter"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="15" unit="deg"/>
|
||||
<define name="DEFAULT_PITCH" value="0" unit="deg"/>
|
||||
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMU">
|
||||
<define name="WEIGHT" value ="1."/>
|
||||
<define name="YAW_RESPONSE_FACTOR" value =".9"/> <!--default 1.-->
|
||||
<define name="PITCH_RESPONSE_FACTOR" value ="1."/> <!--default 1.-->
|
||||
<define name="ROLL_RESPONSE_FACTOR" value ="15."/> <!--default 15-->
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -1,193 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="BOOZ2_a1">
|
||||
|
||||
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
||||
<define name="NB" value="4"/>
|
||||
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
|
||||
</section>
|
||||
|
||||
<servos driver="Mkk">
|
||||
<servo name="FRONT" no="0" min="0" neutral="2" max="210"/>
|
||||
<servo name="BACK" no="1" min="0" neutral="2" max="210"/>
|
||||
<servo name="RIGHT" no="2" min="0" neutral="2" max="210"/>
|
||||
<servo name="LEFT" no="3" min="0" neutral="2" max="210"/>
|
||||
</servos>
|
||||
|
||||
<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>
|
||||
|
||||
<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="4"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<define name="ROLL_COEF" value="{ 0, 0, -256, 256}"/>
|
||||
<define name="PITCH_COEF" value="{ 256, -256, 0, 0}"/>
|
||||
<define name="YAW_COEF" value="{ -256, -256, 256, 256}"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[0]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[1]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[2]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[3]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<define name="GYRO_P_NEUTRAL" value="33924"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="33417"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="32809"/>
|
||||
<define name="GYRO_P_SENS" value=" 1.01" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value=" 1.01" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value=" 1.01" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="32081"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="33738"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="32441"/>
|
||||
<define name="ACCEL_X_SENS" value="2.50411474" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="2.48126183" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="2.51396167" integer="16"/>
|
||||
|
||||
|
||||
<define name="MAG_X_CHAN" value="4"/>
|
||||
<define name="MAG_Y_CHAN" value="0"/>
|
||||
<define name="MAG_Z_CHAN" value="2"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="2358"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="2362"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="2119"/>
|
||||
|
||||
<!-- <define name="MAG_X_SENS" value="-4.94075530" integer="16"/>-->
|
||||
<!-- <define name="MAG_Y_SENS" value=" 5.10207664" 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_Z_SENS" value="4.90788848" integer="16"/>
|
||||
<define name="MAG_45_HACK" value="1"/>
|
||||
<!-- <define name="MAG_X_SENS" value="-4.94075530 * sqrt(2)/2" integer="16"/> -->
|
||||
<!-- <define name="MAG_Y_SENS" value=" 5.10207664 * sqrt(2)/2" integer="16"/> -->
|
||||
<define name="MAG_X_SENS" value=" 3.4936416" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value=" 3.607713" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="4." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="3." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
<!--
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
-->
|
||||
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.9"/>
|
||||
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.9"/>
|
||||
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="250" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.9"/>
|
||||
<define name="REF_MAX_R" value="180." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="400"/>
|
||||
<define name="PHI_DGAIN" value="300"/>
|
||||
<define name="PHI_IGAIN" value="100"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="400"/>
|
||||
<define name="THETA_DGAIN" value="300"/>
|
||||
<define name="THETA_IGAIN" value="100"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="380"/>
|
||||
<define name="PSI_DGAIN" value="320"/>
|
||||
<define name="PSI_IGAIN" value="75"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value=" 300"/>
|
||||
<define name="THETA_DDGAIN" value=" 300"/>
|
||||
<define name="PSI_DDGAIN" value=" 300"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="HOVER_KP" value="500"/>
|
||||
<define name="HOVER_KD" value="200"/>
|
||||
<define name="HOVER_KI" value="100"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="IGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_RC_CLIMB"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_booz2_a1.h" type="string"/>
|
||||
</section>
|
||||
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="booz_1.0"/>
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="motor_mixing"/>
|
||||
<module name="actuators" type="mkk"/>
|
||||
<module name="imu" type="b2_v1.0"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="stabilization" type="int_euler"/>
|
||||
<module name="ahrs" type="int_cmpl_euler"/>
|
||||
<module name="ins" type="hff"/>
|
||||
</firmware>
|
||||
|
||||
|
||||
</airframe>
|
||||
@@ -1,182 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Multiplex EasyStar, using rudder
|
||||
Lisa/MX board
|
||||
XBee 2.4GHz modem in transparent mode
|
||||
-->
|
||||
|
||||
<airframe name="EasyStar2 - Lisa/MX">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="lisa_mx_2.1"/>
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="USE_AIRSPEED"/>
|
||||
<define name="USE_BARO_ETS"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="imu" type="lisa_mx_v2.1"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
|
||||
<module name="airspeed_ets">
|
||||
<configure name="AIRSPEED_ETS_I2C_DEV" value="i2c1"/>
|
||||
</module>
|
||||
<module name="baro_ets">
|
||||
<configure name="BARO_ETS_I2C_DEV" value="i2c1"/>
|
||||
</module>
|
||||
<module name="air_data"/>
|
||||
<module name="geo_mag"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="twog_1.0" />
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1120" neutral="1120" max="1920"/>
|
||||
<servo name="ELEVATOR" no="1" min="1100" neutral="1514" max="1900"/>
|
||||
<servo name="RUDDER" no="2" min="950" neutral="1612" max="2050"/>
|
||||
</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="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
</rc_commands>
|
||||
|
||||
<command_laws>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="RUDDER" value="@ROLL"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="50" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="40" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- ACCEL and GYRO calibration left out to take default datasheet values -->
|
||||
|
||||
<!-- replace this with your own mag calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="-45"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="334"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="7"/>
|
||||
<define name="MAG_X_SENS" value="4.47647816128" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.71085671542" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.41585354498" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000" unit="mA"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="8.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="8.5" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="9.5" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.5" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
|
||||
<define name="CARROT" value="4." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(2.0*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="NO_XBEE_API_INIT" value="TRUE"/>
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="90."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.0" unit="volt"/>
|
||||
<!-- outer loop -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.075" unit="(m/s)/m"/>
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="4." unit="m/s"/>
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.4" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.8" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500" unit="pprz_t"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000" unit="pprz_t"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.02" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05" unit="rad/(m/s)"/>
|
||||
<!-- auto airspeed and altitude inner loop -->
|
||||
<define name="AUTO_AIRSPEED_SETPOINT" value="14.5" unit="m/s"/>
|
||||
<define name="AUTO_AIRSPEED_PGAIN" value="0.060"/>
|
||||
<define name="AUTO_AIRSPEED_IGAIN" value="0.050"/>
|
||||
<define name="AUTO_GROUNDSPEED_SETPOINT" value="6.0" unit="m/s"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="0.75"/>
|
||||
<define name="AUTO_GROUNDSPEED_IGAIN" value="0.25"/>
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.125"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.025"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(25)"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="RadOfDeg(-25)"/>
|
||||
<define name="THROTTLE_SLEW" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.7"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="25" unit="deg"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-25" unit="deg"/>
|
||||
<define name="PITCH_PGAIN" value="20000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="2500"/>
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7400"/>
|
||||
<define name="ROLL_RATE_GAIN" value="200"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.70"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="RadOfDeg(18)"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="RadOfDeg(-20)"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0.4" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="15" unit="deg"/>
|
||||
<define name="DEFAULT_PITCH" value="0" unit="deg"/>
|
||||
<define name="HOME_RADIUS" value="90" unit="m"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_MODEL" value="easystar" type="string"/>
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="10" unit="m/s"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,28 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "airframe.dtd">
|
||||
|
||||
<!--
|
||||
Sparkfun Logomatic V26 data logger
|
||||
|
||||
http://www.sparkfun.com/products/10216
|
||||
|
||||
P1-P8 can be used as ADC_0-ADC_7
|
||||
P1 as PPM_IN
|
||||
P2 as SERV_CLK
|
||||
|
||||
For now only non SDHC SD cards (<= 2GB) are supported. martinmm@pfump.org
|
||||
|
||||
-->
|
||||
|
||||
<airframe name="Logomatic">
|
||||
|
||||
<firmware name="logger">
|
||||
<target name="ap" board="logom_2.6" >
|
||||
<configure name="LOG_MSG_FMT" value="LOG_XBEE"/>
|
||||
<configure name="SPI_CHANNEL" value="0" />
|
||||
<configure name="UART0_BAUD" value="B57600" />
|
||||
<configure name="UART1_BAUD" value="B57600" />
|
||||
</target>
|
||||
</firmware>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -1,219 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Microjet Multiplex (http://www.multiplex-rc.de/)
|
||||
Tiny 1.1 board (http://wiki.paparazziuav.org/wiki/Tiny)
|
||||
Tilted infrared sensor
|
||||
Xbee modem in API mode
|
||||
-->
|
||||
|
||||
<airframe name="Microjet Tiny 1.1">
|
||||
|
||||
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1290" neutral="1290" max="1810"/>
|
||||
<servo name="AILEVON_LEFT" no="1" min="2000" neutral="1510" max="1000"/>
|
||||
<servo name="AILEVON_RIGHT" no="3" min="1000" neutral="1535" max="2000"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="SHUTTER" 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.7"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="1."/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1."/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.5"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="-1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="-3.6" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="5" unit="deg"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="GYRO_P_SIGN" value="1"/>
|
||||
<define name="GYRO_P_NEUTRAL" value="500"/>
|
||||
<!--define name="ADXRS300_RESISTOR_BRIDGE" value="(3.3/(3.3+1.8))"/-->
|
||||
<!--define name="ADXRS300_SENSITIVITY" value="5" unit="mV/(deg/s)"/-->
|
||||
<!--define name="ROLL_SCALE" value="3.3*1000./1024./(IMU_ADXRS300_SENSITIVITY*IMU_ADXRS300_RESISTOR_BRIDGE)" unit="deg/s/adc_unit"/-->
|
||||
<!--define name="RATE_DEGS_TO_RADINT" value="M_PI/180./4096."/-->
|
||||
<!--define name="GYRO_P_SENS" value="IMU_RATE_DEGS_TO_RADINT * IMU_ROLL_SCALE" integer="16"/-->
|
||||
<define name="GYRO_P_SENS" value="0.137518981" integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="2000"/>
|
||||
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="XBEE_INIT" value="ATPL2\rATRN5\rATTT80\r" type="string"/>
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
<define name="RC_MAX_RATE" value="70." /> <!-- pass rate in Hz, -->
|
||||
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.0"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.6" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="12000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
|
||||
<define name="ROLL_SLEW" value="0.1"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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"/>
|
||||
</section>
|
||||
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc" />
|
||||
<target name="ap" board="tiny_1.1">
|
||||
<module name="tune_airspeed"/>
|
||||
<module name="digital_cam" type="servo">
|
||||
<define name="DC_SHUTTER_SERVO" value="COMMAND_SHUTTER" />
|
||||
</module>
|
||||
<module name="openlog"/>
|
||||
</target>
|
||||
|
||||
<define name="AGR_CLIMB" />
|
||||
<define name="LOITER_TRIM" />
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="xbee_api">
|
||||
<configure name="MODEM_BAUD" value="B9600"/>
|
||||
</module>
|
||||
|
||||
<!-- Sensors -->
|
||||
<module name="imu" type="analog">
|
||||
<configure name="GYRO_P" value="ADC_3"/>
|
||||
</module>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs" type="infrared"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
|
||||
<module name="control"/>
|
||||
<module name="navigation"/>
|
||||
<module name="nav" type="survey_polygon"/>
|
||||
<module name="nav" type="line_border"/>
|
||||
<module name="nav" type="line"/>
|
||||
<module name="nav" type="smooth"/>
|
||||
<module name="nav" type="flower"/>
|
||||
<module name="nav" type="line_osam"/>
|
||||
<module name="nav" type="survey_poly_osam"/>
|
||||
<module name="nav" type="vertical_raster"/>
|
||||
<module name="nav" type="bungee_takeoff"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
<section name="CAM">
|
||||
<define name="CAM_HFV" value="65.1"/>
|
||||
<define name="CAM_VFV" value="40.2"/>
|
||||
</section>
|
||||
|
||||
<section name="GCS">
|
||||
<define name="AC_ICON" value="flyingwing"/>
|
||||
</section>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="tiny_1.1" />
|
||||
<target name="usb_tunnel" board="tiny_1.1">
|
||||
<configure name="TUNNEL_PORT" value="UART0"/>
|
||||
</target>
|
||||
</firmware>
|
||||
|
||||
</airframe>
|
||||
@@ -1,180 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Microjet Multiplex (http://www.multiplex-rc.de/)
|
||||
Twog 1.0 board (http://wiki.paparazziuav.org/wiki/TWOG/v1.0)
|
||||
Aspirin v1.5 (http://wiki.paparazziuav.org/wiki/AspirinIMU)
|
||||
Xbee modem in transparent mode
|
||||
-->
|
||||
|
||||
<airframe name="Microjet Twog with Aspirin IMU">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="twog_1.0">
|
||||
<configure name="PERIODIC_FREQUENCY" value="120"/>
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
|
||||
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
|
||||
</target>
|
||||
|
||||
<define name="AGR_CLIMB" />
|
||||
<define name="LOITER_TRIM" />
|
||||
|
||||
<!-- set aspirin to 100Hz Accel/Gyro output -->
|
||||
<define name="ASPIRIN_ACCEL_RATE" value="ADXL345_RATE_100HZ"/>
|
||||
<define name="ASPIRIN_GYRO_LOWPASS" value="ITG3200_DLPF_42HZ"/>
|
||||
<define name="ASPIRIN_GYRO_SMPLRT_DIV" value="9"/>
|
||||
|
||||
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
|
||||
|
||||
<module name="imu" type="aspirin_v1.5">
|
||||
<configure name="ASPIRIN_I2C_DEV" value="i2c0"/>
|
||||
<configure name="ASPIRIN_SPI_DEV" value="spi1"/>
|
||||
<configure name="ASPIRIN_SPI_SLAVE_IDX" value="SPI_SLAVE0"/>
|
||||
</module>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="navigation"/>
|
||||
<module name="sys_mon"/>
|
||||
</firmware>
|
||||
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1290" neutral="1290" max="1810"/>
|
||||
<servo name="AILEVON_LEFT" no="1" min="2000" neutral="1510" max="1000"/>
|
||||
<servo name="AILEVON_RIGHT" no="3" min="1000" neutral="1535" max="2000"/>
|
||||
</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="IMU" prefix="IMU_">
|
||||
<define name="MAG_X_NEUTRAL" value="-45"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="334"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="7"/>
|
||||
|
||||
<define name="MAG_X_SENS" value="4.47647816128" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.71085671542" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.41585354498" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<!-- replace this with your local magnetic field -->
|
||||
<define name="H_X" value="0.3770441"/>
|
||||
<define name="H_Y" value="0.0193986"/>
|
||||
<define name="H_Z" value="0.9259921"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.0"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="30" unit="deg"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-30" unit="deg"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="12000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
|
||||
<define name="ROLL_SLEW" value="0.1"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="40." unit="deg"/>
|
||||
<define name="MAX_PITCH" value="35." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="2000"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,220 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="Miniquad CHNI">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
<!--define name="GUIDANCE_H_USE_REF"/-->
|
||||
|
||||
<target name="ap" board="hbmini_1.0">
|
||||
<define name="FAILSAFE_GROUND_DETECT"/>
|
||||
<define name="USE_GPS_ACC4R"/>
|
||||
<define name="ACTUATORS_START_DELAY" value="3"/>
|
||||
</target>
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="actuators" type="mkk">
|
||||
<configure name="ACTUATORS_MKK_I2C_SCL_TIME" value="25"/>
|
||||
</module>
|
||||
<module name="motor_mixing"/>
|
||||
<module name="imu" type="hbmini"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="stabilization" type="int_euler"/>
|
||||
<module name="ahrs" type="float_cmpl_rmat"/>
|
||||
<module name="ins" type="hff"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
</firmware>
|
||||
|
||||
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
||||
<define name="NB" value="4"/>
|
||||
<!-- NW, SE, NE, SW -->
|
||||
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
|
||||
</section>
|
||||
|
||||
<servos driver="Mkk">
|
||||
<servo name="NW" no="0" min="0" neutral="10" max="100"/>
|
||||
<servo name="SE" no="1" min="0" neutral="10" max="100"/>
|
||||
<servo name="NE" no="2" min="0" neutral="10" max="100"/>
|
||||
<servo name="SW" no="3" min="0" neutral="10" max="100"/>
|
||||
</servos>
|
||||
|
||||
<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>
|
||||
|
||||
<section name="MIXING" prefix="MOTOR_MIXING_">
|
||||
<define name="TRIM_ROLL" value="135"/>
|
||||
<define name="TRIM_PITCH" value="-200"/>
|
||||
<define name="TRIM_YAW" value="-300"/>
|
||||
<define name="NB_MOTOR" value="4"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<define name="ROLL_COEF" value="{ 256, -256, -256, 256}"/>
|
||||
<define name="PITCH_COEF" value="{ 256, -256, 256, -256}"/>
|
||||
<define name="YAW_COEF" value="{ 256, 256, -256, -256}"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
|
||||
<set servo="NW" value="motor_mixing.commands[0]"/>
|
||||
<set servo="SE" value="motor_mixing.commands[1]"/>
|
||||
<set servo="NE" value="motor_mixing.commands[2]"/>
|
||||
<set servo="SW" value="motor_mixing.commands[3]"/>
|
||||
</command_laws>
|
||||
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<define name="GYRO_P_NEUTRAL" value="21460"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="21490"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="21830"/>
|
||||
|
||||
<define name="GYRO_P_SENS" value="5.79" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="5.89" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.56" integer="16"/>
|
||||
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="26480"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="26380"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="25836"/>
|
||||
<define name="ACCEL_X_SENS" value="1.94" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="1.94" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="1.99" integer="16"/>
|
||||
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-108"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="57"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="-95"/>
|
||||
<define name="MAG_X_SENS" value="3.6472944636" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.09086502241" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.74963511486" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="-2.5" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="-2.0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="H_X" value="0.366765"/>
|
||||
<define name="H_Y" value="0.013312"/>
|
||||
<define name="H_Z" value="0.930219"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="220." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.9"/>
|
||||
<define name="REF_MAX_P" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.9"/>
|
||||
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.9"/>
|
||||
<define name="REF_MAX_R" value="180." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="880"/>
|
||||
<define name="PHI_DGAIN" value="400"/>
|
||||
<define name="PHI_IGAIN" value="300"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="880"/>
|
||||
<define name="THETA_DGAIN" value="400"/>
|
||||
<define name="THETA_IGAIN" value="300"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="600"/>
|
||||
<define name="PSI_DGAIN" value="320"/>
|
||||
<define name="PSI_IGAIN" value="150"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="100"/>
|
||||
<define name="THETA_DDGAIN" value="100"/>
|
||||
<define name="PSI_DDGAIN" value="0"/>
|
||||
|
||||
<define name="PHI_AGAIN" value="0"/>
|
||||
<define name="THETA_AGAIN" value="0"/>
|
||||
<define name="PSI_AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
|
||||
<define name="REF_MIN_ZDD" value="-0.5*9.81"/>
|
||||
<define name="REF_MAX_ZDD" value=" 0.5*9.81"/>
|
||||
<define name="REF_MIN_ZD" value="-1.5"/>
|
||||
<define name="REF_MAX_ZD" value=" 1.5"/>
|
||||
<define name="HOVER_KP" value="70"/>
|
||||
<define name="HOVER_KD" value="100"/>
|
||||
<define name="HOVER_KI" value="9"/>
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) / (MAX_PPRZ/2) -->
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) * 20% -->
|
||||
<define name="ADAPT_NOISE_FACTOR" value="1.5"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="30" unit="deg"/>
|
||||
<define name="PGAIN" value="80"/>
|
||||
<define name="DGAIN" value="140"/>
|
||||
<define name="IGAIN" value="10"/>
|
||||
<define name="NGAIN" value="0"/>
|
||||
<!-- feedforward -->
|
||||
<define name="AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="6.5" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="8.4" unit="V"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
<!--define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_Z_HOLD"/-->
|
||||
<define name="MODE_AUTO2" value="AP_MODE_HOVER_Z_HOLD"/>
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
<define name="BOOZ_FMS_TIMEOUT" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="10."/>
|
||||
</section>
|
||||
|
||||
<section name="GCS">
|
||||
<define name="ALT_SHIFT_PLUS_PLUS" value="5"/>
|
||||
<define name="ALT_SHIFT_PLUS" value="1"/>
|
||||
<define name="ALT_SHIFT_MINUS" value="-1"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="nw_motor, se_motor, ne_motor, sw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_hbmini.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,257 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="Blender">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
<!--define name="GUIDANCE_H_USE_REF"/-->
|
||||
|
||||
<target name="ap" board="navgo_1.0">
|
||||
<define name="FAILSAFE_GROUND_DETECT"/>
|
||||
<define name="USE_GPS_ACC4R"/>
|
||||
<define name="ACTUATORS_START_DELAY" value="3"/>
|
||||
</target>
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="actuators" type="mkk">
|
||||
<configure name="ACTUATORS_MKK_I2C_SCL_TIME" value="25"/>
|
||||
</module>
|
||||
<module name="motor_mixing"/>
|
||||
<module name="actuators" type="pwm">
|
||||
<define name="USE_PWM0"/>
|
||||
</module>
|
||||
<module name="imu" type="navgo"/>
|
||||
<module name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</module>
|
||||
<module name="stabilization" type="int_euler"/>
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins" type="hff"/>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="512"/>
|
||||
|
||||
<module name="switch" type="servo"/>
|
||||
<module name="rotorcraft_cam"/>
|
||||
<module name="digital_cam">
|
||||
<!-- AUX1 -->
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOA,GPIO7"/>
|
||||
</module>
|
||||
<module name="nav" type="survey_rectangle_rotorcraft"/>
|
||||
</firmware>
|
||||
|
||||
<section name="MIXING" prefix="MOTOR_MIXING_">
|
||||
<define name="TRIM_ROLL" value="0"/>
|
||||
<define name="TRIM_PITCH" value="0"/>
|
||||
<define name="TRIM_YAW" value="0"/>
|
||||
|
||||
<!-- FRONT CW, RIGHT CCW, BACK CW, LEFT CCW -->
|
||||
<define name="TYPE" value="QUAD_PLUS"/>
|
||||
</section>
|
||||
|
||||
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
||||
<define name="NB" value="4"/>
|
||||
<!-- FRONT CW, RIGHT CCW, BACK CW, LEFT CCW -->
|
||||
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
|
||||
</section>
|
||||
|
||||
<servos driver="Mkk">
|
||||
<servo name="FRONT" no="0" min="0" neutral="2" max="255"/>
|
||||
<servo name="RIGHT" no="1" min="0" neutral="2" max="255"/>
|
||||
<servo name="BACK" no="2" min="0" neutral="2" max="255"/>
|
||||
<servo name="LEFT" no="3" min="0" neutral="2" max="255"/>
|
||||
</servos>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="DROP" no="0" min="1000" neutral="1500" max="2000"/>
|
||||
</servos>
|
||||
|
||||
<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>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[0]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[1]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[2]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[3]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<define name="GYRO_P_NEUTRAL" value="10"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="-32"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="11"/>
|
||||
|
||||
<!-- SENS ITG3200 1/14.375 (deg/s)/LSB, rate frac 12bit => 1/14.375 * pi / 180 * 2^12 -->
|
||||
<define name="GYRO_P_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.97312" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="9"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="14"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-16"/>
|
||||
|
||||
<!-- SENS ADXL345 16G 31.2 mg/LSB, accel frac 10bit => 31.2 * 2^10 / 1000 = 31.9488-->
|
||||
<define name="ACCEL_X_SENS" value="38.5866088465" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="38.7212932023" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="39.403098907" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="80"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-271"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="112"/>
|
||||
<define name="MAG_X_SENS" value="4.44131219218" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.56234629213" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="5.298653926" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
|
||||
</section>
|
||||
|
||||
<!-- Magnetic field for Toulouse (declination -16°) -->
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="PROPAGATE_LOW_PASS_RATES" value="1"/>
|
||||
<define name="H_X" value=" 0.513081"/>
|
||||
<define name="H_Y" value="-0.00242783"/>
|
||||
<define name="H_Z" value=" 0.858336"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<!-- datasheet 1.4 mm/LSB : 0.0014*2^8 = 0.3584 -->
|
||||
<!-- calibration SENS = 1.156 :( -->
|
||||
<define name="SONAR_SENS" value="0.0128633" integer="16"/>
|
||||
<define name="SONAR_OFFSET" value="7"/>
|
||||
<define name="SONAR_MAX_RANGE" value="4.0"/>
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="150" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.85"/>
|
||||
<define name="REF_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="1800"/>
|
||||
<define name="PHI_DGAIN" value="240"/>
|
||||
<define name="PHI_IGAIN" value="200"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="1800"/>
|
||||
<define name="THETA_DGAIN" value="240"/>
|
||||
<define name="THETA_IGAIN" value="200"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="1000"/>
|
||||
<define name="PSI_DGAIN" value="350"/>
|
||||
<define name="PSI_IGAIN" value="20"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="170"/>
|
||||
<define name="THETA_DDGAIN" value="170"/>
|
||||
<define name="PSI_DDGAIN" value="170"/>
|
||||
|
||||
<define name="PHI_AGAIN" value="0"/>
|
||||
<define name="THETA_AGAIN" value="0"/>
|
||||
<define name="PSI_AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
|
||||
<define name="REF_MIN_ZDD" value="-0.5*9.81"/>
|
||||
<define name="REF_MAX_ZDD" value=" 0.5*9.81"/>
|
||||
<define name="REF_MIN_ZD" value="-1.5"/>
|
||||
<define name="REF_MAX_ZD" value=" 1.5"/>
|
||||
<define name="HOVER_KP" value="130"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="0"/>
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) / (MAX_PPRZ/2) -->
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) * 20% -->
|
||||
<define name="ADAPT_NOISE_FACTOR" value="1.5"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="30" unit="deg"/>
|
||||
<define name="PGAIN" value="50"/>
|
||||
<define name="DGAIN" value="140"/>
|
||||
<define name="IGAIN" value="20"/>
|
||||
<define name="NGAIN" value="0"/>
|
||||
<!-- feedforward -->
|
||||
<define name="AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
<!--define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_Z_HOLD"/-->
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
<define name="BOOZ_FMS_TIMEOUT" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="CAM" prefix="ROTORCRAFT_CAM_">
|
||||
<define name="DEFAULT_MODE" value="ROTORCRAFT_CAM_MODE_MANUAL"/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="5" unit="meter"/>
|
||||
</section>
|
||||
|
||||
<section name="SWITCH_SERVO">
|
||||
<define name="SWITCH_SERVO_SERVO" value="DROP"/>
|
||||
<define name="SWITCH_SERVO_ON_VALUE" value="SERVO_DROP_MIN"/>
|
||||
<define name="SWITCH_SERVO_OFF_VALUE" value="SERVO_DROP_MAX"/>
|
||||
<define name="DropOpen()" value="SwitchServoOn()"/>
|
||||
<define name="DropClose()" value="SwitchServoOff()"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="10."/>
|
||||
</section>
|
||||
|
||||
<section name="GCS">
|
||||
<define name="ALT_SHIFT_PLUS_PLUS" value="5"/>
|
||||
<define name="ALT_SHIFT_PLUS" value="1"/>
|
||||
<define name="ALT_SHIFT_MINUS" value="-1"/>
|
||||
<define name="SPEECH_NAME" value="Quad NavGo"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, right_motor, back_motor, left_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,184 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Twinjet Multiplex (http://www.multiplex-rc.de/)
|
||||
Twog v1 board (http://wiki.paparazziuav.org/wiki/Twog_v1)
|
||||
PerkinElmer TPS334 IR Sensors
|
||||
Aligned infrared sensor
|
||||
XBee modem with AT firmware
|
||||
LEA 5H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Twinjet">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="twog_1.0"/>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="imu" type="analog">
|
||||
<configure name="GYRO_P" value="ADC_3"/>
|
||||
</module>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="gps_passthrough"/>
|
||||
<module name="adc_generic">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_7" />
|
||||
</module>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
<module name="nav" type="line"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="twog_1.0" />
|
||||
<target name="usb_tunnel" board="twog_1.0">
|
||||
<configure name="TUNNEL_PORT" value="UART0"/>
|
||||
</target>
|
||||
</firmware>
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILEVON_RIGHT" no="1" min="1230" neutral="1710" max="2100"/>
|
||||
<servo name="AILEVON_LEFT" no="2" min="2120" neutral="1785" max="1300"/>
|
||||
</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="1.00"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
|
||||
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
|
||||
<set servo="AILEVON_LEFT" value="-$aileron + $elevator"/>
|
||||
<set servo="AILEVON_RIGHT" value="$aileron + $elevator"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.6"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_ALIGNED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="5" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="10" unit="deg"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="1."/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1."/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.25"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="GYRO_P_SIGN" value="1."/>
|
||||
<define name="GYRO_P_NEUTRAL" value="316"/>
|
||||
<define name="GYRO_P_SENS" value="1." integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.9"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.53" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="6000."/>
|
||||
<define name="PITCH_DGAIN" value="0."/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="0"/>
|
||||
|
||||
<!-- roll rate loop -->
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.05"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.40"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value=".3"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.8"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="2000"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1500"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.008"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.14"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="75."/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="1000"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="2" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE+0.05" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="50" unit="m"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="CLIMB_THROTTLE" value="0.65"/><!-- Throttle for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Throttle for Aggressive Decent -->
|
||||
<define name="CLIMB_PITCH" value="0.2"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,215 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Use settings/tuning_ins.xml
|
||||
Use telemetry/default_fixedwing_imu.xml
|
||||
|
||||
Reely Condor
|
||||
TWOG v1.0 Board (http://wiki.paparazziuav.org/wiki/TWOG)
|
||||
Sparkfun Razor IMU with Premerlani Code
|
||||
wi.232 Radiomodems
|
||||
-->
|
||||
|
||||
|
||||
<airframe name="Reely Condor CHNI">
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="7" min="1200" neutral="1200" max="2000"/>
|
||||
<servo name="AILERON" no="4" min="1000" neutral="1500" max="2000"/>
|
||||
<servo name="ELEVATOR" no="3" max="2000" neutral="1500" min="1000"/>
|
||||
<servo name="CAM" no="2" max="2000" neutral="1500" min="1000"/>
|
||||
<servo name="TILT" no="6" max="2000" neutral="1501" min="1000"/>
|
||||
</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>
|
||||
|
||||
<command_laws>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="AILERON" value="@ROLL"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="GYRO_P_NEUTRAL" value="512"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="512"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="GYRO_P_SENS" value="0.017" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="0.017" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="0.017" integer="16"/>
|
||||
|
||||
<define name="GYRO_P_SIGN" value="1" />
|
||||
<define name="GYRO_Q_SIGN" value="1" />
|
||||
<define name="GYRO_R_SIGN" value="-1" />
|
||||
|
||||
<define name="ACCEL_X_SENS" value="0.1" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="0.1" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.1" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="512"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="512"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="ACCEL_X_SIGN" value="1"/>
|
||||
<define name="ACCEL_Y_SIGN" value="-1"/>
|
||||
<define name="ACCEL_Z_SIGN" value="1"/>
|
||||
|
||||
<!-- this should not be needed if no mag is used -->
|
||||
<define name="MAG_X_NEUTRAL" value="512"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="512"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg" />
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg" />
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg" />
|
||||
</section>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="60" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="40" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<!-- settings for the Analog IMU -->
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<!-- 3S LiPo with 1050mAh, connected to an 20A ESC -->
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000" unit="mA" />
|
||||
<define name="VOLTAGE_ADC_A" value="0.02456533604651162791"/>
|
||||
<define name="VOLTAGE_ADC_B" value="0.24024993023255813953"/>
|
||||
<define name="VoltageOfAdc(adc)" value ="(VOLTAGE_ADC_A * adc + VOLTAGE_ADC_B)"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="9.5" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMU">
|
||||
<define name="YAW_RESPONSE_FACTOR" value="0.7"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="TELEMETRY_MODE_FBW" value="1"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="12.5" unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="50."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.07"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.55"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.30"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.80"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-500"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.025"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.05"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.075"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.05"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.85"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.6" 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_PGAIN" value="12000."/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="PITCH_PGAIN" value="9000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.8"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="1" 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>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="twog_1.0">
|
||||
<define name="AGR_CLIMB"/>
|
||||
</target>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_BAUD" value="B9600"/>
|
||||
</module>
|
||||
<!-- Actuators are automatically chosen according to the board-->
|
||||
<module name="control"/>
|
||||
<!-- Sensors -->
|
||||
<module name="imu" type="analog">
|
||||
<configure name="GYRO_P" value="ADC_0"/>
|
||||
<configure name="GYRO_Q" value="ADC_1"/>
|
||||
<configure name="GYRO_R" value="ADC_2"/>
|
||||
<configure name="ACCEL_X" value="ADC_5"/>
|
||||
<configure name="ACCEL_Y" value="ADC_6"/>
|
||||
<configure name="ACCEL_Z" value="ADC_7"/>
|
||||
<configure name="ADC_ACCEL_NB_SAMPLES" value="32"/>
|
||||
</module>
|
||||
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<module name="nav" type="line"/>
|
||||
</firmware>
|
||||
|
||||
</airframe>
|
||||
@@ -1,174 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Example airframe
|
||||
Umarim Lite
|
||||
-->
|
||||
|
||||
<airframe name="Weasel">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<define name="USE_I2C0"/>
|
||||
<define name="USE_I2C1"/>
|
||||
<define name="AGR_CLIMB" />
|
||||
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="umarim_lite_2.0"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="transparent"/>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<module name="imu" type="umarim"/>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="control"/>
|
||||
<module name="navigation"/>
|
||||
<!-- Sensors -->
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="7" min="1040" neutral="1040" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="6" min="1900" neutral="1543" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="3" min="1100" neutral="1561" max="1900"/>
|
||||
</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_">
|
||||
<!-- Calibration Neutral -->
|
||||
<define name="GYRO_P_NEUTRAL" value="-15"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="94"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="-7"/>
|
||||
|
||||
<!-- SENS ITG3200 1/14.375 (deg/s)/LSB, rate frac 12bit => 1/14.375 * pi / 180 * 2^12 -->
|
||||
<define name="GYRO_P_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.97312" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<!-- SENS ADXL345 16G 31.2 mg/LSB, accel frac 10bit => 31.2 * 2^10 / 1000 -->
|
||||
<define name="ACCEL_X_SENS" value="31.9488" integer="10"/>
|
||||
<define name="ACCEL_Y_SENS" value="31.9488" integer="10"/>
|
||||
<define name="ACCEL_Z_SENS" value="31.9488" integer="10"/>
|
||||
|
||||
<!-- Just to compile -->
|
||||
<define name="MAG_X_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="0"/>
|
||||
|
||||
<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.048" unit="rad"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="rad"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</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="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.0"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.6" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="12000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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>
|
||||
|
||||
</airframe>
|
||||
@@ -1,180 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
|
||||
<airframe name="Yapa v2">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="twog_1.0">
|
||||
<module name="spi_slave_hs"/>
|
||||
</target>
|
||||
<target name="sim" board="pc">
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
</target>
|
||||
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="gps" type="ublox" />
|
||||
<module name="telemetry" type="xbee_api">
|
||||
<configure name="MODEM_BAUD" value="B9600"/>
|
||||
</module>
|
||||
|
||||
<module name="control"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
|
||||
<module name="ahrs_chimu_spi" >
|
||||
<define name="CHIMU_BIG_ENDIAN" />
|
||||
</module>
|
||||
<module name="nav" type="line"/>
|
||||
</firmware>
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILERON_LEFT" no="1" min="1000" neutral="1500" max="2000"/>
|
||||
<servo name="AILERON_RIGHT" no="2" min="2000" neutral="1500" max="1000"/>
|
||||
<servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/>
|
||||
<servo name="RUDDER" no="4" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="BRAKE" failsafe_value="0"/> <!-- both elerons up as butterfly brake ? -->
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="BRAKE" value="@YAW"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="SERVO_MIXER_GAINS">
|
||||
<define name="AILERON_RATE_UP" value="0.50f"/>
|
||||
<define name="AILERON_RATE_DOWN" value="0.25f"/>
|
||||
|
||||
<define name="AILERON_RATE_UP_BRAKE" value="0.5f"/>
|
||||
<define name="AILERON_RATE_DOWN_BRAKE" value="0.9f"/>
|
||||
|
||||
<define name="PITCH_GAIN" value="0.9f"/>
|
||||
|
||||
<define name="YAW_THRUST" value="0.0f"/>
|
||||
<define name="BRAKE_AILEVON" value="-0.68f"/>
|
||||
<define name="BRAKE_PITCH" value="0.0f"/>
|
||||
<define name="MAX_BRAKE_RATE" value="150"/>
|
||||
|
||||
<define name="LIMIT(X,XL,XH)" value="( ((X)>(XH)) ? (XH) : ( ((X)>(XL)) ? (X) : (XL) ) )"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<!-- Differential Aileron Depending on Brake Value -->
|
||||
<set servo="AILERON_LEFT" value="@ROLL"/>
|
||||
<set servo="AILERON_RIGHT" value="@ROLL"/>
|
||||
|
||||
<!-- Differential Thurst -->
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
|
||||
<!-- Pitch with Brake-Trim Function -->
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.7"/>
|
||||
<define name="MAX_PITCH" value="0.7"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/>
|
||||
|
||||
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="XBEE_INIT" value="ATPL2\rATRN5\rATTT80\r" type="string"/>
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.32"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.20000004768"/>
|
||||
<define name="COURSE_DGAIN" value="0.3"/>
|
||||
<define name="COURSE_PRE_BANK_CORRECTION" value="0.2"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.9" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="12000."/>
|
||||
<define name="PITCH_DGAIN" value="0"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1000."/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="11500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="600."/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
|
||||
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_PERIOD" value="1.5" unit="sec"/>
|
||||
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="50" unit="meter"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,209 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="Yapa v1">
|
||||
<description>
|
||||
YAPA + XSens + XBee
|
||||
</description>
|
||||
|
||||
<!-- ************************* FIRMWARE ************************* -->
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="yapa_2.0"/>
|
||||
<target name="sim" board="pc"/>
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="TUNE_AGRESSIVE_CLIMB"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="xbee_api">
|
||||
<configure name="MODEM_BAUD" value="B57600"/>
|
||||
</module>
|
||||
<!-- Actuators -->
|
||||
<module name="control"/>
|
||||
<!-- Sensors -->
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="xsens">
|
||||
<configure name="XSENS_PORT" value="uart0"/>
|
||||
<configure name="XSENS_BAUD" value="B230400"/>
|
||||
</module>
|
||||
|
||||
|
||||
<module name="light">
|
||||
<define name="LIGHT_LED_STROBE" value="2"/>
|
||||
<!-- <define name="LIGHT_LED_NAV" value="2"/> -->
|
||||
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
|
||||
<define name="NAV_LIGHT_MODE_DEFAULT" value="4"/>
|
||||
</module>
|
||||
<!-- <module name="digital_cam_i2c"/> -->
|
||||
<!-- <module name="ins_ppzuavimu"/> -->
|
||||
<module name="digital_cam">
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO23"/>
|
||||
</module>
|
||||
<module name="nav" type="line"/>
|
||||
</firmware>
|
||||
|
||||
<!-- ************************* ACTUATORS ************************* -->
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILERON_LEFT" no="2" min="900" neutral="1500" max="2100"/>
|
||||
<servo name="AILERON_RIGHT" no="6" min="900" neutral="1500" max="2100"/>
|
||||
<servo name="ELEVATOR" no="7" min="1900" neutral="1500" max="1100"/>
|
||||
<servo name="RUDDER" no="3" min="1175" neutral="1575" max="1975"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="BRAKE" failsafe_value="9600"/>
|
||||
<!-- both elerons up as butterfly brake -->
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="BRAKE" value="@FLAPS"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="RadOfDeg(75)"/>
|
||||
<define name="MAX_PITCH" value="RadOfDeg(45)"/>
|
||||
</section>
|
||||
|
||||
<section name="SERVO_MIXER_GAINS">
|
||||
<define name="AILERON_NEUTRAL" value="0.3f"/>
|
||||
<define name="AILERON_RATE_UP" value="1.0f"/>
|
||||
<define name="AILERON_RATE_DOWN" value="0.5f"/>
|
||||
<define name="AILERON_RATE_UP_BRAKE" value="1.0f"/>
|
||||
<define name="AILERON_RATE_DOWN_BRAKE" value="1.0f"/>
|
||||
<define name="PITCH_GAIN" value="0.9f"/>
|
||||
<define name="BRAKE_AILEVON" value="-0.7f"/>
|
||||
<define name="BRAKE_PITCH" value="0.1f"/>
|
||||
<define name="MAX_BRAKE_RATE" value="80"/>
|
||||
<define name="RUDDER_OF_AILERON" value="0.3"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<!-- Brake Rate Limiter -->
|
||||
<let var="brake_value_nofilt" value="Clip(-@BRAKE, 0, MAX_PPRZ)"/>
|
||||
<ratelimit var="brake_value" value="$brake_value_nofilt" rate_min="-MAX_BRAKE_RATE" rate_max="MAX_BRAKE_RATE"/>
|
||||
<!-- Differential Aileron Depending on Brake Value -->
|
||||
<let var="aileron_up_rate" value="(AILERON_RATE_UP * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_UP_BRAKE * $brake_value)"/>
|
||||
<let var="aileron_down_rate" value="(AILERON_RATE_DOWN * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_DOWN_BRAKE * $brake_value)"/>
|
||||
<let var="aileron_up" value="((-@ROLL) * (((float)$aileron_up_rate) / ((float)MAX_PPRZ)))"/>
|
||||
<let var="aileron_down" value="((-@ROLL) * (((float)$aileron_down_rate) / ((float)MAX_PPRZ)))"/>
|
||||
<let var="leftturn" value="(@ROLL >= 0? 0 : 1)"/>
|
||||
<let var="rightturn" value="(1 - $leftturn)"/>
|
||||
<set servo="AILERON_LEFT" value="($aileron_up * $leftturn) + ($aileron_down * $rightturn) - $brake_value*(BRAKE_AILEVON) - (MAX_PPRZ * AILERON_NEUTRAL)"/>
|
||||
<set servo="AILERON_RIGHT" value="($aileron_up * $rightturn) + ($aileron_down * $leftturn) + $brake_value*(BRAKE_AILEVON) + (MAX_PPRZ *AILERON_NEUTRAL)"/>
|
||||
<set servo="RUDDER" value="-(@YAW + @ROLL * RUDDER_OF_AILERON)"/>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<!-- Pitch with Brake-Trim Function -->
|
||||
<set servo="ELEVATOR" value="@PITCH * PITCH_GAIN - BRAKE_PITCH * $brake_value"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DEFAULT_THROTTLE" value="0.0" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.0" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* SENSORS ************************* -->
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="H_X" value="0.51562740288882"/>
|
||||
<define name="H_Y" value="-0.05707735220832"/>
|
||||
<define name="H_Z" value="0.85490967783446"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0.0" unit="rad"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="-0.0885749980807" unit="rad"/>
|
||||
</section>
|
||||
|
||||
<section name="XSENS">
|
||||
<define name="GPS_IMU_LEVER_ARM_X" value="-0.285f"/>
|
||||
<define name="GPS_IMU_LEVER_ARM_Y" value="0.0f"/>
|
||||
<define name="GPS_IMU_LEVER_ARM_Z" value="0.0f"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* GAINS ************************* -->
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.90"/>
|
||||
<define name="COURSE_DGAIN" value="0.35"/>
|
||||
<define name="COURSE_PRE_BANK_CORRECTION" value="1.0039999485"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.851999998093" unit="radians"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.6" unit="radians"/>
|
||||
<define name="PITCH_PGAIN" value="16917.2929688"/>
|
||||
<define name="PITCH_DGAIN" value="7.73400020599"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="3007.81298828"/>
|
||||
<define name="ROLL_SLEW" value="2."/>
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="11718.75"/>
|
||||
<define name="ROLL_RATE_GAIN" value="820.312011719"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.108000002801"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.6"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.9"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.158000007272" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0."/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0."/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.361000001431"/>
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="30"/>
|
||||
<define name="BLEND_END" value="15"/>
|
||||
<define name="CLIMB_THROTTLE" value="1."/>
|
||||
<define name="CLIMB_PITCH" value="0.40000000596"/>
|
||||
<define name="DESCENT_THROTTLE" value="0."/>
|
||||
<define name="DESCENT_PITCH" value="-0.10000000149"/>
|
||||
<define name="CLIMB_NAV_RATIO" value="0.800000011921"/>
|
||||
<define name="DESCENT_NAV_RATIO" value="0.834999978542"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* MISC ************************* -->
|
||||
|
||||
<section name="BAT">
|
||||
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="8." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="XBEE_INIT" value="ATPL4\rATRN5\rATTT80\r" type="string"/>
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
<define name="COMMAND_ROLL_TRIM" value="180"/>
|
||||
<define name="COMMAND_PITCH_TRIM" value="-194."/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_PERIOD" value="1.5" unit="sec"/>
|
||||
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="50" unit="meter"/>
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -1,156 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Funjet Multiplex (http://www.multiplex-rc.de/), Jeti ECO 25
|
||||
Tiny 2.11 board (http://wiki.paparazziuav.org/wiki/Tiny_v2)
|
||||
PerkinElmer TPS334 IR Sensors
|
||||
Tilted infrared sensor (http://wiki.paparazziuav.org/wiki/Image:Tiny_v2_1_Funjet.jpg)
|
||||
XBee modem with AT firmware
|
||||
LEA 5H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Delta Wing">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="tiny_2.11"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="gps_passthrough"/>
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="tiny_2.11"/>
|
||||
</firmware>
|
||||
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="2" min="1900" neutral="1521" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="6" min="1100" neutral="1510" max="1900"/>
|
||||
</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.45"/>
|
||||
<define name="AILEVON_ELEVATOR_RATE" value="0.8"/>
|
||||
</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="50" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="35" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="-1"/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1"/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.5"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="-1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</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="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.06"/> <!-- -0.024 -->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.35"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.023"/> <!-- -0.012 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.06"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.9"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.70" unit="rad"/> <!-- 0.5 -->
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="ROLL_PGAIN" value="6600."/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="PITCH_PGAIN" value="5500."/>
|
||||
<define name="PITCH_DGAIN" value="0.4"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="2400"/>
|
||||
</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.5"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,150 +0,0 @@
|
||||
<airframe name="DEMO">
|
||||
|
||||
<makefile>
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
FLASH_MODE = IAP
|
||||
|
||||
|
||||
#
|
||||
# simple emtpy demo
|
||||
#
|
||||
demo1.ARCHDIR = $(ARCH)
|
||||
|
||||
demo1.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\"
|
||||
demo1.srcs = main_demo1.c
|
||||
|
||||
#
|
||||
# hardware init ( pll ), system time and LEDs
|
||||
#
|
||||
demo2.ARCHDIR = $(ARCH)
|
||||
|
||||
demo2.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\"
|
||||
demo2.srcs = main_demo2.c
|
||||
|
||||
demo2.CFLAGS += -DPERIODIC_FREQUENCY='100.'
|
||||
demo2.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
demo2.CFLAGS += -DUSE_LED
|
||||
|
||||
#
|
||||
# UART (interrupts) and formated ascii printing
|
||||
#
|
||||
demo3.ARCHDIR = $(ARCH)
|
||||
|
||||
demo3.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\"
|
||||
demo3.srcs = main_demo3.c
|
||||
|
||||
demo3.CFLAGS += -DPERIODIC_FREQUENCY='10.'
|
||||
demo3.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
demo3.CFLAGS += -DUSE_LED
|
||||
|
||||
demo3.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
demo3.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
|
||||
demo3.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
#
|
||||
# DOWNLINK : send formated messages according to messages.xml description
|
||||
# requires "link" to run on the other side of the serial link
|
||||
#
|
||||
demo4.ARCHDIR = $(ARCH)
|
||||
|
||||
demo4.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\"
|
||||
demo4.srcs = main_demo4.c
|
||||
|
||||
demo4.CFLAGS += -DPERIODIC_FREQUENCY='100.'
|
||||
demo4.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
demo4.CFLAGS += -DUSE_LED
|
||||
|
||||
demo4.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
demo4.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
|
||||
demo4.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
demo4.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=uart0
|
||||
demo4.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
#
|
||||
# DATALINK : receives datalink messages. demonstrates the "settings" service
|
||||
# which lets you adjust variables described in the settings.xml file
|
||||
# IvySendMsg("1ME RAW_DATALINK 144 SETTING;0;0;%d", foo_value);
|
||||
#
|
||||
demo5.ARCHDIR = $(ARCH)
|
||||
|
||||
demo5.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\"
|
||||
demo5.srcs = main_demo5.c
|
||||
|
||||
demo5.CFLAGS += -DPERIODIC_FREQUENCY='100.'
|
||||
demo5.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
demo5.CFLAGS += -DUSE_LED
|
||||
|
||||
demo5.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
demo5.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
|
||||
demo5.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
demo5.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=uart0
|
||||
demo5.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
demo5.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=uart0
|
||||
|
||||
|
||||
#
|
||||
# Serial link over USB
|
||||
#
|
||||
demo6.ARCHDIR = $(ARCH)
|
||||
|
||||
demo6.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\"
|
||||
demo6.srcs = main_demo6.c
|
||||
|
||||
demo6.CFLAGS += -DPERIODIC_FREQUENCY='100.'
|
||||
demo6.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
demo6.CFLAGS += -DUSE_LED
|
||||
|
||||
demo6.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
demo6.CFLAGS += -DUSE_USB_SERIAL
|
||||
#demo6.LDFLAGS += -L$(SRC_ARCH)/lpcusb -lusbstack
|
||||
demo6.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c $(SRC_ARCH)/lpcusb/usbinit.c
|
||||
demo6.srcs += $(SRC_ARCH)/usb_ser_hw.c
|
||||
|
||||
demo6.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=usb_serial
|
||||
demo6.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
//demo6.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=uart0
|
||||
|
||||
|
||||
|
||||
#
|
||||
#
|
||||
#
|
||||
test_spk.ARCHDIR = $(ARCH)
|
||||
|
||||
test_spk.CFLAGS += -DBOARD_CONFIG=\"booz2_board_usb.h\"
|
||||
test_spk.srcs = main_test_spk.c
|
||||
|
||||
test_spk.CFLAGS += -DPERIODIC_FREQUENCY='512.'
|
||||
test_spk.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
test_spk.CFLAGS += -DUSE_LED
|
||||
|
||||
test_spk.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
test_spk.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DUSE_USB_SERIAL
|
||||
test_spk.CFLAGS += -DDOWNLINK_DEVICE=usb_serial -DPPRZ_UART=usb_serial -DDATALINK=PPRZ
|
||||
test_spk.srcs += modules/datalink/downlink.c $(SRC_ARCH)/usb_ser_hw.c modules/datalink/pprz_transport.c
|
||||
test_spk.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbcontrol.c
|
||||
test_spk.srcs += $(SRC_ARCH)/lpcusb/usbstdreq.c $(SRC_ARCH)/lpcusb/usbinit.c
|
||||
|
||||
test_spk.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B115200
|
||||
test_spk.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
</makefile>
|
||||
|
||||
</airframe>
|
||||
@@ -1,190 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="Easy Glider Tiny 0.99">
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1290" neutral="1290" max="1810"/>
|
||||
<servo name="ELEVATOR" no="1" min="1770" neutral="1457" max="970"/>
|
||||
<servo name="RUDDER" no="3" min="1040" neutral="1595" max="2040"/>
|
||||
<servo name="AILERON_LEFT" no="4" min="2000" neutral="1508" max="1000"/>
|
||||
<servo name="AILERON_RIGHT" no="5" min="2000" neutral="1527" max="1000"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="BRAKE" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="BRAKE" value="@GAIN1"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="MIXER">
|
||||
<define name="AILERON_DIFF" value="0.66"/>
|
||||
<define name="COMBI_SWITCH" value="1.0"/>
|
||||
|
||||
<define name="BRAKE_DEFLECTION_TIME" value="2.0" /> <!-- seconds -->
|
||||
<define name="MAX_BRAKE_RATE" value="(MAX_PPRZ / (60 * BRAKE_DEFLECTION_TIME ))" />
|
||||
<define name="BRAKE_AILEVON" value="-0.68f"/>
|
||||
<define name="BRAKE_PITCH" value="0.01f"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<ratelimit var="brake_value" value="Clip(@BRAKE, 0, MAX_PPRZ)" rate_min="-MAX_BRAKE_RATE" rate_max="MAX_BRAKE_RATE" />
|
||||
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="ELEVATOR" value="@PITCH + BRAKE_PITCH * $brake_value"/>
|
||||
<set servo="RUDDER" value="@YAW + @ROLL*COMBI_SWITCH"/>
|
||||
|
||||
<let var="roll" value="@ROLL"/>
|
||||
<set servo="AILERON_LEFT" value="($roll > 0 ? AILERON_DIFF : 1) * $roll + BRAKE_AILEVON * $brake_value"/>
|
||||
<set servo="AILERON_RIGHT" value="($roll > 0 ? 1 : AILERON_DIFF) * $roll + BRAKE_AILEVON * $brake_value"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.7"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="1"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="0.75"/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="0.75"/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.5"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="18" unit="deg"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1.0"/>
|
||||
<define name="CORRECTION_DOWN" value="1.0"/>
|
||||
<define name="CORRECTION_LEFT" value="1.0"/>
|
||||
<define name="CORRECTION_RIGHT" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.03"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.55"/>
|
||||
<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="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.10800004005"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.6" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="15184.5644531"/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1250"/>
|
||||
|
||||
<define name="ROLL_SLEW" value="0.1"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.3"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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"/>
|
||||
</section>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="tiny_0.99"/>
|
||||
|
||||
<define name="AGR_CLIMB" />
|
||||
<define name="LOITER_TRIM" />
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_BAUD" value="B9600"/>
|
||||
</module>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board -->
|
||||
<module name="control"/>
|
||||
<!-- Sensors -->
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="tiny_0.99" />
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="adc_generic">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_7"/> <!-- current sensor -->
|
||||
</module>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
</airframe>
|
||||
@@ -1,164 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Multiplex EasyStar, using rudder
|
||||
TWOG v1 board
|
||||
Tilted infrared sensor
|
||||
XBee 2.4GHz modem in transparent mode
|
||||
-->
|
||||
|
||||
<airframe name="EasyStar TWOGv1">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="twog_1.0"/>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="twog_1.0"/>
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="7" min="1120" neutral="1120" max="1920"/>
|
||||
<servo name="ELEVATOR" no="3" min="1100" neutral="1515" max="1900"/>
|
||||
<servo name="RUDDER" no="4" min="950" neutral="1440" max="2050"/>
|
||||
</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="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
</rc_commands>
|
||||
|
||||
<command_laws>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="RUDDER" value="@ROLL"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="50" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="40" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="510"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="500"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="0.7"/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="0.7"/>
|
||||
<define name="VERTICAL_CORRECTION" value="1."/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="-5.3" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="-3" unit="deg"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000" unit="mA"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="8.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="8.5" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="9.5" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.5" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
|
||||
<define name="CARROT" value="4." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(2.0*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
<define name="NO_XBEE_API_INIT" value="TRUE"/>
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="100."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.0" unit="volt"/>
|
||||
<!-- outer loop -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.075" unit="(m/s)/m"/>
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="4." unit="m/s"/>
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.4" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.8" unit="%"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500" unit="pprz_t"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1000" unit="pprz_t"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.02" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05" unit="rad/(m/s)"/>
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.125"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.025"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(25)"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="RadOfDeg(-25)"/>
|
||||
<define name="THROTTLE_SLEW" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.7"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="25" unit="deg"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-25" unit="deg"/>
|
||||
<define name="PITCH_PGAIN" value="20000."/>
|
||||
<define name="PITCH_DGAIN" value="1.5"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="2500"/>
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7400"/>
|
||||
<define name="ROLL_RATE_GAIN" value="200"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="RadOfDeg(18)"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="RadOfDeg(-20)"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0.4" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="15" unit="deg"/>
|
||||
<define name="DEFAULT_PITCH" value="0" unit="deg"/>
|
||||
<define name="HOME_RADIUS" value="90" unit="m"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,187 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Funjet Multiplex (http://www.multiplex-rc.de/), Jeti ECO 25
|
||||
Tiny 2.11 board (http://wiki.paparazziuav.org/wiki/Tiny_v2)
|
||||
PerkinElmer TPS334 IR Sensors
|
||||
Tilted infrared sensor (http://wiki.paparazziuav.org/wiki/Image:Tiny_v2_1_Funjet.jpg)
|
||||
XBee modem with AT firmware
|
||||
LEA 5H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Funjet Tiny 2.11">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="tiny_2.11"/>
|
||||
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<define name="USE_JOYSTICK" value="TRUE"/>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<module name="control"/>
|
||||
<!-- Sensors -->
|
||||
<module name="gps" type="ublox"/>
|
||||
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="gps_passthrough"/>
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="tiny_2.11"/>
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="2" min="1900" neutral="1521" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="6" min="1100" neutral="1510" max="1900"/>
|
||||
</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.45"/>
|
||||
<define name="AILEVON_ELEVATOR_RATE" value="0.8"/>
|
||||
</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="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="-1"/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1"/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.5"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="-1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</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="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.06"/> <!-- -0.024 -->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.35"/>
|
||||
<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="-1200"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.023"/> <!-- -0.012 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.06"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.9"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.70" unit="rad"/> <!-- 0.5 -->
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="ROLL_PGAIN" value="6600."/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="PITCH_PGAIN" value="5500."/>
|
||||
<define name="PITCH_DGAIN" value="0.4"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="2400"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.35"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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.5"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,195 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Funjet Multiplex (http://www.multiplex-rc.de/), Jeti ECO 25
|
||||
Tiny 2.11 board (http://wiki.paparazziuav.org/wiki/Tiny_v2)
|
||||
PerkinElmer TPS334 IR Sensors
|
||||
Tilted infrared sensor (http://wiki.paparazziuav.org/wiki/Image:Tiny_v2_1_Funjet.jpg)
|
||||
XBee modem with AT firmware
|
||||
LEA 5H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Funjet Tiny 2.11">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="tiny_2.11"/>
|
||||
|
||||
<define name="AGR_CLIMB"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<define name="USE_JOYSTICK" value="TRUE"/>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<module name="control"/>
|
||||
<!-- Sensors -->
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="ins" type="gps_passthrough"/>
|
||||
<module name="navigation"/>
|
||||
</firmware>
|
||||
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="tiny_2.11"/>
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="60">
|
||||
<module name="cam_point">
|
||||
<define name="POINT_CAM_YAW_PITCH" value="1"/>
|
||||
<define name="SHOW_CAM_COORDINATES" value="1"/>
|
||||
</module>
|
||||
<module name="digital_cam">
|
||||
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO23"/>
|
||||
</module>
|
||||
<module name="sys_mon"/>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="2" min="1900" neutral="1521" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="6" min="1100" neutral="1510" max="1900"/>
|
||||
</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.45"/>
|
||||
<define name="AILEVON_ELEVATOR_RATE" value="0.8"/>
|
||||
</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="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="-1"/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1"/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.5"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="-1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</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="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.06"/> <!-- -0.024 -->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.45"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.35"/>
|
||||
<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="-1200"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.023"/> <!-- -0.012 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.01"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.06"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.9"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.70" unit="rad"/> <!-- 0.5 -->
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="ROLL_PGAIN" value="6600."/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="PITCH_PGAIN" value="5500."/>
|
||||
<define name="PITCH_DGAIN" value="0.4"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="2400"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.35"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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.5"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,48 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
|
||||
Connects a microSD card to the SPI port of the Paparazzi Tiny. Keep cables
|
||||
short, microSD card can be directly soldered to Molex cable. For now only
|
||||
non SDHC SD cards (<= 2GB) are supported. martinmm@pfump.org
|
||||
|
||||
microSD TinyV2 SPI J3
|
||||
8 nc
|
||||
7 DO 5 MISO
|
||||
6 GND 1 GND
|
||||
5 CLK 7 SCK
|
||||
4 Vcc 2 +3V3
|
||||
3 DI 4 MOSI
|
||||
2 CS 3 SSEL
|
||||
1 nc
|
||||
|
||||
Looking onto the gold plated connector side of the microSD card:
|
||||
|
||||
###############
|
||||
I 8
|
||||
I 7
|
||||
I 6
|
||||
I 5
|
||||
I 4
|
||||
I 3
|
||||
I 2
|
||||
I 1
|
||||
###### ##
|
||||
\ I \
|
||||
## ##
|
||||
|
||||
-->
|
||||
|
||||
<airframe name="Logger">
|
||||
|
||||
<firmware name="logger">
|
||||
<target name="ap" board="tiny_2.11" >
|
||||
<configure name="LOG_MSG_FMT" value="LOG_PPRZ"/>
|
||||
<configure name="SPI_CHANNEL" value="1" />
|
||||
<configure name="UART0_BAUD" value="B9600" />
|
||||
<configure name="UART1_BAUD" value="B9600" />
|
||||
</target>
|
||||
</firmware>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -1,35 +0,0 @@
|
||||
<airframe name="Turntable">
|
||||
|
||||
<makefile>
|
||||
ARCH=lpc21
|
||||
|
||||
FLASH_MODE = IAP
|
||||
|
||||
MB=firmwares/motor_bench
|
||||
|
||||
main.ARCHDIR = $(ARCH)
|
||||
|
||||
# uncomment the next line to set the number of steps the encoder has (default 256)
|
||||
#main.CFLAGS += -DNB_STEP=256
|
||||
|
||||
main.CFLAGS += -DBOARD_CONFIG=\"boards/olimex_lpc_h2148.h\" -I$(MB)
|
||||
main.CFLAGS += -DPERIPHERALS_AUTO_INIT
|
||||
main.srcs = $(MB)/main_turntable.c
|
||||
main.srcs += $(SRC_ARCH)/armVIC.c
|
||||
main.srcs += mcu.c
|
||||
main.srcs += $(SRC_ARCH)/mcu_arch.c
|
||||
|
||||
main.CFLAGS += -DUSE_LED
|
||||
main.CFLAGS += -DPERIODIC_FREQUENCY='512.' -DSYS_TIME_LED=1
|
||||
main.srcs += mcu_periph/sys_time.c $(MB)/turntable_systime.c
|
||||
|
||||
main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200
|
||||
main.srcs += mcu_periph/uart.c
|
||||
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=uart0
|
||||
|
||||
main.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
</makefile>
|
||||
|
||||
</airframe>
|
||||
@@ -1,36 +0,0 @@
|
||||
<airframe name="TurntableUsb">
|
||||
|
||||
<makefile>
|
||||
ARCH=lpc21
|
||||
|
||||
FLASH_MODE = IAP
|
||||
|
||||
MB=firmwares/motor_bench
|
||||
|
||||
main.ARCHDIR = $(ARCH)
|
||||
|
||||
# uncomment the next line to set the number of steps the encoder has (default 256)
|
||||
#main.CFLAGS += -DNB_STEP=256
|
||||
|
||||
main.CFLAGS += -DBOARD_CONFIG=\"boards/olimex_lpc_h2148.h\" -I$(MB)
|
||||
main.CFLAGS += -DPERIPHERALS_AUTO_INIT
|
||||
main.srcs = $(MB)/main_turntable.c
|
||||
main.srcs += $(SRC_ARCH)/armVIC.c
|
||||
main.srcs += mcu.c
|
||||
main.srcs += $(SRC_ARCH)/mcu_arch.c
|
||||
|
||||
main.CFLAGS += -DUSE_LED
|
||||
main.CFLAGS += -DPERIODIC_FREQUENCY='512.' -DSYS_TIME_LED=1
|
||||
main.srcs += mcu_periph/sys_time.c $(MB)/turntable_systime.c
|
||||
|
||||
main.CFLAGS += -DUSE_USB_SERIAL
|
||||
main.srcs += $(SRC_ARCH)/usb_ser_hw.c
|
||||
main.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c
|
||||
main.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c
|
||||
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=usb_serial
|
||||
|
||||
main.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
</makefile>
|
||||
|
||||
</airframe>
|
||||
@@ -1,187 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Twinjet Multiplex (http://www.multiplex-rc.de/)
|
||||
Twog v1 board (http://wiki.paparazziuav.org/wiki/Twog_v1)
|
||||
PerkinElmer TPS334 IR Sensors
|
||||
Aligned infrared sensor
|
||||
XBee modem with AT firmware
|
||||
LEA 5H GPS
|
||||
-->
|
||||
|
||||
<airframe name="Twinjet">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="twog_1.0">
|
||||
<define name="UBX_EXTERNAL"/>
|
||||
</target>
|
||||
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="navigation"/>
|
||||
<module name="ins" type="gps_passthrough"/>
|
||||
<define name="USE_JOYSTICK" value="TRUE"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="twog_1.0" />
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="twog_extra_dl"/>
|
||||
<module name="adc_generic">
|
||||
<flag name="ADC_CHANNEL_GENERIC1" value="ADC_3"/>
|
||||
<flag name="ADC_CHANNEL_GENERIC2" value="ADC_5"/>
|
||||
<flag name="USE_ADC_3"/>
|
||||
<flag name="USE_ADC_5"/>
|
||||
</module>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILEVON_RIGHT" no="1" min="1230" neutral="1710" max="2100"/>
|
||||
<servo name="AILEVON_LEFT" no="2" min="2120" neutral="1785" max="1300"/>
|
||||
<servo name="CHAN3" no="3" min="2120" neutral="1785" max="1300"/>
|
||||
<servo name="CHAN4" no="4" min="2120" neutral="1785" max="1300"/>
|
||||
<servo name="CHAN5" no="5" min="2120" neutral="1785" max="1300"/>
|
||||
<servo name="CHAN6" no="6" min="2120" neutral="1785" max="1300"/>
|
||||
<servo name="CHAN7" no="7" min="2120" neutral="1785" max="1300"/>
|
||||
</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="1.00"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
|
||||
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
|
||||
<set servo="AILEVON_LEFT" value="$aileron + $elevator"/>
|
||||
<set servo="AILEVON_RIGHT" value="-$aileron + $elevator"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.6"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_ALIGNED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="5" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="10" unit="deg"/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="1."/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1."/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.25"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.9"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.53" unit="rad"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="6000."/>
|
||||
<define name="PITCH_DGAIN" value="0."/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="0"/>
|
||||
|
||||
<!-- roll rate loop -->
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="7500"/>
|
||||
<define name="ROLL_RATE_GAIN" value="1500"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.05"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.40"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value=".3"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.8"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="2000"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-1500"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.15" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.008"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.14"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="75."/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="1000"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="6.3" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="7.0" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="7.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="2" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE+0.05" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="50" unit="m"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="CLIMB_THROTTLE" value="0.65"/><!-- Throttle for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.1"/><!-- Throttle for Aggressive Decent -->
|
||||
<define name="CLIMB_PITCH" value="0.2"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="10"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,201 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- Twinstar II, 2x Jeti 18 advance plus, AXI 2212/26
|
||||
Graupner C19 receiver
|
||||
TWOG V1 board
|
||||
PerkinElmer TPS334 IR Sensors
|
||||
Tilted infrared sensor
|
||||
XBee modem with AT firmware
|
||||
LEA 4P GPS (set to POSLLH)
|
||||
-->
|
||||
|
||||
<airframe name="Twinstar">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="twog_1.0"/>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
|
||||
<module name="radio_control" type="ppm"/>
|
||||
<module name="telemetry" type="transparent"/>
|
||||
<module name="control"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="ins" type="gps_passthrough"/>
|
||||
<module name="navigation"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="tunnel" board="twog_1.0"/>
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<module name="infrared_adc"/>
|
||||
<module name="ahrs_infrared"/>
|
||||
</modules>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1000" neutral="1000" max="2000"/>
|
||||
<servo name="AILERON_LEFT" no="1" min="1050" neutral="1480" max="1900"/>
|
||||
<servo name="ELEVATOR" no="2" min="1750" neutral="1530" max="1250"/>
|
||||
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/>
|
||||
<servo name="AILERON_RIGHT" no="4" min="1200" neutral="1610" max="2000"/>
|
||||
<servo name="FWHEEL" no="5" min="1900" neutral="1470" max="1100"/>
|
||||
<servo name="HATCH" no="6" min="1000" neutral="1500" max="2000"/>
|
||||
<servo name="CAM_ROLL" no="7" min="1000" neutral="1500" max="2000"/>
|
||||
<servo name="CAM_PITCH" no="8" min="1000" neutral="1500" max="2000"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="HATCH" failsafe_value="0"/>
|
||||
<axis name="CAM_ROLL" failsafe_value="0"/>
|
||||
<axis name="CAM_PITCH" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="HATCH" value="@CALIB"/>
|
||||
</rc_commands>
|
||||
|
||||
<auto_rc_commands>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
</auto_rc_commands>
|
||||
|
||||
<section name="MIXER">
|
||||
<define name="AILERON_DIFF" value="0.8"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<set servo="MOTOR" value="@THROTTLE"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
<let var="roll" value="@ROLL"/>
|
||||
<set servo="AILERON_LEFT" value="($roll > 0 ? AILERON_DIFF : 1) * $roll"/>
|
||||
<set servo="AILERON_RIGHT" value="($roll > 0 ? 1 : AILERON_DIFF) * $roll"/>
|
||||
<set servo="RUDDER" value="@YAW"/>
|
||||
<set servo="FWHEEL" value="@YAW"/>
|
||||
<set servo="HATCH" value="@HATCH"/>
|
||||
<set servo="CAM_ROLL" value="@CAM_ROLL"/>
|
||||
<set servo="CAM_PITCH" value="@CAM_PITCH"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.85"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="INFRARED" prefix="IR_">
|
||||
<define name="ADC_IR1_NEUTRAL" value="512"/>
|
||||
<define name="ADC_IR2_NEUTRAL" value="512"/>
|
||||
<define name="ADC_TOP_NEUTRAL" value="512"/>
|
||||
|
||||
<define name="CORRECTION_UP" value="1."/>
|
||||
<define name="CORRECTION_DOWN" value="1."/>
|
||||
<define name="CORRECTION_LEFT" value="1."/>
|
||||
<define name="CORRECTION_RIGHT" value="1."/>
|
||||
|
||||
<define name="LATERAL_CORRECTION" value="-1"/>
|
||||
<define name="LONGITUDINAL_CORRECTION" value="1"/>
|
||||
<define name="VERTICAL_CORRECTION" value="1.7"/>
|
||||
|
||||
<define name="HORIZ_SENSOR_TILTED" value="1"/>
|
||||
<define name="IR1_SIGN" value="1"/>
|
||||
<define name="IR2_SIGN" value="-1"/>
|
||||
<define name="TOP_SIGN" value="1"/>
|
||||
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="MINIMUM_AIRSPEED" value="10." unit="m/s"/>
|
||||
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="MAXIMUM_AIRSPEED" value="18." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
|
||||
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="120."/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.06"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- 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="-1200"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.023"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05"/>
|
||||
|
||||
<!-- auto pitch inner loop -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.06"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="1.0"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.60" 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_PGAIN" value="6000."/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="PITCH_PGAIN" value="9000."/>
|
||||
<define name="PITCH_DGAIN" value="1700."/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="1500"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.35"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.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.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="100" unit="m"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,81 +0,0 @@
|
||||
<airframe name="DEMO">
|
||||
|
||||
<makefile>
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
FLASH_MODE = IAP
|
||||
|
||||
|
||||
WIND_TUNNEL=wind_tunnel
|
||||
|
||||
ap.ARCHDIR = $(ARCH)
|
||||
|
||||
ap.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\" -I$(WIND_TUNNEL)
|
||||
ap.srcs = $(WIND_TUNNEL)/main.c
|
||||
|
||||
ap.CFLAGS += -DPERIODIC_FREQUENCY='10.'
|
||||
ap.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
ap.CFLAGS += -DUSE_LED
|
||||
|
||||
ap.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
ap.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
|
||||
ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
ap.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=uart0
|
||||
ap.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
ap.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=uart0
|
||||
#ap.srcs += $(BOOZ)/booz_datalink.c
|
||||
|
||||
ap.srcs += $(WIND_TUNNEL)/wt_servo.c
|
||||
|
||||
|
||||
#
|
||||
#
|
||||
#
|
||||
|
||||
MB=motor_bench
|
||||
|
||||
mb.ARCHDIR = $(ARCH)
|
||||
|
||||
mb.CFLAGS += -DBOARD_CONFIG=\"conf_demo.h\" -I$(WIND_TUNNEL) -I$(MB)
|
||||
mb.srcs = $(WIND_TUNNEL)/main_mb.c
|
||||
|
||||
mb.CFLAGS += -DPERIODIC_FREQUENCY='100.'
|
||||
mb.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
|
||||
|
||||
mb.CFLAGS += -DUSE_LED
|
||||
|
||||
mb.srcs += $(SRC_ARCH)/armVIC.c
|
||||
|
||||
mb.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
|
||||
mb.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
mb.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=uart0
|
||||
mb.srcs += modules/datalink/downlink.c modules/datalink/pprz_transport.c
|
||||
|
||||
mb.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=uart0
|
||||
|
||||
mb.srcs += $(WIND_TUNNEL)/wt_servo.c
|
||||
|
||||
mb.CFLAGS += -DUSE_TWI_CONTROLLER
|
||||
mb.CFLAGS += -DI2C_SCLL=100 -DI2C_SCLH=100
|
||||
mb.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c $(MB)/mb_twi_controller_mkk.c
|
||||
|
||||
mb.CFLAGS += -DMB_TACHO
|
||||
mb.srcs += $(MB)/mb_tacho.c
|
||||
|
||||
#mb.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1
|
||||
#mb.srcs += $(SRC_ARCH)/adc_hw.c
|
||||
#mb.srcs += $(MB)/mb_current.c
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
</makefile>
|
||||
|
||||
</airframe>
|
||||
@@ -1,36 +0,0 @@
|
||||
#
|
||||
# booz_1.0.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Booz
|
||||
#
|
||||
ARCH=lpc21
|
||||
BOARD=booz
|
||||
BOARD_VERSION=1.0
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
#
|
||||
#
|
||||
# some default values shared between different firmwares
|
||||
#
|
||||
#
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= 1
|
||||
BARO_LED ?= 2
|
||||
AHRS_ALIGNER_LED ?= 3
|
||||
GPS_LED ?= 4
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
RADIO_CONTROL_LINK = UART0
|
||||
|
||||
|
||||
MODEM_PORT ?= UART1
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART0
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
@@ -1,41 +0,0 @@
|
||||
#
|
||||
# hb_1.1.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/HB_v1
|
||||
#
|
||||
ARCH=lpc21
|
||||
BOARD=hb
|
||||
BOARD_VERSION=1.1
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
#
|
||||
#
|
||||
# some default values shared between different firmwares
|
||||
#
|
||||
#
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= 2
|
||||
SYS_TIME_LED ?= 1
|
||||
|
||||
|
||||
RADIO_CONTROL_LINK = UART0
|
||||
|
||||
#
|
||||
# default UART configuration
|
||||
#
|
||||
MODEM_PORT ?= UART0
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART1
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
@@ -1,42 +0,0 @@
|
||||
#
|
||||
# hbmini_1.0.makefile
|
||||
#
|
||||
# prototype for HBMini board
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=hbmini
|
||||
BOARD_VERSION=1.0
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= none
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART0
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART1
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
# All targets on the HBMini board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
|
||||
@@ -1,23 +0,0 @@
|
||||
#
|
||||
# logom_2.6.makefile
|
||||
#
|
||||
# http://www.sparkfun.com/products/10216
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=logom
|
||||
BOARD_VERSION=2.6
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
|
||||
# All targets on the board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
|
||||
@@ -1,42 +0,0 @@
|
||||
#
|
||||
# navgo_1.0.makefile
|
||||
#
|
||||
# prototype for NavGo board
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=navgo
|
||||
BOARD_VERSION=1.0
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= 1
|
||||
BARO_LED ?= 2
|
||||
AHRS_ALIGNER_LED ?= 3
|
||||
GPS_LED ?= 4
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART1
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART0
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
# All targets on the NavGo board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
|
||||
@@ -1,13 +0,0 @@
|
||||
#
|
||||
# sdlog_1.0.makefile
|
||||
#
|
||||
# Paparazzi SD Logger
|
||||
#
|
||||
|
||||
|
||||
include $(PAPARAZZI_SRC)/conf/boards/tiny_2.11.makefile
|
||||
|
||||
BOARD=sdlog
|
||||
BOARD_VERSION=1.0
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
@@ -1,49 +0,0 @@
|
||||
#
|
||||
# tiny_0.99.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Tiny_v0.99
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=tiny
|
||||
BOARD_VERSION=0.99
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
# default flash mode is via usb bootloader
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= none
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART0
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART1
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
|
||||
#
|
||||
# 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_4015
|
||||
|
||||
# All targets on the TINY board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
@@ -1,53 +0,0 @@
|
||||
#
|
||||
# tiny_1.1.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Tiny_v1.1
|
||||
#
|
||||
ARCH=lpc21
|
||||
|
||||
|
||||
BOARD=tiny
|
||||
BOARD_VERSION=1.1
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
# default flash mode is via usb bootloader
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= none
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
TUNNEL_RX_LED ?= 1
|
||||
TUNNEL_TX_LED ?= 2
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART0
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART1
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
#
|
||||
# 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_4015
|
||||
|
||||
|
||||
# All targets on the TINY board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
@@ -1,49 +0,0 @@
|
||||
#
|
||||
# tiny_2.1.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Tiny_v2
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=tiny
|
||||
BOARD_VERSION=2.1
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
# default flash mode is via usb bootloader
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= 2
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART1
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART0
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
#
|
||||
# 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_4017
|
||||
|
||||
# All targets on the TINY board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
@@ -1,52 +0,0 @@
|
||||
#
|
||||
# tiny_2.11.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Tiny_v2
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=tiny
|
||||
BOARD_VERSION=2.11
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
|
||||
# default flash mode is via usb bootloader
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= 2
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART1
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART0
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
|
||||
#
|
||||
# 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_4017
|
||||
|
||||
|
||||
# All targets on the TINY board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
@@ -1,50 +0,0 @@
|
||||
#
|
||||
# twog_1.0.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Twog_v1
|
||||
#
|
||||
|
||||
ARCH=lpc21
|
||||
|
||||
BOARD=twog
|
||||
BOARD_VERSION=1.0
|
||||
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
# default flash mode is via usb bootloader
|
||||
FLASH_MODE ?= IAP
|
||||
|
||||
|
||||
LPC21ISP_BAUD = 38400
|
||||
LPC21ISP_XTAL = 12000
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= 2
|
||||
SYS_TIME_LED ?= none
|
||||
|
||||
|
||||
#
|
||||
# default uart settings
|
||||
#
|
||||
MODEM_PORT ?= UART1
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART0
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
#
|
||||
# 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_4017
|
||||
|
||||
|
||||
# All targets on the TINY board run on the same processor achitecture
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user