mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-23 21:36:28 +08:00
Merge branch 'master' into ahrs_int_cmpl_quat_correction_scaling
for testing and conflict resolution
This commit is contained in:
@@ -54,6 +54,7 @@
|
||||
/sw/ground_segment/cockpit/gtk_save_settings.ml
|
||||
/sw/ground_segment/cockpit/gtk_setting_time.ml
|
||||
/sw/ground_segment/cockpit/gcs
|
||||
/sw/ground_segment/cockpit/gcs.opt
|
||||
/sw/ground_segment/cockpit/gtk_strip.ml
|
||||
/sw/ground_segment/cockpit/ant_track
|
||||
/sw/ground_segment/cockpit/compass
|
||||
@@ -80,6 +81,7 @@
|
||||
/sw/ground_segment/tmtc/dia
|
||||
/sw/ground_segment/tmtc/ivy2udp
|
||||
/sw/ground_segment/tmtc/server
|
||||
/sw/ground_segment/tmtc/server.opt
|
||||
/sw/ground_segment/tmtc/diadec
|
||||
/sw/ground_segment/tmtc/ivy_serial_bridge
|
||||
/sw/ground_segment/tmtc/GSM/SMS_GS
|
||||
|
||||
+77
-2
@@ -1,11 +1,86 @@
|
||||
Paparazzi 4.9 - development branch
|
||||
==================================
|
||||
Paparazzi 5.0.0_stable
|
||||
======================
|
||||
|
||||
Stable version release
|
||||
|
||||
General
|
||||
-------
|
||||
|
||||
- STM libs completely replaced by libopencm3
|
||||
- [gcc-arm-embedded] (https://launchpad.net/gcc-arm-embedded) is the new recommended toolchain
|
||||
- Use findlib (ocamlfind) for ocaml packages. Faster build.
|
||||
[#274] (https://github.com/paparazzi/paparazzi/pull/274)
|
||||
- Building/Running the groundsegment on an ARM (e.g. RaspberryPi).
|
||||
- Input2ivy uses SDL for joysticks (cross-platform, works on OSX as well now)
|
||||
[#220] (https://github.com/paparazzi/paparazzi/pull/220)
|
||||
- Option to change text papget color using a combobox
|
||||
[#194] (https://github.com/paparazzi/paparazzi/pull/194)
|
||||
- Redundant communications
|
||||
[#429] (https://github.com/paparazzi/paparazzi/pull/429)
|
||||
- Log also contains includes like procedures now, so replay if these missions is possible.
|
||||
[#227] (https://github.com/paparazzi/paparazzi/issues/227)
|
||||
- Paparazzi Center
|
||||
- New simulation launcher with dialog and detection of available ones.
|
||||
[#354] (https://github.com/paparazzi/paparazzi/pull/354)
|
||||
- Checkbox to print extra configuration information during build.
|
||||
- GCS:
|
||||
- Fix panning with mouse if there are no background tiles.
|
||||
[#9] (https://github.com/paparazzi/paparazzi/issues/9)
|
||||
- Higher zoom level for maps.
|
||||
[#277] (https://github.com/paparazzi/paparazzi/issues/277)
|
||||
|
||||
Hardware support
|
||||
----------------
|
||||
|
||||
- initial support for STM32F4
|
||||
- Apogee autopilot
|
||||
- KroozSD autopilot
|
||||
- Parrot AR Drone 2 support: raw and sdk versions
|
||||
- CH Robotics UM6 IMU/AHRS
|
||||
- GPS/INS XSens Mti-G support
|
||||
- GPS Sirf support
|
||||
- GPS Skytraq now usable for fixedwings as well
|
||||
[#167] (https://github.com/paparazzi/paparazzi/issues/167)
|
||||
- Mikrokopter V2 BLDC
|
||||
[#377] (https://github.com/paparazzi/paparazzi/pull/377)
|
||||
- PX4Flow sensor
|
||||
[#379] (https://github.com/paparazzi/paparazzi/pull/379)
|
||||
- Dropped AVR support
|
||||
|
||||
Airborne
|
||||
--------
|
||||
|
||||
- State interface with automatic coordinate transformations
|
||||
[#237] (https://github.com/paparazzi/paparazzi/pull/237)
|
||||
- New AHRS filter: Multiplicative quaternion linearized Kalman Filter
|
||||
- New SPI driver with transaction queues.
|
||||
- Fix transactions with zero length input.
|
||||
[#348] (https://github.com/paparazzi/paparazzi/issues/348)
|
||||
- Peripherals: Cleanup and refactoring.
|
||||
- MPU60x0 peripheral supporting SPI and I2C with slave.
|
||||
- UDP datalink.
|
||||
- Magnetometer current offset calibration.
|
||||
[#346] (https://github.com/paparazzi/paparazzi/pull/346)
|
||||
- Gain scheduling module.
|
||||
[#335] (https://github.com/paparazzi/paparazzi/pull/335)
|
||||
|
||||
Rotorcraft firmware specific
|
||||
----------------------------
|
||||
|
||||
- Quadshot transitioning vehicle support.
|
||||
- Care Free Mode
|
||||
|
||||
|
||||
Paparazzi 4.2.1_stable
|
||||
======================
|
||||
|
||||
Maintenance release
|
||||
|
||||
- fix elf PT_LOAD type in lpc21iap LPC USB download
|
||||
- fix electrical.current estimate in sim
|
||||
- fix LPC+xbee_api in rotorcraft
|
||||
- fix conversion of vsupply to decivolts if offset is used
|
||||
- more robust dfu flash script, only upload to Lisa/M
|
||||
|
||||
|
||||
Paparazzi 4.2.0_stable
|
||||
|
||||
@@ -31,7 +31,7 @@ PAPARAZZI_SRC=$(shell pwd)
|
||||
empty=
|
||||
space=$(empty) $(empty)
|
||||
ifneq ($(findstring $(space),$(PAPARAZZI_SRC)),)
|
||||
$(error No fucking spaces allowed in the current directory name)
|
||||
$(error No spaces allowed in the current directory name)
|
||||
endif
|
||||
ifeq ($(PAPARAZZI_HOME),)
|
||||
PAPARAZZI_HOME=$(PAPARAZZI_SRC)
|
||||
@@ -118,6 +118,7 @@ conf/%.xml :conf/%.xml.example
|
||||
|
||||
|
||||
ground_segment: print_build_version update_google_version conf libpprz subdirs commands static
|
||||
ground_segment.opt: ground_segment cockpit.opt tmtc.opt
|
||||
|
||||
static: cockpit tmtc tools sim_static joystick static_h
|
||||
|
||||
@@ -130,9 +131,15 @@ multimon:
|
||||
cockpit: libpprz
|
||||
$(MAKE) -C $(COCKPIT)
|
||||
|
||||
cockpit.opt: libpprz
|
||||
$(MAKE) -C $(COCKPIT) opt
|
||||
|
||||
tmtc: libpprz cockpit multimon
|
||||
$(MAKE) -C $(TMTC)
|
||||
|
||||
tmtc.opt: libpprz cockpit.opt multimon
|
||||
$(MAKE) -C $(TMTC) opt
|
||||
|
||||
tools: libpprz
|
||||
$(MAKE) -C $(TOOLS)
|
||||
|
||||
@@ -289,8 +296,8 @@ run_tests:
|
||||
test: all replace_current_conf_xml run_tests restore_conf_xml
|
||||
|
||||
|
||||
.PHONY: all print_build_version update_google_version ground_segment \
|
||||
subdirs $(SUBDIRS) conf ext libpprz multimon cockpit tmtc tools\
|
||||
.PHONY: all print_build_version update_google_version ground_segment ground_segment.opt \
|
||||
subdirs $(SUBDIRS) conf ext libpprz multimon cockpit cockpit.opt tmtc tmtc.opt tools\
|
||||
static sim_static lpctools commands \
|
||||
clean cleanspaces ab_clean dist_clean distclean dist_clean_irreversible \
|
||||
test replace_current_conf_xml run_tests restore_conf_xml
|
||||
|
||||
@@ -23,8 +23,6 @@
|
||||
# This is the common Makefile for finding the arm compiler and OpenOcd
|
||||
#
|
||||
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-toolchain
|
||||
|
||||
#
|
||||
# some generic and informative targets
|
||||
#
|
||||
@@ -40,51 +38,6 @@ printcommands:
|
||||
@$(CC) --version | head -1
|
||||
@echo ""
|
||||
|
||||
# Display size of file.
|
||||
HEXSIZE = $(SIZE) --target=$(FORMAT) $(OBJDIR)/$(TARGET).hex
|
||||
ELFSIZE = $(SIZE) -A -x $(OBJDIR)/$(TARGET).elf
|
||||
sizebefore:
|
||||
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Previous size:"; $(ELFSIZE); fi
|
||||
|
||||
sizeafter:
|
||||
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Current size:"; $(ELFSIZE); fi
|
||||
.PHONY : printcommands
|
||||
|
||||
# Target: clean project.
|
||||
clean: clean_list
|
||||
|
||||
clean_list :
|
||||
@echo
|
||||
$(RM) $(OBJDIR)/$(TARGET).hex
|
||||
$(RM) $(OBJDIR)/$(TARGET).obj
|
||||
$(RM) $(OBJDIR)/$(TARGET).elf
|
||||
$(RM) $(OBJDIR)/$(TARGET).map
|
||||
$(RM) $(OBJDIR)/$(TARGET).obj
|
||||
$(RM) $(OBJDIR)/$(TARGET).a90
|
||||
$(RM) $(OBJDIR)/$(TARGET).sym
|
||||
$(RM) $(OBJDIR)/$(TARGET).lnk
|
||||
$(RM) $(OBJDIR)/$(TARGET).lss
|
||||
$(RM) $(COBJ)
|
||||
$(RM) $(AOBJ)
|
||||
$(RM) $(COBJARM)
|
||||
$(RM) $(AOBJARM)
|
||||
$(RM) $(LST)
|
||||
$(RM) $(SRC:.c=.s)
|
||||
$(RM) $(SRC:.c=.d)
|
||||
$(RM) $(SRCARM:.c=.s)
|
||||
$(RM) $(SRCARM:.c=.d)
|
||||
$(RM) .dep/*
|
||||
$(RM) *~
|
||||
|
||||
.PHONY : printcommands sizebefore sizeafter clean clean_list
|
||||
|
||||
#
|
||||
# Find OpenOCD
|
||||
#
|
||||
# first try in the path
|
||||
OOCD = $(shell which openocd)
|
||||
#if OpenOCD could not be found in the path, try the toolchain dir (for backwards compatibility)
|
||||
ifeq ($(OOCD),)
|
||||
ifneq ($(TOOLCHAIN),)
|
||||
OOCD = $(shell if test -e $(TOOLCHAIN_DIR)/bin/openocd ; then echo $(TOOLCHAIN_DIR)/bin/openocd ; else echo "Warning: OpenOCD not found"; fi)
|
||||
endif
|
||||
endif
|
||||
|
||||
@@ -0,0 +1,61 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# Copyright (C) 2012 Felix Ruess <felix.ruess@gmail.com>
|
||||
|
||||
|
||||
#
|
||||
# This is the common Makefile for finding the arm compiler and OpenOcd
|
||||
# for bare metal systems like on the ARM7TDMI, cortex M3/4
|
||||
|
||||
# include the common ARM makefiles to print the commands and find the toolchain
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-common
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-embedded-toolchain
|
||||
|
||||
# Display size of file.
|
||||
HEXSIZE = $(SIZE) --target=$(FORMAT) $(OBJDIR)/$(TARGET).hex
|
||||
ELFSIZE = $(SIZE) -A -x $(OBJDIR)/$(TARGET).elf
|
||||
sizebefore:
|
||||
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Previous size:"; $(ELFSIZE); fi
|
||||
|
||||
sizeafter:
|
||||
@if [ -f $(OBJDIR)/$(TARGET).elf ]; then echo; echo "Current size:"; $(ELFSIZE); fi
|
||||
|
||||
# Target: clean project.
|
||||
clean: clean_list
|
||||
|
||||
clean_list :
|
||||
@echo
|
||||
$(RM) $(OBJDIR)/$(TARGET).hex
|
||||
$(RM) $(OBJDIR)/$(TARGET).obj
|
||||
$(RM) $(OBJDIR)/$(TARGET).elf
|
||||
$(RM) $(OBJDIR)/$(TARGET).map
|
||||
$(RM) $(OBJDIR)/$(TARGET).obj
|
||||
$(RM) $(OBJDIR)/$(TARGET).a90
|
||||
$(RM) $(OBJDIR)/$(TARGET).sym
|
||||
$(RM) $(OBJDIR)/$(TARGET).lnk
|
||||
$(RM) $(OBJDIR)/$(TARGET).lss
|
||||
$(RM) $(COBJ)
|
||||
$(RM) $(AOBJ)
|
||||
$(RM) $(COBJARM)
|
||||
$(RM) $(AOBJARM)
|
||||
$(RM) $(LST)
|
||||
$(RM) $(SRC:.c=.s)
|
||||
$(RM) $(SRC:.c=.d)
|
||||
$(RM) $(SRCARM:.c=.s)
|
||||
$(RM) $(SRCARM:.c=.d)
|
||||
$(RM) .dep/*
|
||||
$(RM) *~
|
||||
|
||||
.PHONY : sizebefore sizeafter clean clean_list
|
||||
|
||||
#
|
||||
# Find OpenOCD
|
||||
#
|
||||
# first try in the path
|
||||
OOCD = $(shell which openocd)
|
||||
#if OpenOCD could not be found in the path, try the toolchain dir (for backwards compatibility)
|
||||
ifeq ($(OOCD),)
|
||||
ifneq ($(TOOLCHAIN),)
|
||||
OOCD = $(shell if test -e $(TOOLCHAIN_DIR)/bin/openocd ; then echo $(TOOLCHAIN_DIR)/bin/openocd ; else echo "Warning: OpenOCD not found"; fi)
|
||||
endif
|
||||
endif
|
||||
@@ -1,8 +1,11 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# Copyright (C) 2012 Felix Ruess <felix.ruess@gmail.com>
|
||||
|
||||
|
||||
#
|
||||
# This is the common Makefile for finding the arm compiler
|
||||
#
|
||||
# This is the common Makefile for finding the arm compiler and OpenOcd
|
||||
# for bare metal systems like on the ARM7TDMI, cortex M3/4
|
||||
|
||||
#
|
||||
# try to pick up the compiler from the path
|
||||
@@ -0,0 +1,59 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
|
||||
#
|
||||
# Copyright (C) 2012 - TU Delft Robotics Minor - Dino Hensen and Freek van Tienen
|
||||
#
|
||||
# Minimal makefile for arm-linux-gnueabi or arm-none-linux-gnueabi toolchain.
|
||||
# Assuming installed in default location.
|
||||
|
||||
|
||||
#
|
||||
# try to pick up the compiler from the path
|
||||
#
|
||||
CC = $(shell which arm-linux-gnueabi-gcc)
|
||||
LD = $(shell which arm-linux-gnueabi-gcc)
|
||||
AR = $(shell which arm-linux-gnueabi-ar)
|
||||
CP = $(shell which arm-linux-gnueabi-objcopy)
|
||||
DMP = $(shell which arm-linux-gnueabi-objdump)
|
||||
NM = $(shell which arm-linux-gnueabi-nm)
|
||||
SIZE = $(shell which arm-linux-gnueabi-size)
|
||||
GDB = $(shell which arm-linux-gnueabi-gdb)
|
||||
TOOLCHAIN_DIR=$(shell dirname `which arm-linux-gnueabi`)
|
||||
GCC_LIB_DIR=$(TOOLCHAIN_DIR)/../arm-linux-gnueabi/lib
|
||||
|
||||
# if the above toolchain is used add the include folder
|
||||
CFLAGS += -I/usr/arm-linux-gnueabi/include
|
||||
|
||||
#
|
||||
# if not found in path, try the codesourcery toolchain in /usr/local/codesourcery
|
||||
#
|
||||
ifeq ($(CC),)
|
||||
TOOLCHAIN=$(shell find -L /usr/local/codesourcery -maxdepth 2 -type d -name arm-none-linux-gnueabi 2>/dev/null | head -n 1)
|
||||
ifneq ($(TOOLCHAIN),)
|
||||
TOOLCHAIN_DIR=$(shell dirname $(TOOLCHAIN))
|
||||
GCC_BIN_DIR=$(TOOLCHAIN_DIR)/bin
|
||||
GCC_LIB_DIR=$(TOOLCHAIN_DIR)/arm-none-linux-gnueabi/lib
|
||||
|
||||
# Define programs and commands.
|
||||
GCC_BIN_PREFIX=$(GCC_BIN_DIR)/arm-none-linux-gnueabi
|
||||
CC = $(GCC_BIN_PREFIX)-gcc
|
||||
LD = $(GCC_BIN_PREFIX)-gcc
|
||||
AR = $(GCC_BIN_PREFIX)-ar
|
||||
CP = $(GCC_BIN_PREFIX)-objcopy
|
||||
DMP = $(GCC_BIN_PREFIX)-objdump
|
||||
NM = $(GCC_BIN_PREFIX)-nm
|
||||
SIZE = $(GCC_BIN_PREFIX)-size
|
||||
GDB = $(GCC_BIN_PREFIX)-gdb
|
||||
else
|
||||
# toolchain not found...
|
||||
endif
|
||||
endif
|
||||
|
||||
# checking if gcc has thumb2 instruction
|
||||
MULTILIB = $(shell if $(CC) --print-multi-lib | grep thumb2 > /dev/null ; then echo "yes"; else echo "no"; fi)
|
||||
|
||||
# some general commands
|
||||
RM = rm
|
||||
|
||||
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-common
|
||||
+1
-1
@@ -37,7 +37,7 @@ Q=@
|
||||
#
|
||||
# find compiler toolchain
|
||||
#
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-common
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-embedded
|
||||
|
||||
#
|
||||
# if the new arm-none-eabi multilib compiler was not found try the old arm-elf one
|
||||
|
||||
+47
-21
@@ -1,6 +1,6 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# Copyright (C) 2009-2010 The Paparazzi Team
|
||||
# Copyright (C) 2009-2013 The Paparazzi Team
|
||||
#
|
||||
# This file is part of paparazzi.
|
||||
#
|
||||
@@ -20,22 +20,14 @@
|
||||
# Boston, MA 02111-1307, USA.
|
||||
#
|
||||
|
||||
|
||||
#
|
||||
# find compiler toolchain
|
||||
#
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-linux
|
||||
|
||||
# Define programs and commands.
|
||||
|
||||
# Look for an open embedded directory
|
||||
OVERO_OE := $(shell find -L /opt/paparazzi/omap ~ / -maxdepth 1 -type d -name overo-oe 2>/dev/null | head -n 1)
|
||||
|
||||
# Multiple places to look for compiler within oe directory structure
|
||||
CC_NAME = arm-angstrom-linux-gnueabi-gcc
|
||||
CCPATH1 = $(OVERO_OE)/tmp/cross/armv7a/bin
|
||||
CCPATH2 = $(OVERO_OE)/tmp/sysroots/i686-linux/usr/armv7a/bin
|
||||
CCPATH3 = $(OVERO_OE)/tmp/sysroots/x86_64-linux/usr/armv7a/bin
|
||||
CC := $(shell find -L $(CCPATH1) $(CCPATH2) $(CCPATH3) -name $(CC_NAME) -type f 2>/dev/null | head -n 1)
|
||||
LD = $(CC)
|
||||
|
||||
GLIB_INC = $(OVERO_OE)/tmp/work/armv7a-angstrom-linux-gnueabi/glib-2.0-2.22.4-r1/staging-pkg/staging/armv7a-angstrom-linux-gnueabi/usr/include/glib-2.0
|
||||
GLIB_LIB = $(OVERO_OE)/tmp/work/armv7a-angstrom-linux-gnueabi/glib-2.0-2.22.4-r1/staging-pkg/staging/armv7a-angstrom-linux-gnueabi/usr/lib/
|
||||
|
||||
# Launch with "make Q=''" to get full command display
|
||||
Q=@
|
||||
|
||||
@@ -46,28 +38,31 @@ CINCS = $(INCLUDES) -I$(PAPARAZZI_SRC)/sw/include
|
||||
# Compiler flags.
|
||||
CFLAGS += $(CINCS)
|
||||
CFLAGS += -O$(OPT) -mfloat-abi=softfp -mtune=cortex-a8 -mfpu=vfp -march=armv7-a
|
||||
CFLAGS += -fno-short-enums
|
||||
# CFLAGS += -malignment-traps
|
||||
CFLAGS += -Wall -Wcast-qual -Wimplicit -Wcast-align
|
||||
CFLAGS += -Wpointer-arith -Wswitch
|
||||
CFLAGS += -Wredundant-decls -Wreturn-type -Wshadow -Wunused
|
||||
CFLAGS += -Wredundant-decls -Wreturn-type -Wshadow -Wunused
|
||||
#-Wno-unused-result
|
||||
#CFLAGS += -Wa,-adhlns=$(OBJDIR)/$(notdir $(subst $(suffix $<),.lst,$<))
|
||||
#CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
|
||||
CFLAGS += -lm
|
||||
|
||||
# flags only for C
|
||||
CFLAGS + = -Wstrict-prototypes -Wmissing-declarations
|
||||
CFLAGS += -Wstrict-prototypes -Wmissing-declarations
|
||||
CFLAGS += -Wmissing-prototypes -Wnested-externs
|
||||
CFLAGS += $(CSTANDARD)
|
||||
CFLAGS += $($(TARGET).CFLAGS)
|
||||
|
||||
LDFLAGS += -lm
|
||||
|
||||
CXX = /opt/paparazzi/omap/overo-oe/tmp/sysroots/i686-linux/usr/armv7a/bin/arm-angstrom-linux-gnueabi-g++
|
||||
CXXFLAGS = -pipe -O3 -fshow-column -ffast-math -fPIC
|
||||
CXXFLAGS += -g -ffunction-sections -fdata-sections
|
||||
CXXFLAGS += -mfloat-abi=softfp -mtune=cortex-a8 -mfpu=vfp -march=armv7-a
|
||||
CXXFLAGS += -Wall -Wextra
|
||||
CXXFLAGS += $($(TARGET).CXXFLAGS)
|
||||
|
||||
|
||||
SRC_C_OMAP = $($(TARGET).srcs)
|
||||
OBJ_C_OMAP = $(SRC_C_OMAP:%.c=$(OBJDIR)/%.o)
|
||||
|
||||
@@ -80,9 +75,38 @@ build: elf
|
||||
|
||||
elf: $(OBJDIR)/$(TARGET).elf
|
||||
|
||||
# Program the device.
|
||||
# Program the device and start it.
|
||||
load upload program: $(OBJDIR)/$(TARGET).elf
|
||||
scp $(OBJDIR)/$(TARGET).elf $(USER)@$(HOST):$(TARGET_DIR)
|
||||
|
||||
# If it is not the SDK version, then kill program.elf
|
||||
ifneq ($(BOARD_TYPE), sdk)
|
||||
-echo "killall -9 program.elf" | telnet $(HOST)
|
||||
endif
|
||||
|
||||
# Kill the application
|
||||
-echo "killall -9 $(TARGET).elf" | telnet $(HOST)
|
||||
|
||||
# Upload the modules and start the application
|
||||
-{ \
|
||||
echo "mkdir -p $(TARGET_DIR)"; \
|
||||
} | telnet $(HOST)
|
||||
|
||||
# Upload the drivers and new application
|
||||
{ \
|
||||
echo "binary"; \
|
||||
echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/cdc-acm.ko /$(SUB_DIR)/cdc-acm.ko"; \
|
||||
echo "put $(OBJDIR)/$(TARGET).elf /$(SUB_DIR)/$(TARGET).elf"; \
|
||||
echo "quit"; \
|
||||
} | ftp -n $(HOST)
|
||||
|
||||
# Upload the modules and start the application
|
||||
-{ \
|
||||
echo "cd $(TARGET_DIR)"; \
|
||||
echo "insmod cdc-acm.ko"; \
|
||||
echo "chmod 777 $(TARGET).elf"; \
|
||||
echo "./$(TARGET).elf > /dev/null 2>&1 &"; \
|
||||
} | telnet $(HOST)
|
||||
|
||||
|
||||
# Link: create ELF output file from object files.
|
||||
.SECONDARY : $(OBJDIR)/$(TARGET).elf
|
||||
@@ -118,5 +142,7 @@ $(OBJDIR)/.depend:
|
||||
$(Q)$(CC) -MM -MG $(CFLAGS) $($(TARGET).CFLAGS) $($(TARGET).srcs) | sed 's|\([^\.]*\.o\)|$(OBJDIR)/\1|' > $@
|
||||
|
||||
ifneq ($(MAKECMDGOALS),clean)
|
||||
ifneq ($(MAKECMDGOALS),erase)
|
||||
-include $(OBJDIR)/.depend
|
||||
endif
|
||||
endif
|
||||
|
||||
+24
-9
@@ -45,26 +45,35 @@ Q=@
|
||||
# End of configuration part.
|
||||
#
|
||||
|
||||
LBITS := $(shell getconf LONG_BIT)
|
||||
ifeq ($(LBITS),64)
|
||||
FPIC = -fPIC
|
||||
else
|
||||
FPIC =
|
||||
endif
|
||||
|
||||
INCLUDES += -I `ocamlc -where`
|
||||
INCLUDES += -I $(shell $(OCAMLC) -where)
|
||||
|
||||
CFLAGS = -W -Wall
|
||||
CFLAGS += $(INCLUDES)
|
||||
CFLAGS += $($(TARGET).CFLAGS)
|
||||
CFLAGS += $(LOCAL_CFLAGS)
|
||||
CFLAGS += $(FPIC)
|
||||
CFLAGS += -fPIC
|
||||
CFLAGS += -O2
|
||||
CFLAGS += -g
|
||||
CFLAGS += -std=gnu99
|
||||
|
||||
LDFLAGS = -lm
|
||||
|
||||
# build sim in custom mode for Darwin and ARM systems for now...
|
||||
UNAME = $(shell uname -s)
|
||||
ifeq ($(UNAME),Darwin)
|
||||
SIMSITLCUSTOM=TRUE
|
||||
endif
|
||||
|
||||
MNAME = $(shell uname -m)
|
||||
ifneq (,$(findstring arm,$(MNAME)))
|
||||
SIMSITLCUSTOM=TRUE
|
||||
endif
|
||||
|
||||
ifdef SIMSITLCUSTOM
|
||||
CAMLINCLUDES += $(shell ocamlfind query -r -i-format lablgtk2) $(shell ocamlfind query -r -i-format xml-light) $(shell ocamlfind query -r -i-format glibivy)
|
||||
CAMLCMAS = unix.cma str.cma xml-light.cma glibivy-ocaml.cma lib-pprz.cma lablgtk.cma
|
||||
endif
|
||||
|
||||
|
||||
#
|
||||
# General rules
|
||||
@@ -81,9 +90,15 @@ autopilot.so : $($(TARGET).objs)
|
||||
@echo BUILD $@
|
||||
$(Q)$(CC) -shared -o $(OBJDIR)/$@ $^
|
||||
|
||||
ifdef SIMSITLCUSTOM
|
||||
$(OBJDIR)/simsitl : $($(TARGET).objs) $(SITLCMA) $(SIMSITLML)
|
||||
@echo LD $@
|
||||
$(Q)$(OCAMLC) -g -custom $(CAMLINCLUDES) -o $@ $(CAMLCMAS) $(MYGTKINITCMO) $^
|
||||
else
|
||||
$(OBJDIR)/simsitl : autopilot.so $(SITLCMA) $(SIMSITLML)
|
||||
@echo LD $@
|
||||
$(Q)$(OCAMLC) -g $(CAMLINCLUDES) -o $@ $(LINKPKG) $(MYGTKINITCMO) $^ -dllpath $(OBJDIR) -dllpath $(SIMDIR)
|
||||
endif
|
||||
|
||||
|
||||
# The id of the A/C is hardcoded in the code (to be improved with dynlink ?)
|
||||
|
||||
+69
-14
@@ -34,10 +34,14 @@ Q=@
|
||||
#
|
||||
# find compiler toolchain
|
||||
#
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-common
|
||||
include $(PAPARAZZI_SRC)/conf/Makefile.arm-embedded
|
||||
|
||||
|
||||
ifeq ($(ARCH_L),f4)
|
||||
MCU = cortex-m4
|
||||
else
|
||||
MCU = cortex-m3
|
||||
endif
|
||||
#DEBUG = dwarf-2
|
||||
OPT = s
|
||||
#OPT = 2
|
||||
@@ -98,7 +102,17 @@ $(info Using "$($(TARGET).LDSCRIPT)" as ldscript for target "$(TARGET)".)
|
||||
endif
|
||||
endif
|
||||
|
||||
CFLAGS = -I. -I./$(ARCH) -I../ext/libopencm3/include $(INCLUDES) -D__thumb2__ -msoft-float -O$(OPT)
|
||||
CFLAGS = -I. -I./$(ARCH) -I../ext/libopencm3/include $(INCLUDES)
|
||||
CFLAGS += -D__thumb2__ -Wall -O$(OPT)
|
||||
ifeq ($(ARCH_L), )
|
||||
CFLAGS += -msoft-float
|
||||
else ifeq ($(ARCH_L),f4)
|
||||
ifndef HARD_FLOAT
|
||||
CFLAGS += -msoft-float
|
||||
else
|
||||
CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
endif
|
||||
endif
|
||||
CFLAGS += -Wl,--gc-sections
|
||||
CFLAGS += -mfix-cortex-m3-ldrd
|
||||
CFLAGS += -mcpu=$(MCU) -mthumb -ansi
|
||||
@@ -107,33 +121,51 @@ CFLAGS += -std=gnu99
|
||||
CFLAGS += -fno-common
|
||||
CFLAGS += -g$(DEBUG)
|
||||
CFLAGS += -ffunction-sections -fdata-sections
|
||||
|
||||
# flags for warnings
|
||||
CFLAGS += -Wall -Wextra
|
||||
CFLAGS += -Wimplicit
|
||||
CFLAGS += -Wcast-align
|
||||
CFLAGS += -Wpointer-arith -Wswitch
|
||||
CFLAGS += -Wredundant-decls -Wreturn-type -Wshadow -Wunused
|
||||
CFLAGS += -Wa,-adhlns=$(OBJDIR)/$(notdir $(subst $(suffix $<),.lst,$<))
|
||||
CFLAGS += -Wnested-externs
|
||||
CFLAGS += -Wmissing-prototypes
|
||||
CFLAGS += -Wstrict-prototypes
|
||||
CFLAGS += -Wmissing-declarations
|
||||
CFLAGS += -Wswitch-default
|
||||
|
||||
CFLAGS += -Wa,-adhlns=$(OBJDIR)/$(notdir $(subst $(suffix $<),.lst,$<))
|
||||
ifneq ($(ARCH_L), )
|
||||
ifeq ($(ARCH_L),f4)
|
||||
CFLAGS += -DSTM32F4
|
||||
endif
|
||||
else
|
||||
CFLAGS += -DSTM32F1
|
||||
endif
|
||||
|
||||
CFLAGS += $($(TARGET).CFLAGS)
|
||||
|
||||
AFLAGS = -ahls
|
||||
AFLAGS = -ahls -mapcs-32
|
||||
AFLAGS += -mcpu=$(MCU) -mthumb
|
||||
AFLAGS += -x assembler-with-cpp -Wa,-adhlns=$(OBJDIR)/$(<:.S=.lst),--g$(DEBUG)
|
||||
|
||||
LDFLAGS = -L../ext/libopencm3/lib
|
||||
LDFLAGS += -T$(LDSCRIPT) -nostartfiles -O$(OPT)
|
||||
LDFLAGS += -mthumb -mcpu=$(MCU) -msoft-float -mfix-cortex-m3-ldrd
|
||||
LDFLAGS += -L../ext/libopencm3/lib
|
||||
LDFLAGS += -T$(LDSCRIPT) -nostartfiles -O$(OPT) -mthumb -mcpu=$(MCU)
|
||||
|
||||
ifeq ($(ARCH_L), )
|
||||
LDFLAGS += -mfix-cortex-m3-ldrd -msoft-float
|
||||
else ifeq ($(ARCH_L),f4)
|
||||
ifndef HARD_FLOAT
|
||||
LDFLAGS += -mfix-cortex-m3-ldrd -msoft-float
|
||||
else
|
||||
LDFLAGS += -lnosys -D__thumb2__\
|
||||
-mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
endif
|
||||
endif
|
||||
|
||||
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(TARGET).map,--cref,--gc-sections
|
||||
LDLIBS += -lc -lm -lgcc -lopencm3_stm32f1
|
||||
ifneq ($(ARCH_L), )
|
||||
LDLIBS += -lopencm3_stm32$(ARCH_L)
|
||||
else
|
||||
LDLIBS += -lopencm3_stm32f1
|
||||
endif
|
||||
LDLIBS += -lc -lm -lgcc
|
||||
|
||||
CPFLAGS = -j .isr_vector -j .text -j .data
|
||||
CPFLAGS_BIN = -Obinary
|
||||
@@ -199,11 +231,27 @@ $(AOBJ) : $(OBJDIR)/%.o : %.S
|
||||
# check which flash mode is configured
|
||||
#
|
||||
ifeq ($(FLASH_MODE),DFU)
|
||||
ifeq ($(DFU_UTIL),y)
|
||||
#
|
||||
# DFU flash mode
|
||||
# DFU flash mode using dfu-util
|
||||
DFU_ADDR ?= 0x08000000
|
||||
upload: $(OBJDIR)/$(TARGET).bin
|
||||
@echo "Using dfu-util at $(DFU_ADDR)"
|
||||
$(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR) -D $^
|
||||
else
|
||||
#
|
||||
# DFU flash mode paparazzi stm32_mem
|
||||
ifdef DFU_ADDR
|
||||
DFU_ADDR_CMD = --addr=$(DFU_ADDR)
|
||||
endif
|
||||
ifdef DFU_PRODUCT
|
||||
DFU_PRODUCT_CMD = --product=$(DFU_PRODUCT)
|
||||
endif
|
||||
upload: $(OBJDIR)/$(TARGET).bin
|
||||
@echo "Using stm32 mem dfu loader"
|
||||
$(PYTHON) $(PAPARAZZI_SRC)/sw/tools/dfu/stm32_mem.py $^
|
||||
$(PYTHON) $(PAPARAZZI_SRC)/sw/tools/dfu/stm32_mem.py $(DFU_PRODUCT_CMD) $(DFU_ADDR_CMD) $^
|
||||
endif
|
||||
|
||||
#
|
||||
# serial flash mode
|
||||
else ifeq ($(FLASH_MODE),SERIAL)
|
||||
@@ -246,6 +294,12 @@ endif
|
||||
# SWD flash mode
|
||||
else ifeq ($(FLASH_MODE),SWD)
|
||||
# only works if BMP_PORT is defined
|
||||
ifeq ($(STLINK),y)
|
||||
STLINK_ADDR ?= 0x08000000
|
||||
upload: $(OBJDIR)/$(TARGET).bin
|
||||
@echo "Using ST-LINK with SWD at $(STLINK_ADDR)"
|
||||
$(Q)st-flash write $^ $(STLINK_ADDR)
|
||||
else
|
||||
BMP_PORT ?= /dev/ttyACM0
|
||||
BMP_UPLOAD_SCRIPT ?= $(PAPARAZZI_SRC)/sw/tools/flash_scripts/bmp_swd_flash.scr
|
||||
upload: $(OBJDIR)/$(TARGET).elf
|
||||
@@ -257,6 +311,7 @@ upload: $(OBJDIR)/$(TARGET).elf
|
||||
-ex 'target extended-remote $(BMP_PORT)' \
|
||||
-x $(BMP_UPLOAD_SCRIPT) \
|
||||
$<
|
||||
endif
|
||||
#
|
||||
# no known flash mode
|
||||
else
|
||||
|
||||
@@ -123,9 +123,9 @@
|
||||
</section>
|
||||
|
||||
<section name="GLS_APPROACH" prefix="APP_" >
|
||||
<define name="ANGLE" value="5" />
|
||||
<define name="INTERCEPT_AF_TOD" value="10" />
|
||||
<define name="TARGET_SPEED" value="13" />
|
||||
<define name="ANGLE" value="5" unit="deg"/>
|
||||
<define name="INTERCEPT_AF_SD" value="10" unit="m"/>
|
||||
<define name="TARGET_SPEED" value="13" unit="m/s"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
|
||||
@@ -0,0 +1,224 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- this is an asctec frame equiped with Lisa/L#3 and asctec V2 controllers -->
|
||||
|
||||
<airframe name="lisa_asctec">
|
||||
<!-- ************************* FIRMWARE ************************* -->
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_l_1.0">
|
||||
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="asctec_v2"/>
|
||||
<subsystem name="telemetry" type="xbee_api"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_FLAPS"/>
|
||||
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>
|
||||
<define name="USE_I2C_ACTUATORS_REBOOT_HACK"/>
|
||||
</target>
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="mkk"/>
|
||||
</target>
|
||||
<subsystem name="imu" type="aspirin_v2.1"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="lisa_test_progs">
|
||||
<target name="test_led" board="lisa_l_1.0"/>
|
||||
<target name="test_uart" board="lisa_l_1.1"/>
|
||||
<target name="test_servos" board="lisa_l_1.1"/>
|
||||
<target name="test_telemetry" board="lisa_l_1.1"/>
|
||||
<target name="test_baro" board="lisa_l_1.1"/>
|
||||
<target name="test_imu_b2" board="lisa_l_1.1"/>
|
||||
<target name="test_imu_b2_2" board="lisa_l_1.1"/>
|
||||
<target name="test_imu_aspirin" board="lisa_l_1.1"/>
|
||||
<target name="test_rc_spektrum" board="lisa_l_1.1"/>
|
||||
<target name="test_rc_ppm" board="lisa_l_1.1"/>
|
||||
<target name="test_adc" board="lisa_l_1.1"/>
|
||||
<target name="test_hmc5843" board="lisa_l_1.1"/>
|
||||
<target name="test_itg3200" board="lisa_l_1.1"/>
|
||||
<target name="test_adxl345" board="lisa_l_1.1"/>
|
||||
<target name="test_esc_mkk_simple" board="lisa_l_1.1"/>
|
||||
<target name="test_esc_asctecv1_simple" board="lisa_l_1.1"/>
|
||||
<!--target name="test_actuators_mkk" board="lisa_l_1.1"/>
|
||||
<target name="test_actuators_asctecv1" board="lisa_l_1.1"/-->
|
||||
</firmware>
|
||||
|
||||
<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_HOVER_Z_HOLD"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* MODULES ************************* -->
|
||||
|
||||
<modules main_freq="512">
|
||||
<!-- <load name="high_speed_logger_spi_link.xml"/> -->
|
||||
<load name="imu_quality_assessment.xml"/>
|
||||
</modules>
|
||||
|
||||
<!-- ************************* ACTUATORS ************************* -->
|
||||
|
||||
<servos driver="Asctec_v2">
|
||||
<servo name="FRONT" no="0" min="0" neutral="3" max="200"/>
|
||||
<servo name="BACK" no="1" min="0" neutral="3" max="200"/>
|
||||
<servo name="LEFT" no="2" min="0" neutral="3" max="200"/>
|
||||
<servo name="RIGHT" no="3" min="0" neutral="3" max="200"/>
|
||||
</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"/>
|
||||
<!-- Driver expects: Front - Back - Left - Right -->
|
||||
<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_motors_on,FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
|
||||
</command_laws>
|
||||
|
||||
<!-- ************************* SENSORS ************************* -->
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="ACCEL_X_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="200"/>
|
||||
<define name="ACCEL_X_SENS" value="9.810" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="9.810" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="9.810" integer="16"/>
|
||||
<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="180." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="10." integer="16"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* GAINS ************************* -->
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
</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="180." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="900"/>
|
||||
<define name="PHI_DGAIN" value="200"/>
|
||||
<define name="PHI_IGAIN" value="200"/>
|
||||
<define name="THETA_PGAIN" value="900"/>
|
||||
<define name="THETA_DGAIN" value="200"/>
|
||||
<define name="THETA_IGAIN" value="200"/>
|
||||
<define name="PSI_PGAIN" value="900"/>
|
||||
<define name="PSI_DGAIN" value="200"/>
|
||||
<define name="PSI_IGAIN" value="10"/>
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value=" 200"/>
|
||||
<define name="THETA_DDGAIN" value=" 200"/>
|
||||
<define name="PSI_DDGAIN" value=" 200"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="HOVER_KP" value="500"/>
|
||||
<define name="HOVER_KD" value="200"/>
|
||||
<define name="HOVER_KI" value="100"/>
|
||||
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
|
||||
<define name="RC_CLIMB_COEF" value="163"/>
|
||||
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
|
||||
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.4"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="IGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* MISC ************************* -->
|
||||
|
||||
<!-- for the sim -->
|
||||
|
||||
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
||||
<define name="NB" value="4"/>
|
||||
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 }"/>
|
||||
</section>
|
||||
|
||||
<section name="MAGNETICS" prefix="AHRS_H_">
|
||||
<define name="X" value="0.4"/>
|
||||
<define name="Y" value="0"/>
|
||||
<define name="Z" value="0.9"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="FACE_REINJ_1" value="1024"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_booz2_a1.h""/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,214 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
|
||||
http://www.robbe.de/roxxy-bl-outrunner-2827-34.html
|
||||
|
||||
Technische Daten
|
||||
|
||||
Abmessungen: Ø 28 x 29 mm
|
||||
Freie Wellenlänge: 12.5 mm
|
||||
Gewicht ca.: 57 g
|
||||
Laststrom (5min/120°C): 9 A
|
||||
Umdrehung / Volt: 760 Umin/V
|
||||
Max.Wirkungsgrad: 76 %
|
||||
Laststrom max. (60 Sek.): 10 A
|
||||
Zellenzahl: 6-10 NC/NiMH
|
||||
Leistung: 110 W
|
||||
Wellendurchmesser: 3.17 mm
|
||||
Spannung: 7-12 Volt
|
||||
LiPo/LiIo-Zellen: 2-3
|
||||
|
||||
-->
|
||||
|
||||
<airframe name="BOOZ2_a1">
|
||||
<!-- ************************* FIRMWARE ************************* -->
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_2.0">
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_FLAPS"/>
|
||||
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>
|
||||
</target>
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="xbee_api"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="mkk_v2"/>
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="USE_PWM0"/>
|
||||
</subsystem>
|
||||
<subsystem name="imu" type="aspirin_v2.1"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
</firmware>
|
||||
|
||||
<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>
|
||||
|
||||
<!-- ************************* MODULES ************************* -->
|
||||
|
||||
<modules>
|
||||
<load name="configure_actuators_mkk_v2.xml"/>
|
||||
<load name="imu_quality_assessment.xml"/>
|
||||
</modules>
|
||||
|
||||
<!-- ************************* ACTUATORS ************************* -->
|
||||
|
||||
<section name="ACTUATORS_MKK_V2" prefix="ACTUATORS_MKK_V2_">
|
||||
<define name="NB" value="3"/>
|
||||
<define name="ADDR" value="{ 0x52, 0x56, 0x54 }"/>
|
||||
<define name="DEVICE" value="i2c1"/>
|
||||
</section>
|
||||
|
||||
<servos driver="Mkk_v2">
|
||||
<servo name="FRONTRIGHT" no="0" min="0" neutral="30" max="2047"/>
|
||||
<servo name="FRONTLEFT" no="1" min="0" neutral="30" max="2047"/>
|
||||
<servo name="BACK" no="2" min="0" neutral="30" max="2047"/>
|
||||
</servos>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="TAIL" 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>
|
||||
|
||||
<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="3"/>
|
||||
<define name="SCALE" value="2048"/>
|
||||
<define name="ROLL_COEF" value="{ 2048, -2048, 0}"/>
|
||||
<define name="PITCH_COEF" value="{ 1024, 1024, -2048}"/>
|
||||
<define name="YAW_COEF" value="{ 0, 0, 0}"/>
|
||||
<define name="THRUST_COEF" value="{ 2048, 2048, 2048}"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||
<set servo="FRONTRIGHT" value="motor_mixing.commands[SERVO_FRONTRIGHT]"/>
|
||||
<set servo="FRONTLEFT" value="motor_mixing.commands[SERVO_FRONTLEFT]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||
<set servo="TAIL" value="@YAW"/>
|
||||
</command_laws>
|
||||
|
||||
<!-- ************************* SENSORS ************************* -->
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="MAG_X_NEUTRAL" value="-152"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-51"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="10"/>
|
||||
<define name="MAG_X_SENS" value="4.04042714046" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.95350991963" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.83055079257" 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="-90." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="15." integer="16"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* GAINS ************************* -->
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
</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="360." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.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="800" 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="1200" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.85"/>
|
||||
<define name="REF_MAX_R" value="600." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(7000.)"/>
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="400"/>
|
||||
<define name="PHI_DGAIN" value="410"/>
|
||||
<define name="PHI_IGAIN" value="0"/>
|
||||
<define name="THETA_PGAIN" value="400"/>
|
||||
<define name="THETA_DGAIN" value="410"/>
|
||||
<define name="THETA_IGAIN" value="114"/>
|
||||
<define name="PSI_PGAIN" value="900"/>
|
||||
<define name="PSI_DGAIN" value="1328"/>
|
||||
<define name="PSI_IGAIN" value="0"/>
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value=" 100"/>
|
||||
<define name="THETA_DDGAIN" value=" 100"/>
|
||||
<define name="PSI_DDGAIN" value=" 300"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="HOVER_KP" value="500"/>
|
||||
<define name="HOVER_KD" value="200"/>
|
||||
<define name="HOVER_KI" value="100"/>
|
||||
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
|
||||
<define name="RC_CLIMB_COEF" value="163"/>
|
||||
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
|
||||
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="IGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<!-- ************************* MISC ************************* -->
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="XBEE_INIT" value=""ATID3332\r""/>
|
||||
<define name="FACE_REINJ_1" value="1024"/>
|
||||
<define name="VoltageOfAdc(adc)" value="(0.00528*adc)"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_booz2_a1.h""/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,215 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Apogee test board
|
||||
-->
|
||||
|
||||
<airframe name="Apogee">
|
||||
|
||||
<modules>
|
||||
<!--load name="sys_mon.xml"/-->
|
||||
<load name="mcp355x.xml">
|
||||
<define name="USE_SPI1"/>
|
||||
</load>
|
||||
</modules>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<define name="USE_I2C1"/>
|
||||
<define name="USE_I2C2"/>
|
||||
<!--define name="AGR_CLIMB"/-->
|
||||
<define name="ALT_KALMAN"/>
|
||||
<!--define name="LOITER_TRIM"/-->
|
||||
<!--define name="PITCH_TRIM"/-->
|
||||
<define name="USE_GYRO_PITCH_RATE"/>
|
||||
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="apogee_1.0"/>
|
||||
<!--configure name="FLASH_MODE" value="SWD"/-->
|
||||
|
||||
<subsystem name="radio_control" type="sbus"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<subsystem name="imu" type="apogee"/>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control"/>
|
||||
<subsystem name="navigation"/>
|
||||
<!-- Sensors -->
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
|
||||
<subsystem name="spi_master"/>
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="0" min="1040" neutral="1040" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="1" min="1900" neutral="1543" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="2" 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="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0 "/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_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." unit="rad"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0.144" unit="rad"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-158)*16.5698"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
|
||||
|
||||
<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.18"/> <!-- 0.024 -->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="5."/>
|
||||
|
||||
<!-- Cruise throttle + limits -->
|
||||
<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_PITCH_MAX_PITCH" value="RadOfDeg(20.)"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-RadOfDeg(20.)"/>
|
||||
|
||||
<!-- Climb loop (throttle) -->
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.002"/> <!-- 0.005 -->
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0.0"/> <!-- 0.005 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.004"/> <!-- 0.005 -->
|
||||
|
||||
<!-- Climb loop (pitch) -->
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.03"/>
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.04"/> <!-- 0.03 -->
|
||||
<define name="AUTO_PITCH_DGAIN" value="0.04"/> <!-- 0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
|
||||
<!-- airspeed control -->
|
||||
<define name="AUTO_AIRSPEED_SETPOINT" value="16."/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.1"/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.12"/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.06"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.042"/>
|
||||
<define name="AIRSPEED_MAX" value="30"/>
|
||||
<define name="AIRSPEED_MIN" value="10"/>
|
||||
|
||||
<!-- groundspeed control -->
|
||||
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
|
||||
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
|
||||
|
||||
<!-- pitch trim --> <!-- 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="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="8800."/>
|
||||
<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="14000."/>
|
||||
<define name="PITCH_DGAIN" value="0."/>
|
||||
<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_PITCH" value="0."/>
|
||||
<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""/>
|
||||
<!--define name="JSBSIM_INIT" value=""Malolo1-IC""/-->
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15.0"/>
|
||||
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="RadOfDeg(0.)"/>
|
||||
<define name="JSBSIM_IR_PITCH_NEUTRAL" value="RadOfDeg(0.)"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -26,9 +26,7 @@
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm">
|
||||
<define name="USE_HIGH_ACCEL_FLAG"/>
|
||||
</subsystem>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
|
||||
@@ -32,9 +32,7 @@
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm">
|
||||
<define name="USE_HIGH_ACCEL_FLAG"/>
|
||||
</subsystem>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float">
|
||||
<!--define name="USE_BAROMETER"/-->
|
||||
</subsystem>
|
||||
|
||||
@@ -39,9 +39,7 @@
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm">
|
||||
<define name="USE_HIGH_ACCEL_FLAG"/>
|
||||
</subsystem>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control" type="new">
|
||||
<define name="USE_GYRO_PITCH_RATE"/>
|
||||
|
||||
@@ -66,9 +66,7 @@
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm">
|
||||
<define name="USE_HIGH_ACCEL_FLAG"/>
|
||||
</subsystem>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control" type="new"/>
|
||||
<subsystem name="navigation"/>
|
||||
@@ -157,8 +155,8 @@
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="rad"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0.144" unit="rad"/>
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="4." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
|
||||
@@ -0,0 +1,219 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<airframe name="Quark">
|
||||
|
||||
<modules>
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
</modules>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<define name="USE_I2C0"/>
|
||||
<define name="USE_I2C1"/>
|
||||
<!--define name="AGR_CLIMB"/-->
|
||||
<define name="ALT_KALMAN"/>
|
||||
<define name="USE_AIRSPEED"/>
|
||||
<!--define name="LOITER_TRIM"/-->
|
||||
<!--define name="PITCH_TRIM"/-->
|
||||
<configure name="PERIODIC_FREQUENCY" value="125"/>
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="125"/>
|
||||
<define name="CONTROL_FREQUENCY" value="125"/>
|
||||
|
||||
<target name="sim" board="pc"/>
|
||||
<target name="ap" board="umarim_lite_2.0"/>
|
||||
|
||||
<subsystem name="radio_control" type="datalink"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control" type="new"/>
|
||||
<subsystem name="navigation"/>
|
||||
<!-- Sensors -->
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
</firmware>
|
||||
|
||||
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="MOTOR" no="2" min="1040" neutral="1040" max="2000"/>
|
||||
<servo name="AILEVON_LEFT" no="0" min="1900" neutral="1394" max="1100"/>
|
||||
<servo name="AILEVON_RIGHT" no="1" min="1100" neutral="1369" 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>
|
||||
|
||||
<command_laws>
|
||||
<let var="aileron" value="@ROLL"/>
|
||||
<let var="elevator" value="@PITCH"/>
|
||||
<set servo="MOTOR" value="@THROTTLE"/>
|
||||
<set servo="AILEVON_LEFT" value="$elevator - $aileron"/>
|
||||
<set servo="AILEVON_RIGHT" value="$elevator + $aileron"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.85"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<define name="GYRO_P_SIGN" value="1"/>
|
||||
<define name="GYRO_Q_SIGN" value="-1"/>
|
||||
<define name="GYRO_R_SIGN" value="-1"/>
|
||||
|
||||
<!-- Calibration Neutral -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
|
||||
<!-- 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="-13"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="-14"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-34"/>
|
||||
|
||||
<define name="ACCEL_X_SENS" value="38.8302353809" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="38.6959597569" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="39.2279525433" 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="UMARIM IMU" prefix="UMARIM_">
|
||||
<define name="ACCEL_RANGE" value="ADXL345_RANGE_8G"/>
|
||||
<define name="GYRO_LOWPASS" value="ITG3200_DLPF_20HZ"/>
|
||||
<define name="GYRO_SMPLRT_DIV" value="7"/> <!-- 125 Hz -->
|
||||
</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="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
|
||||
<define name="MAX_BAT_LEVEL" value="8.0" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="6.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="ALT_KALMAN_ENABLED" value="TRUE"/>
|
||||
|
||||
<define name="TRIGGER_DELAY" value="1."/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="50."/>
|
||||
|
||||
<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.15"/> <!-- -0.024 -->
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="3." 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.004"/> <!-- -0.005 -->
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0.01"/> <!-- 0.005 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.004"/> <!-- 0.005 -->
|
||||
|
||||
<!-- Climb loop (pitch) -->
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.02"/>
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.038"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_DGAIN" value="0.036"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
|
||||
<!-- 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="0." unit="deg"/>
|
||||
<define name="PITCH_DASH_TRIM" value="0." unit="deg"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.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="10000."/>
|
||||
<define name="PITCH_DGAIN" value="100."/>
|
||||
<define name="PITCH_IGAIN" value="250."/>
|
||||
<define name="PITCH_KFFA" value="0."/>
|
||||
<define name="PITCH_KFFD" value="0."/>
|
||||
|
||||
<define name="PITCH_OF_ROLL" value="0.0" unit="deg"/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<!--define name="ELEVATOR_OF_ROLL" value="1400"/-->
|
||||
</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"/-->
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -20,26 +20,27 @@
|
||||
<define name="USE_I2C1"/>
|
||||
<!--define name="AGR_CLIMB"/-->
|
||||
<define name="ALT_KALMAN"/>
|
||||
<define name="USE_AIRSPEED"/>
|
||||
<!--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">
|
||||
<configure name="FLASH_MODE" value="IAP"/>
|
||||
</target>
|
||||
<target name="ap" board="umarim_1.0"/>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem 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"/>
|
||||
</subsystem>
|
||||
|
||||
<!-- Communication -->
|
||||
<subsystem name="telemetry" type="xbee_api"/>
|
||||
|
||||
<!-- Actuators are automatically chosen according to board-->
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm">
|
||||
<define name="USE_HIGH_ACCEL_FLAG"/>
|
||||
</subsystem>
|
||||
<subsystem name="imu" type="umarim"/>
|
||||
<subsystem name="ahrs" type="float_dcm"/>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control" type="new"/>
|
||||
<subsystem name="navigation"/>
|
||||
@@ -49,17 +50,11 @@
|
||||
<!--subsystem name="spi"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
<firmware name="setup">
|
||||
<target name="setup_actuators" board="umarim_1.0"/>
|
||||
<target name="tunnel" board="umarim_1.0"/>
|
||||
</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"/>
|
||||
<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>
|
||||
@@ -83,13 +78,13 @@
|
||||
<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"/>
|
||||
<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"/>
|
||||
<define name="MAX_ROLL" value="45" unit="deg"/>
|
||||
<define name="MAX_PITCH" value="30" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
@@ -123,8 +118,8 @@
|
||||
</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"/>
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="3." unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="deg"/>
|
||||
<define name="BARO_SENS" value="1.0"/> <!-- TODO calibration -->
|
||||
</section>
|
||||
|
||||
@@ -161,15 +156,15 @@
|
||||
|
||||
<!-- Climb loop (throttle) -->
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.004"/> <!-- -0.005 -->
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0.01"/> <!-- 0.005 -->
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0.004"/> <!-- 0.005 -->
|
||||
<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.038"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_DGAIN" value="0.036"/> <!-- -0.03 -->
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<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."/>
|
||||
@@ -206,8 +201,8 @@
|
||||
<define name="ROLL_KFFA" value="0"/>
|
||||
<define name="ROLL_KFFD" value="0"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="10000."/>
|
||||
<define name="PITCH_DGAIN" 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."/>
|
||||
@@ -234,7 +229,7 @@
|
||||
<define name="MAX_ROLL_DOT" value="20" unit="rad/s"/-->
|
||||
<define name="JSBSIM_MODEL" value=""Malolo1""/>
|
||||
<!--define name="JSBSIM_INIT" value=""Malolo1-IC""/-->
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15.0"/>
|
||||
<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>
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
<subsystem name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
</firmware>
|
||||
@@ -133,7 +133,6 @@
|
||||
|
||||
<!-- Magnetic field for Gifhorn (declination 2°) -->
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="PROPAGATE_FREQUENCY" value="512"/>
|
||||
<define name="PROPAGATE_LOW_PASS_RATES" value="1"/>
|
||||
<define name="H_X" value="0.3794131"/>
|
||||
<define name="H_Y" value="0.0141005"/>
|
||||
|
||||
@@ -47,7 +47,7 @@
|
||||
<subsystem name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||
<subsystem name="ins" type="extended"/>
|
||||
</firmware>
|
||||
@@ -102,13 +102,13 @@
|
||||
<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="-12"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-10"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="-11"/>
|
||||
<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="22.008352" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="21.79885" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="14.675745" integer="16"/>
|
||||
<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"/>
|
||||
@@ -206,13 +206,14 @@
|
||||
|
||||
|
||||
<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="50"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<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="100"/>
|
||||
<define name="AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
|
||||
@@ -3,11 +3,11 @@
|
||||
<airframe name="Hummingbird (Asctec) Enac-Navgo 1">
|
||||
|
||||
<modules main_freq="512">
|
||||
<load name="mavlink_decoder.xml">
|
||||
<!--load name="mavlink_decoder.xml">
|
||||
<configure name="MAVLINK_PORT" value="UART0"/>
|
||||
<configure name="MAVLINK_BAUD" value="B115200"/>
|
||||
</load>
|
||||
<load name="px4flow.xml"/>
|
||||
<load name="px4flow.xml"/-->
|
||||
<!--load name="adc_generic.xml">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_0"/>
|
||||
</load-->
|
||||
@@ -23,23 +23,23 @@
|
||||
<define name="ACTUATORS_START_DELAY" value="3"/>
|
||||
</target>
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="telemetry" type="xbee_api"/>
|
||||
<!--subsystem name="actuators" type="skiron">
|
||||
<define name="SKIRON_I2C_SCL_TIME" value="25"/>
|
||||
</subsystem-->
|
||||
<subsystem name="actuators" type="asctec_v2"/>
|
||||
<subsystem name="actuators" type="asctec_v2"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="imu" type="navgo"/>
|
||||
<!--subsystem name="gps" type="ublox">
|
||||
<subsystem name="imu" type="navgo"/>
|
||||
<subsystem name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</subsystem-->
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
</firmware>
|
||||
|
||||
<section name="MIXING" prefix="MOTOR_MIXING_">
|
||||
@@ -48,9 +48,9 @@
|
||||
<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="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>
|
||||
|
||||
@@ -62,25 +62,25 @@
|
||||
</servos-->
|
||||
|
||||
<servos driver="Asctec_v2">
|
||||
<servo name="FRONT" no="0" min="0" neutral="1" max="200"/>
|
||||
<servo name="BACK" no="1" min="0" neutral="1" max="200"/>
|
||||
<servo name="LEFT" no="2" min="0" neutral="1" max="200"/>
|
||||
<servo name="RIGHT" no="3" min="0" neutral="1" max="200"/>
|
||||
<servo name="FRONT" no="0" min="0" neutral="1" max="200"/>
|
||||
<servo name="BACK" no="1" min="0" neutral="1" max="200"/>
|
||||
<servo name="LEFT" no="2" min="0" neutral="1" max="200"/>
|
||||
<servo name="RIGHT" no="3" min="0" neutral="1" max="200"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<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_motors_on,FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
@@ -110,9 +110,9 @@
|
||||
<define name="MAG_Y_SENS" value="4.23614065134" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.937732599" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" 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"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
|
||||
</section>
|
||||
|
||||
@@ -146,76 +146,77 @@
|
||||
<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"/>
|
||||
<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_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_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_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="1500"/>
|
||||
<define name="PHI_DGAIN" value="200"/>
|
||||
<define name="PHI_IGAIN" value="200"/>
|
||||
<define name="PHI_PGAIN" value="1272"/>
|
||||
<define name="PHI_DGAIN" value="132"/>
|
||||
<define name="PHI_IGAIN" value="146"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="1500"/>
|
||||
<define name="THETA_DGAIN" value="200"/>
|
||||
<define name="THETA_IGAIN" value="200"/>
|
||||
<define name="THETA_PGAIN" value="1272"/>
|
||||
<define name="THETA_DGAIN" value="132"/>
|
||||
<define name="THETA_IGAIN" value="157"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="1000"/>
|
||||
<define name="PSI_DGAIN" value="350"/>
|
||||
<define name="PSI_IGAIN" value="20"/>
|
||||
<define name="PSI_PGAIN" value="1000"/>
|
||||
<define name="PSI_DGAIN" value="244"/>
|
||||
<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_DDGAIN" value="170"/>
|
||||
<define name="THETA_DDGAIN" value="150"/>
|
||||
<define name="PSI_DDGAIN" value="170"/>
|
||||
|
||||
<define name="PHI_AGAIN" value="0"/>
|
||||
<define name="PHI_AGAIN" value="0"/>
|
||||
<define name="THETA_AGAIN" value="0"/>
|
||||
<define name="PSI_AGAIN" value="0"/>
|
||||
<define name="PSI_AGAIN" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<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"/>
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<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) -->
|
||||
<define name="RC_CLIMB_COEF" value ="163"/>
|
||||
<define name="RC_CLIMB_COEF" value="163"/>
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) * 20% -->
|
||||
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
|
||||
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
|
||||
<define name="ADAPT_NOISE_FACTOR" value="1.5"/>
|
||||
</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="50"/>
|
||||
<define name="DGAIN" value="80"/>
|
||||
<define name="IGAIN" value="20"/>
|
||||
<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"/>
|
||||
@@ -227,9 +228,8 @@
|
||||
|
||||
<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"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
|
||||
@@ -30,7 +30,7 @@
|
||||
<subsystem name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
</firmware>
|
||||
|
||||
@@ -30,7 +30,7 @@
|
||||
<subsystem name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<define name="PRINT_CONFIG"/>
|
||||
|
||||
@@ -0,0 +1,223 @@
|
||||
<!DOCTYPE airframe SYSTEM "airframe.dtd">
|
||||
|
||||
<airframe name="ardrone2_raw">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="ardrone2_raw">
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
<!--configure name="USE_NEW_I2C_DRIVER" value="1"/ -->
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="200"/>
|
||||
<define name="AHRS_PROPAGATE_FREQUENCY" value="200"/>
|
||||
<define name="INS_PROPAGATE_FREQUENCY" value="200"/>
|
||||
<define name="USE_BAROMETER"/>
|
||||
<subsystem name="telemetry" type="udp"/>
|
||||
<subsystem name="radio_control" type="datalink"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="motor_mixing"/>
|
||||
|
||||
<subsystem name="actuators" type="ardrone2"/>
|
||||
<subsystem name="imu" type="ardrone2"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_quat"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="extended"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
</modules>
|
||||
|
||||
<commands>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<servos driver="Default">
|
||||
<servo name="TOP_LEFT" no="0" min="0" neutral="1" max="500"/>
|
||||
<servo name="TOP_RIGHT" no="1" min="0" neutral="1" max="500"/>
|
||||
<servo name="BOTTOM_LEFT" no="3" min="0" neutral="1" max="500"/>
|
||||
<servo name="BOTTOM_RIGHT" no="2" min="0" neutral="1" max="500"/>
|
||||
</servos>
|
||||
|
||||
<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="255"/>
|
||||
<!-- Time cross layout (X), as documented in paparazzi -->
|
||||
<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_motors_on,FALSE,values)"/>
|
||||
<set servo="TOP_LEFT" value="motor_mixing.commands[SERVO_TOP_LEFT]"/>
|
||||
<set servo="TOP_RIGHT" value="motor_mixing.commands[SERVO_TOP_RIGHT]"/>
|
||||
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[SERVO_BOTTOM_LEFT]"/>
|
||||
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[SERVO_BOTTOM_RIGHT]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="ACCEL_X_NEUTRAL" value="2056"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="2060"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="2052"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="99"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="59"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="-65"/>
|
||||
<define name="MAG_X_SENS" value="14.8494072406" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="14.4187929352" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="15.4390790318" integer="16"/>
|
||||
<define name="MAG_X_CURRENT_COEF" value="0.00175105205138"/>
|
||||
<define name="MAG_Y_CURRENT_COEF" value="0.000172518663485"/>
|
||||
<define name="MAG_Z_CURRENT_COEF" value="0.00022802329524"/>
|
||||
|
||||
|
||||
|
||||
<!-- roll -->
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<!-- pitch -->
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<!-- yaw -->
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<!-- local magnetic field, calculated for: 52°3'56", 4°31'24" -->
|
||||
<!-- http://paparazzi.enac.fr/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="H_X" value="0.3892503"/>
|
||||
<define name="H_Y" value="0.0017972"/>
|
||||
<define name="H_Z" value="0.9211303"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="22.4" integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="REF_TAU" value="4"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="75"/>
|
||||
<define name="IGAIN_Q" value="75"/>
|
||||
<define name="IGAIN_R" value="50"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300"/>
|
||||
<define name="DDGAIN_Q" value="300"/>
|
||||
<define name="DDGAIN_R" value="300"/>
|
||||
</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="600" unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="900" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.9"/>
|
||||
<define name="REF_MAX_P" value="600." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="900" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.9"/>
|
||||
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="600" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.9"/>
|
||||
<define name="REF_MAX_R" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(4000.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="592"/>
|
||||
<define name="PHI_DGAIN" value="303"/>
|
||||
<define name="PHI_IGAIN" value="0"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="606"/>
|
||||
<define name="THETA_DGAIN" value="303"/>
|
||||
<define name="THETA_IGAIN" value="0"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="529"/>
|
||||
<define name="PSI_DGAIN" value="353"/>
|
||||
<define name="PSI_IGAIN" value="0"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="0"/>
|
||||
<define name="THETA_DDGAIN" value="0"/>
|
||||
<define name="PSI_DDGAIN" value="52"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="HOVER_KP" value="283"/>
|
||||
<define name="HOVER_KD" value="82"/>
|
||||
<define name="HOVER_KI" value="13"/>
|
||||
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
|
||||
<define name="RC_CLIMB_COEF" value="163"/>
|
||||
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
|
||||
<define name="RC_CLIMB_DEAD_BAND" value="160000"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="20" unit="deg"/>
|
||||
<define name="PGAIN" value="79"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="IGAIN" value="26"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"top_left_motor", "top_right_motor", "bottom_right_motor", "bottom_left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
||||
</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_HOVER_Z_HOLD"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
|
||||
<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>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,154 @@
|
||||
<!DOCTYPE airframe SYSTEM "airframe.dtd">
|
||||
|
||||
<airframe name="ardrone2_sdk">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="ardrone2_sdk">
|
||||
<define name="USE_INS_NAV_INIT" />
|
||||
<define name="ROTORCRAFT_COMMANDS_YAW_ALWAYS_ENABLED"/>
|
||||
<!-- <define name="USE_GPS_HEIGHT" /> -->
|
||||
<!-- <define name="ARDRONE_FLIGHT_INDOOR" /> -->
|
||||
<!-- <define name="ARDRONE_WITHOUT_SHELL" /> -->
|
||||
<!-- <define name="ARDRONE_OWNER_MAC" value="00:24:d7:47:f0:f4" /> -->
|
||||
</target>
|
||||
|
||||
<subsystem name="radio_control" type="datalink" />
|
||||
<subsystem name="telemetry" type="udp" />
|
||||
<subsystem name="gps" type="ardrone2" />
|
||||
<subsystem name="ahrs" type="ardrone2" />
|
||||
<subsystem name="ins" type="ardrone2" />
|
||||
<subsystem name="actuators" type="ardrone2" />
|
||||
<subsystem name="stabilization" type="passthrough"/>
|
||||
<subsystem name="imu" type="ardrone2" />
|
||||
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<load name="sys_mon.xml" />
|
||||
</modules>
|
||||
|
||||
<commands>
|
||||
<axis name="PITCH" failsafe_value="0" />
|
||||
<axis name="ROLL" failsafe_value="0" />
|
||||
<axis name="YAW" failsafe_value="0" />
|
||||
<axis name="THRUST" failsafe_value="0" />
|
||||
</commands>
|
||||
|
||||
<servos driver="Default" />
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<define name="SP_MAX_P" value="10000" />
|
||||
<define name="SP_MAX_Q" value="10000" />
|
||||
<define name="SP_MAX_R" value="10000" />
|
||||
<define name="DEADBAND_P" value="20" />
|
||||
<define name="DEADBAND_Q" value="20" />
|
||||
<define name="DEADBAND_R" value="200" />
|
||||
<define name="REF_TAU" value="4" />
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400" />
|
||||
<define name="GAIN_Q" value="400" />
|
||||
<define name="GAIN_R" value="350" />
|
||||
|
||||
<define name="IGAIN_P" value="75" />
|
||||
<define name="IGAIN_Q" value="75" />
|
||||
<define name="IGAIN_R" value="50" />
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300" />
|
||||
<define name="DDGAIN_Q" value="300" />
|
||||
<define name="DDGAIN_R" value="300" />
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="30." unit="deg" />
|
||||
<define name="SP_MAX_THETA" value="30." unit="deg" />
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s" />
|
||||
<define name="DEADBAND_A" value="0" />
|
||||
<define name="DEADBAND_E" value="0" />
|
||||
<define name="DEADBAND_R" value="250" />
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)" />
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)" />
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)" />
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)" />
|
||||
<define name="MAX_SUM_ERR" value="2000000" />
|
||||
<define name="HOVER_KP" value="425" />
|
||||
<define name="HOVER_KD" value="200" />
|
||||
<define name="HOVER_KI" value="125" />
|
||||
<!-- 1.5m/s for full stick : BOOZ_SPEED_I_OF_F(1.5) / (MAX_PPRZ/2) -->
|
||||
<define name="RC_CLIMB_COEF" value="163" />
|
||||
<!-- BOOZ_SPEED_I_OF_F(1.5) * 20% -->
|
||||
<define name="RC_CLIMB_DEAD_BAND" value="160000" />
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.5"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="30." unit="deg" />
|
||||
<define name="PGAIN" value="7" />
|
||||
<define name="DGAIN" value="2" />
|
||||
<define name="IGAIN" value="0" />
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_STARTUP" value="AP_MODE_NAV" />
|
||||
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT" />
|
||||
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD" />
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV" />
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value=".2" unit="V" />
|
||||
<define name="CRITIC_BAT_LEVEL" value="1.9" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="2.5" unit="V" />
|
||||
<define name="MAX_BAT_LEVEL" value="10.0" unit="V" />
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="ACCEL_X_NEUTRAL" value="2072" />
|
||||
<define name="ACCEL_Y_NEUTRAL" value="2040" />
|
||||
<define name="ACCEL_Z_NEUTRAL" value="2047" />
|
||||
<define name="ACCEL_X_SENS" value="19.1079036954" integer="16" />
|
||||
<define name="ACCEL_Y_SENS" value="19.5393623518" integer="16" />
|
||||
<define name="ACCEL_Z_SENS" value="19.6539180847" 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="GYRO_P_SENS_NUM" value="4359" />
|
||||
<define name="GYRO_P_SENS_DEN" value="1000" />
|
||||
<define name="GYRO_Q_SENS_NUM" value="4359" />
|
||||
<define name="GYRO_Q_SENS_DEN" value="1000" />
|
||||
<define name="GYRO_R_SENS_NUM" value="4359" />
|
||||
<define name="GYRO_R_SENS_DEN" value="1000" />
|
||||
|
||||
<define name="GYRO_P_SIGN" value="1" />
|
||||
<define name="GYRO_Q_SIGN" value="-1" />
|
||||
<define name="GYRO_R_SIGN" value="-1" />
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="118" />
|
||||
<define name="MAG_Y_NEUTRAL" value="-65" />
|
||||
<define name="MAG_Z_NEUTRAL" value="110" />
|
||||
<define name="MAG_X_SENS" value="14.6416865144" integer="16" />
|
||||
<define name="MAG_Y_SENS" value="14.5167340835" integer="16" />
|
||||
<define name="MAG_Z_SENS" value="15.1670335124" integer="16" />
|
||||
|
||||
<define name="MAG_X_SIGN" value="-1" />
|
||||
<define name="MAG_Y_SIGN" value="1" />
|
||||
<define name="MAG_Z_SIGN" value="-1" />
|
||||
|
||||
<!-- roll -->
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg" />
|
||||
<!-- pitch -->
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg" />
|
||||
<!-- yaw -->
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg" />
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -19,7 +19,7 @@
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="actuators" type="mkk"/>
|
||||
<subsystem name="imu" type="b2_v1.0"/>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
</firmware>
|
||||
|
||||
@@ -204,7 +204,7 @@
|
||||
<subsystem name="actuators" type="asctec"/>
|
||||
<subsystem name="imu" type="b2_v1.1"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||
<subsystem name="ins"/>
|
||||
</firmware>
|
||||
|
||||
@@ -0,0 +1,17 @@
|
||||
<airframe>
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="ACCEL_X_NEUTRAL" value="40"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="-11"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="250"/>
|
||||
<define name="ACCEL_X_SENS" value="4.86864977158" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="4.90451364272" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="4.85134642596" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-178"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="73"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="-11"/>
|
||||
<define name="MAG_X_SENS" value="4.19385009207" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.32306399648" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.63243801309" integer="16"/>
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -223,12 +223,10 @@ B2L -> CW
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_2.0">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -249,7 +247,7 @@ B2L -> CW
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -51,7 +51,7 @@
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
|
||||
</section>
|
||||
|
||||
<include href="conf/airframes/esden/calib/asp21-018.xml"/>
|
||||
<include href="conf/airframes/esden/calib/asp22-019.xml"/>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
@@ -65,7 +65,6 @@
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
|
||||
<define name="AUTOPILOT_KILL_WITHOUT_AHRS" value="TRUE"/>
|
||||
<define name="LOBATT_WING_WAGGLE" value="TRUE"/>
|
||||
<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
@@ -186,7 +185,6 @@
|
||||
|
||||
<section name="MISC">
|
||||
<define name="FACE_REINJ_1" value="1024"/>
|
||||
<define name="REF_QUAT_INFINITESIMAL_STEP" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
@@ -210,6 +208,7 @@
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<configure name="RADIO_CONTROL_PPM_PIN" value="UART1_RX"/>
|
||||
</subsystem>
|
||||
<configure name="LISA_M_BARO" value="BARO_MS5611_SPI"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -234,7 +233,7 @@
|
||||
</subsystem>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
</airframe>
|
||||
|
||||
@@ -215,16 +215,14 @@
|
||||
<load name="led_safety_status.xml"/>
|
||||
</modules>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_l_1.1">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_l_1.1">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
@@ -244,7 +242,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -178,12 +178,10 @@
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_2.0">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -205,7 +203,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -195,8 +195,6 @@
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<configure name="RADIO_CONTROL_PPM_PIN" value="UART1_RX"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -220,7 +218,7 @@
|
||||
</subsystem>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -0,0 +1,250 @@
|
||||
<!-- this is a quadshot vehicle equiped with Lia -->
|
||||
<!-- Copyright (C) 2012, Transition Robotics, Inc. -->
|
||||
|
||||
<airframe name="qs_asp22">
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="A1" no="0" min="1000" neutral="1050" max="2000"/>
|
||||
<servo name="A2" no="1" min="1000" neutral="1050" max="2000"/>
|
||||
<servo name="B1" no="2" min="1000" neutral="1050" max="2000"/>
|
||||
<servo name="B2" no="3" min="1000" neutral="1050" max="2000"/>
|
||||
<servo name="ELEVON_LEFT" no="4" min="1000" neutral="1500" max="2000"/>
|
||||
<servo name="ELEVON_RIGHT" no="5" 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_motors_on,FALSE,values)"/>
|
||||
<set servo="A1" value="motor_mixing.commands[SERVO_A1]"/>
|
||||
<set servo="A2" value="motor_mixing.commands[SERVO_A2]"/>
|
||||
<set servo="B1" value="motor_mixing.commands[SERVO_B1]"/>
|
||||
<set servo="B2" value="motor_mixing.commands[SERVO_B2]"/>
|
||||
|
||||
<let var="aileron_feedback_left" value="-@YAW"/>
|
||||
<let var="aileron_feedback_right" value="-@YAW"/>
|
||||
|
||||
<let var="elevator_feedback_left" value="-@PITCH"/>
|
||||
<let var="elevator_feedback_right" value="+@PITCH"/>
|
||||
|
||||
<let var="hover_left" value="3*$aileron_feedback_left"/>
|
||||
<let var="hover_right" value="3*$aileron_feedback_right"/>
|
||||
|
||||
<let var="forward_left" value="6*$aileron_feedback_left+4*$elevator_feedback_left"/>
|
||||
<let var="forward_right" value="6*$aileron_feedback_right+4*$elevator_feedback_right"/>
|
||||
|
||||
<set servo="ELEVON_LEFT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_left : $forward_left" />
|
||||
<set servo="ELEVON_RIGHT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_right : $forward_right" />
|
||||
</command_laws>
|
||||
|
||||
<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="PITCH_COEF" value="{ -256, -256, 256, 256 }"/>
|
||||
<define name="ROLL_COEF" value="{ 256, -256, 256, -256 }"/>
|
||||
<define name="YAW_COEF" value="{ -256, 256, 128, -128 }"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
|
||||
</section>
|
||||
|
||||
<include href="conf/airframes/esden/calib/asp22-019.xml"/>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="90." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_RATE_DIRECT"/>
|
||||
|
||||
<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MIN_BAT_LEVEL" value="10.4" units="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
|
||||
<define name="GAIN_P" value="350"/>
|
||||
<define name="GAIN_Q" value="250"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="200"/>
|
||||
<define name="IGAIN_Q" value="200"/>
|
||||
<define name="IGAIN_R" value="200"/>
|
||||
</section>
|
||||
|
||||
<section name ="GAIN_SETS">
|
||||
<define name="NUMBER_OF_GAINSETS" value="2"/>
|
||||
<define name="SCHEDULING_VARIABLE" value="(radio.values[COMMAND_THRUST]+ transition_status"/>
|
||||
<define name="SCHEDULING_POINTS" value="{1000, 6000}"/>
|
||||
<define name="SCHEDULING_VARIABLE_FRAC" value="0"/>
|
||||
|
||||
<define name="PHI_P" value="{230, 230}"/>
|
||||
<define name="PHI_D" value="{170, 170}"/>
|
||||
<define name="PHI_I" value="{30, 30}"/>
|
||||
<define name="PHI_DD" value="{0, 0}"/>
|
||||
|
||||
<define name="THETA_P" value="{200, 300}"/>
|
||||
<define name="THETA_D" value="{100, 50}"/>
|
||||
<define name="THETA_I" value="{40, 40}"/>
|
||||
<define name="THETA_DD" value="{0, 0}"/>
|
||||
|
||||
<define name="PSI_P" value="{300, 300}"/>
|
||||
<define name="PSI_D" value="{150, 150}"/>
|
||||
<define name="PSI_I" value="{0, 0}"/>
|
||||
<define name="PSI_DD" value="{0, 0}"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="60." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="60." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
<define name="DEADBAND_A" value="250"/>
|
||||
<define name="SP_PSI_DELTA_LIMIT" value="90" unit="deg"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="3000" 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="3000" 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="3000" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.9"/>
|
||||
<define name="REF_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="230"/>
|
||||
<define name="PHI_DGAIN" value="170"/>
|
||||
<define name="PHI_IGAIN" value="30"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="300"/>
|
||||
<define name="THETA_DGAIN" value="50"/>
|
||||
<define name="THETA_IGAIN" value="40"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="300"/>
|
||||
<define name="PSI_DGAIN" value="150"/>
|
||||
<define name="PSI_IGAIN" value="0"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value=" 0"/>
|
||||
<!--define name="THETA_DDGAIN" value=" 140"/-->
|
||||
<define name="THETA_DDGAIN" value=" 0"/>
|
||||
<define name="PSI_DDGAIN" value=" 0"/>
|
||||
|
||||
<!-- <define name="TURN_COORDINATION" value="0"/>
|
||||
<define name="TURN_ACCEL_COORDINATION" value="0"/>-->
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="22.4" integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="HOVER_KP" value="200"/>
|
||||
<define name="HOVER_KD" value="175"/>
|
||||
<define name="HOVER_KI" value="72"/>
|
||||
<define name="RC_CLIMB_COEF" value ="163"/>
|
||||
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
|
||||
<!-- <define name="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value ="0.3"/> -->
|
||||
</section>
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="PROPAGATE_FREQUENCY" value="512"/>
|
||||
<define name="H_X" value=" 0.47577"/>
|
||||
<define name="H_Y" value=" 0.11811"/>
|
||||
<define name="H_Z" value=" 0.87161"/>
|
||||
</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="MISC">
|
||||
<define name="USE_EARTH_BOUND_RC_SETPOINT" value="TRUE"/>
|
||||
<!-- <define name="USE_REFERENCE_SYSTEM" value="FALSE"/> -->
|
||||
<define name="SWITCH_STICKS_FOR_RATE_CONTROL" value="TRUE"/>
|
||||
<define name="TRANSITION_MAX_OFFSET" value="-82.0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_booz2_a1.h""/>
|
||||
</section>
|
||||
|
||||
<modules main_freq="512">
|
||||
<!--load name="vehicle_interface_overo_link.xml"/-->
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="led_safety_status.xml">
|
||||
<define name="USE_LED_BODY" value="1"/>
|
||||
<define name="SAFETY_WARNING_LED" value="BODY"/>
|
||||
</load>
|
||||
<!--load name="gain_scheduling.xml"/-->
|
||||
</modules>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_2.0">
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<configure name="RADIO_CONTROL_PPM_PIN" value="UART1_RX"/>
|
||||
</subsystem>
|
||||
<configure name="LISA_M_BARO" value="BARO_MS5611_SPI"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400"/>
|
||||
<define name="USE_SERVOS_7AND8"/>
|
||||
</subsystem>
|
||||
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="imu" type="aspirin_v2.2"/>
|
||||
<!-- <subsystem name="imu" type="aspirin_v1.5"/> -->
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_quat"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat">
|
||||
<configure name="USE_MAGNETOMETER" value="0"/>
|
||||
<define name="AHRS_USE_GPS_HEADING" value="0"/>
|
||||
</subsystem>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
</airframe>
|
||||
@@ -213,12 +213,10 @@
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_l_1.1">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -239,7 +237,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -174,12 +174,10 @@
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_1.0">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -200,7 +198,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -180,12 +180,10 @@
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_2.0">
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
<define name="RADIO_MODE" value="RADIO_FLAP"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
<configure name="LISA_M_BARO" value="BARO_MS5611_SPI"/>
|
||||
</target>
|
||||
|
||||
@@ -207,7 +205,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -178,10 +178,8 @@
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_m_2.0">
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<configure name="RADIO_CONTROL_PPM_PIN" value="UART1_RX"/>
|
||||
<configure name="RADIO_CONTROL_PPM_PIN" value="UART1_RX"/>
|
||||
</subsystem>
|
||||
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -202,7 +200,7 @@
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins"/>
|
||||
<!--define name="USE_INS_NAV_INIT"/-->
|
||||
<!--subsystem name="stabilization" type="euler"/>
|
||||
<!--subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/-->
|
||||
</firmware>
|
||||
|
||||
|
||||
@@ -9,7 +9,6 @@
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="lisa_m_1.0">
|
||||
<define name="LISA_M_LONGITUDINAL_X"/>
|
||||
<define name="SENSOR_SYNC_SEND"/>
|
||||
|
||||
<configure name="PERIODIC_FREQUENCY" value="120"/>
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
|
||||
@@ -27,7 +26,6 @@
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
<define name="SENSOR_SYNC_SEND"/>
|
||||
<!-- Sensors -->
|
||||
<!--
|
||||
<subsystem name="ahrs" type="int_cmpl_quat">
|
||||
@@ -60,7 +58,9 @@
|
||||
|
||||
<modules>
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="airspeed_ets.xml"/>
|
||||
<load name="airspeed_ets.xml">
|
||||
<define name="AIRSPEED_ETS_SYNC_SEND"/>
|
||||
</load>
|
||||
<load name="adc_generic.xml">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="0"/>
|
||||
<configure name="ADC_CHANNEL_GENERIC2" value="1"/>
|
||||
@@ -180,9 +180,9 @@
|
||||
</section>
|
||||
|
||||
<section name="GLS_APPROACH" prefix="APP_">
|
||||
<define name="ANGLE" value="5"/>
|
||||
<define name="INTERCEPT_AF_TOD" value="10"/>
|
||||
<define name="TARGET_SPEED" value="13"/>
|
||||
<define name="ANGLE" value="5" unit="deg"/>
|
||||
<define name="INTERCEPT_AF_SD" value="10" unit="m"/>
|
||||
<define name="TARGET_SPEED" value="13" unit="m/s"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
@@ -192,6 +192,8 @@
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="3."/>
|
||||
|
||||
<define name="AIRSPEED_PGAIN" value="0."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.36700001359"/>
|
||||
@@ -199,7 +201,14 @@
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.518000006676" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.307000011206"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="s"/>
|
||||
<define name="AUTO_THROTTLE_OF_AIRSPEED_PGAIN" value="0.0"/>
|
||||
<define name="AUTO_THROTTLE_OF_AIRSPEED_IGAIN" value="0.0"/>
|
||||
|
||||
<define name="AUTO_PITCH_OF_AIRSPEED_PGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_OF_AIRSPEED_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_PITCH_OF_AIRSPEED_DGAIN" value="0.0"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="m/s/s"/>
|
||||
|
||||
<!--define name="AUTO_GROUNDSPEED_SETPOINT" value="15." unit="m/s"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
|
||||
|
||||
@@ -44,14 +44,14 @@ twog_1.0 + aspirin + ETS baro + ETS speed
|
||||
|
||||
<modules>
|
||||
<load name="airspeed_ets.xml">
|
||||
<define name="SENSOR_SYNC_SEND"/>
|
||||
<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 -->
|
||||
<!-- <define name="AIRSPEED_ETS_I2C_DEV" value="i2c1"/> -->
|
||||
</load>
|
||||
<load name="baro_ets.xml">
|
||||
<define name="BARO_ETS_SCALE" value="0.3"/>
|
||||
<define name="BARO_ETS_TELEMETRY"/>
|
||||
<define name="BARO_ETS_SYNC_SEND"/>
|
||||
</load>
|
||||
<load name="baro_board.xml">
|
||||
<define name="BARO_ABS_EVENT" value="BaroEtsUpdate"/>
|
||||
@@ -156,7 +156,7 @@ twog_1.0 + aspirin + ETS baro + ETS speed
|
||||
<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="1" unit="s"/> <!--default is 1-->
|
||||
<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)"/>
|
||||
@@ -170,8 +170,8 @@ twog_1.0 + aspirin + ETS baro + ETS speed
|
||||
|
||||
<section name="GLS_APPROACH" prefix="APP_">
|
||||
<define name="ANGLE" value="10" unit="deg"/>
|
||||
<define name="INTERCEPT_AF_TOD" value="100"/>
|
||||
<define name="TARGET_SPEED" value="13"/>
|
||||
<define name="INTERCEPT_AF_SD" value="100" unit="m"/>
|
||||
<define name="TARGET_SPEED" value="13" unit="m/s"/>
|
||||
</section>
|
||||
|
||||
<!-- ########################################################################################### -->
|
||||
@@ -183,6 +183,7 @@ twog_1.0 + aspirin + ETS baro + ETS speed
|
||||
<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"/>
|
||||
|
||||
|
||||
@@ -210,7 +210,7 @@
|
||||
<subsystem name="actuators" type="mkk"/>
|
||||
<subsystem name="imu" type="b2_v1.0"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
</firmware>
|
||||
|
||||
@@ -189,7 +189,7 @@
|
||||
<!-- <subsystem name="imu" type="b2_v1.1"/> -->
|
||||
<subsystem name="imu" type="aspirin_v1.0"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||
<subsystem name="ins"/>
|
||||
</firmware>
|
||||
|
||||
@@ -0,0 +1,190 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../../airframe.dtd">
|
||||
|
||||
<airframe name="KroozSD fixedwing example">
|
||||
|
||||
<modules>
|
||||
</modules>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<target name="ap" board="krooz_sd"/>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<define name="LOITER_TRIM"/>
|
||||
<define name="ALT_KALMAN"/>
|
||||
<define name="AGR_CLIMB"/>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="imu" type="krooz_sd"/>
|
||||
<subsystem name="ahrs" type="float_dcm">
|
||||
<define name="USE_HIGH_ACCEL_FLAG"/>
|
||||
<define name="KROOZ_GYRO_RANGE" value="MPU60X0_GYRO_RANGE_500"/>
|
||||
<configure name="AHRS_PROPAGATE_FREQUENCY" value="60"/>
|
||||
</subsystem>
|
||||
<subsystem name="ins" type="alt_float"/>
|
||||
<subsystem name="control"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="navigation"/>
|
||||
<subsystem name="actuators" type="pwm"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
<!-- commands section -->
|
||||
<servos driver="Pwm">
|
||||
<servo name="MOTOR" no="4" min="1100" neutral="1100" max="1900"/>
|
||||
<servo name="ELEVATOR" no="3" min="1200" neutral="1430" max="1800"/>
|
||||
<servo name="RUDDER" no="1" min="1200" neutral="1619" max="2000"/>
|
||||
<servo name="AILERON_RIGHT" no="0" 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_">
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_P_SENS" value="1.0908" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="1.0908" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="1.0908" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-48"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="86"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-479"/>
|
||||
<define name="ACCEL_X_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.6131" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-282"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-78"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="109"/>
|
||||
<define name="MAG_X_SENS" value="3.33430456557" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.53180739126" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.68297143457" 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="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0." 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="ALT_KALMAN_ENABLED" value="TRUE"/>
|
||||
<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>
|
||||
@@ -0,0 +1,245 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<airframe name="Hexarotor KroozSD Mkk">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="krooz_sd"/>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="mkk">
|
||||
<define name="I2C_TRANSACTION_QUEUE_LEN" value="10"/>
|
||||
<define name="I2C1_CLOCK_SPEED" value="42000"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="imu" type="krooz_sd"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
|
||||
<define name="NO_RC_THRUST_LIMIT"/>
|
||||
<define name="USE_RC_FP_BLOCK_SWITCHING"/>
|
||||
<define name="USE_ATTITUDE_REF" value="0"/>
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<!--<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="sys_mon.xml"/>
|
||||
<load name="geo_mag.xml"/>
|
||||
<load name="osd_max7456.xml"/>-->
|
||||
</modules>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
||||
<define name="NB" value="6"/>
|
||||
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 , 0x5A , 0x5C }"/>
|
||||
</section>
|
||||
|
||||
<servos driver="Mkk">
|
||||
<servo name="FF" no="0" min="0" neutral="3" max="210"/>
|
||||
<servo name="FR" no="1" min="0" neutral="3" max="210"/>
|
||||
<servo name="DR" no="2" min="0" neutral="3" max="210"/>
|
||||
<servo name="DD" no="3" min="0" neutral="3" max="210"/>
|
||||
<servo name="DL" no="4" min="0" neutral="3" max="210"/>
|
||||
<servo name="FL" no="5" min="0" neutral="3" max="210"/>
|
||||
</servos>
|
||||
|
||||
<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="TRIM_A" value="0"/>
|
||||
<define name="TRIM_E" value="0"/>
|
||||
<define name="TRIM_R" value="0"/>
|
||||
<define name="NB_MOTOR" value="6"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<define name="ROLL_COEF" value="{ 0, -256, -256, 0, 256, 256 }"/>
|
||||
<define name="PITCH_COEF" value="{ 256, 128, -128, -256, -128, 128 }"/>
|
||||
<define name="YAW_COEF" value="{ -256, 249, -249, 256, -249, 249 }"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256 }"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||
<set servo="FF" value="motor_mixing.commands[SERVO_FF]"/>
|
||||
<set servo="FR" value="motor_mixing.commands[SERVO_FR]"/>
|
||||
<set servo="DR" value="motor_mixing.commands[SERVO_DR]"/>
|
||||
<set servo="DD" value="motor_mixing.commands[SERVO_DD]"/>
|
||||
<set servo="DL" value="motor_mixing.commands[SERVO_DL]"/>
|
||||
<set servo="FL" value="motor_mixing.commands[SERVO_FL]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_P_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="0.5454" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-48"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="86"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-479"/>
|
||||
<define name="ACCEL_X_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.6131" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-282"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-78"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="109"/>
|
||||
<define name="MAG_X_SENS" value="3.33430456557" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.53180739126" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.68297143457" 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_">
|
||||
<define name="PROPAGATE_LOW_PASS_RATES" value="1"/>
|
||||
<define name="GRAVITY_UPDATE_NORM_HEURISTIC" value="1"/>
|
||||
<define name="H_X" value="0.3586845"/>
|
||||
<define name="H_Y" value="0.0168651"/>
|
||||
<define name="H_Z" value="0.933303"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="22." integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="REF_TAU" value="4"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="75"/>
|
||||
<define name="IGAIN_Q" value="75"/>
|
||||
<define name="IGAIN_R" value="50"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300"/>
|
||||
<define name="DDGAIN_Q" value="300"/>
|
||||
<define name="DDGAIN_R" value="300"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="100." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(2000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="100." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(2000.)"/>
|
||||
|
||||
<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(180.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="850"/>
|
||||
<define name="PHI_DGAIN" value="400"/>
|
||||
<define name="PHI_IGAIN" value="100"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="850"/>
|
||||
<define name="THETA_DGAIN" value="400"/>
|
||||
<define name="THETA_IGAIN" value="100"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="4000"/>
|
||||
<define name="PSI_DGAIN" value="1500"/>
|
||||
<define name="PSI_IGAIN" value="300"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="300"/>
|
||||
<define name="THETA_DDGAIN" value="300"/>
|
||||
<define name="PSI_DDGAIN" value="2000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="TILT_COEFF" value="0.35"/>
|
||||
<define name="REF_MIN_ZDD" value="-0.2*9.81"/> <!-- max descent acceleration -->
|
||||
<define name="REF_MAX_ZDD" value="0.2*9.81"/> <!-- max climb acceleration -->
|
||||
<define name="REF_MIN_ZD" value="-3."/> <!-- max descent speed -->
|
||||
<define name="REF_MAX_ZD" value="3."/> <!-- max climb speed -->
|
||||
<define name="HOVER_KP" value="120"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="RC_CLIMB_COEF" value ="500"/>
|
||||
<define name="RC_DESCENT_COEF" value ="200"/>
|
||||
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="USE_REF" value="1"/>
|
||||
<define name="USE_SPEED_REF" value="1"/> <!-- using RC to control horizontal setpoint -->
|
||||
<define name="MAX_BANK" value="27" unit="deg"/>
|
||||
<define name="REF_MAX_ACCEL" value="7."/> <!-- max reference horizontal acceleration in m/s2 -->
|
||||
<define name="REF_MAX_SPEED" value="2."/> <!-- max reference horizontal speed in m/s -->
|
||||
<define name="RC_SPEED_DEAD_BAND" value="200000"/>
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="120"/>
|
||||
<define name="IGAIN" value="10"/>
|
||||
<define name="AGAIN" value="10"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CRITIC_BAT_LEVEL" value="14.0" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="14.3" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="16.8" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,248 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<airframe name="Oktorotor KroozSD Mkk">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="krooz_sd"/>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="mkk">
|
||||
<define name="I2C_TRANSACTION_QUEUE_LEN" value="10"/>
|
||||
<define name="I2C1_CLOCK_SPEED" value="42000"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="imu" type="krooz_sd"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
|
||||
<define name="NO_RC_THRUST_LIMIT"/>
|
||||
<define name="USE_RC_FP_BLOCK_SWITCHING"/>
|
||||
<define name="USE_ATTITUDE_REF" value="0"/>
|
||||
<define name="KILL_ON_GROUND_DETECT" value="TRUE"/>
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<!--<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="sys_mon.xml"/>
|
||||
<load name="geo_mag.xml"/>
|
||||
<load name="osd_max7456.xml"/>-->
|
||||
</modules>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<section name="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
|
||||
<define name="NB" value="8"/>
|
||||
<define name="ADDR" value="{ 0x52, 0x54, 0x56, 0x58 , 0x5A, 0x5C, 0x5E, 0x60}"/>
|
||||
</section>
|
||||
|
||||
<servos driver="Mkk">
|
||||
<servo name="FF" no="0" min="0" neutral="3" max="210"/>
|
||||
<servo name="FR" no="1" min="0" neutral="3" max="210"/>
|
||||
<servo name="RR" no="2" min="0" neutral="3" max="210"/>
|
||||
<servo name="DR" no="3" min="0" neutral="3" max="210"/>
|
||||
<servo name="DD" no="4" min="0" neutral="3" max="210"/>
|
||||
<servo name="DL" no="5" min="0" neutral="3" max="210"/>
|
||||
<servo name="LL" no="6" min="0" neutral="3" max="210"/>
|
||||
<servo name="FL" no="7" min="0" neutral="3" max="210"/>
|
||||
</servos>
|
||||
|
||||
<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="MAX_SATURATION_OFFSET" value="2000"/>
|
||||
<define name="NB_MOTOR" value="8"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<define name="ROLL_COEF" value="{ 108, -108, -256, -256, -108, 108, 256, 256}"/>
|
||||
<define name="PITCH_COEF" value="{ 256, 256, 108, -108, -256, -256, -108, 108}"/>
|
||||
<define name="YAW_COEF" value="{ -256, 256, -256, 256, -256, 256, -256, 256}"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256, 256, 256}"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||
<set servo="FF" value="motor_mixing.commands[SERVO_FF]"/>
|
||||
<set servo="FR" value="motor_mixing.commands[SERVO_FR]"/>
|
||||
<set servo="RR" value="motor_mixing.commands[SERVO_RR]"/>
|
||||
<set servo="DR" value="motor_mixing.commands[SERVO_DR]"/>
|
||||
<set servo="DD" value="motor_mixing.commands[SERVO_DD]"/>
|
||||
<set servo="DL" value="motor_mixing.commands[SERVO_DL]"/>
|
||||
<set servo="LL" value="motor_mixing.commands[SERVO_LL]"/>
|
||||
<set servo="FL" value="motor_mixing.commands[SERVO_FL]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_P_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="0.5454" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-48"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="86"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-479"/>
|
||||
<define name="ACCEL_X_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.6131" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-282"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-78"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="109"/>
|
||||
<define name="MAG_X_SENS" value="3.33430456557" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.53180739126" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.68297143457" 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_">
|
||||
<define name="PROPAGATE_LOW_PASS_RATES" value="1"/>
|
||||
<define name="GRAVITY_UPDATE_NORM_HEURISTIC" value="1"/>
|
||||
<define name="H_X" value="0.3586845"/>
|
||||
<define name="H_Y" value="0.0168651"/>
|
||||
<define name="H_Z" value="0.933303"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="22." integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="REF_TAU" value="4"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="75"/>
|
||||
<define name="IGAIN_Q" value="75"/>
|
||||
<define name="IGAIN_R" value="50"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300"/>
|
||||
<define name="DDGAIN_Q" value="300"/>
|
||||
<define name="DDGAIN_R" value="300"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="100." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(2000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="100." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(2000.)"/>
|
||||
|
||||
<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(180.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="850"/>
|
||||
<define name="PHI_DGAIN" value="400"/>
|
||||
<define name="PHI_IGAIN" value="100"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="850"/>
|
||||
<define name="THETA_DGAIN" value="400"/>
|
||||
<define name="THETA_IGAIN" value="100"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="4000"/>
|
||||
<define name="PSI_DGAIN" value="1500"/>
|
||||
<define name="PSI_IGAIN" value="300"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="300"/>
|
||||
<define name="THETA_DDGAIN" value="300"/>
|
||||
<define name="PSI_DDGAIN" value="2000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="TILT_COEFF" value="0.35"/>
|
||||
<define name="REF_MIN_ZDD" value="-0.2*9.81"/> <!-- max descent acceleration -->
|
||||
<define name="REF_MAX_ZDD" value="0.2*9.81"/> <!-- max climb acceleration -->
|
||||
<define name="REF_MIN_ZD" value="-3."/> <!-- max descent speed -->
|
||||
<define name="REF_MAX_ZD" value="3."/> <!-- max climb speed -->
|
||||
<define name="HOVER_KP" value="120"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="RC_CLIMB_COEF" value ="500"/>
|
||||
<define name="RC_DESCENT_COEF" value ="200"/>
|
||||
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="USE_REF" value="1"/>
|
||||
<define name="USE_SPEED_REF" value="1"/> <!-- using RC to control horizontal setpoint -->
|
||||
<define name="MAX_BANK" value="27" unit="deg"/>
|
||||
<define name="REF_MAX_ACCEL" value="1.2"/> <!-- max reference horizontal acceleration in m/s2 -->
|
||||
<define name="REF_MAX_SPEED" value="2."/> <!-- max reference horizontal speed in m/s -->
|
||||
<define name="RC_SPEED_DEAD_BAND" value="200000"/>
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="180"/>
|
||||
<define name="IGAIN" value="3"/>
|
||||
<define name="AGAIN" value="20"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CRITIC_BAT_LEVEL" value="13.0" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="13.2" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="16.8" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,237 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<airframe name="Quadrotor KroozSD Mkk">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="krooz_sd">
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="imu" type="krooz_sd"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
<subsystem name="actuators" type="mkk">
|
||||
<define name="I2C1_CLOCK_SPEED" value="42000"/>
|
||||
</subsystem>
|
||||
<subsystem name="motor_mixing"/>
|
||||
|
||||
<define name="NO_RC_THRUST_LIMIT"/>
|
||||
<define name="USE_RC_FP_BLOCK_SWITCHING"/>
|
||||
<define name="USE_ATTITUDE_REF" value="0"/>
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<!--<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="sys_mon.xml"/>
|
||||
<load name="geo_mag.xml"/>-->
|
||||
<load name="osd_max7456.xml"/>
|
||||
</modules>
|
||||
|
||||
<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="3" max="210"/>
|
||||
<servo name="BACK" no="1" min="0" neutral="3" max="210"/>
|
||||
<servo name="RIGHT" no="2" min="0" neutral="3" max="210"/>
|
||||
<servo name="LEFT" no="3" min="0" neutral="3" max="210"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
|
||||
</command_laws>
|
||||
|
||||
<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, -MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE }"/>
|
||||
<define name="PITCH_COEF" value="{ MOTOR_MIXING_SCALE, -MOTOR_MIXING_SCALE, 0, 0 }"/>
|
||||
<define name="YAW_COEF" value="{ -MOTOR_MIXING_SCALE, -MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE }"/>
|
||||
<define name="THRUST_COEF" value="{ MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE }"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_P_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="0.5454" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-48"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="86"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-479"/>
|
||||
<define name="ACCEL_X_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.6131" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="74"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-118"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="104"/>
|
||||
<define name="MAG_X_SENS" value="3.44419577366" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.40350478221" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.77559859867" 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_">
|
||||
<define name="PROPAGATE_LOW_PASS_RATES" value="1"/>
|
||||
<define name="GRAVITY_UPDATE_NORM_HEURISTIC" value="1"/>
|
||||
<define name="H_X" value="0.3586845"/>
|
||||
<define name="H_Y" value="0.0168651"/>
|
||||
<define name="H_Z" value="0.933303"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="22." integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="REF_TAU" value="4"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="75"/>
|
||||
<define name="IGAIN_Q" value="75"/>
|
||||
<define name="IGAIN_R" value="50"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300"/>
|
||||
<define name="DDGAIN_Q" value="300"/>
|
||||
<define name="DDGAIN_R" value="300"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="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(180.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="850"/>
|
||||
<define name="PHI_DGAIN" value="400"/>
|
||||
<define name="PHI_IGAIN" value="100"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="850"/>
|
||||
<define name="THETA_DGAIN" value="400"/>
|
||||
<define name="THETA_IGAIN" value="100"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="4000"/>
|
||||
<define name="PSI_DGAIN" value="1500"/>
|
||||
<define name="PSI_IGAIN" value="300"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="300"/>
|
||||
<define name="THETA_DDGAIN" value="300"/>
|
||||
<define name="PSI_DDGAIN" value="2000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="REF_MIN_ZDD" value="-0.2*9.81"/> <!-- max descent acceleration -->
|
||||
<define name="REF_MAX_ZDD" value="0.2*9.81"/> <!-- max climb acceleration -->
|
||||
<define name="REF_MIN_ZD" value="-3."/> <!-- max descent speed -->
|
||||
<define name="REF_MAX_ZD" value="3."/> <!-- max climb speed -->
|
||||
<define name="HOVER_KP" value="120"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="RC_CLIMB_COEF" value ="500"/>
|
||||
<define name="RC_DESCENT_COEF" value ="200"/>
|
||||
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="USE_REF" value="1"/>
|
||||
<define name="USE_SPEED_REF" value="1"/> <!-- using RC to control horizontal setpoint -->
|
||||
<define name="MAX_BANK" value="27" unit="deg"/>
|
||||
<define name="REF_MAX_ACCEL" value="7."/> <!-- max reference horizontal acceleration in m/s2 -->
|
||||
<define name="REF_MAX_SPEED" value="2."/> <!-- max reference horizontal speed in m/s -->
|
||||
<define name="RC_SPEED_DEAD_BAND" value="200000"/>
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="120"/>
|
||||
<define name="IGAIN" value="10"/>
|
||||
<define name="AGAIN" value="10"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CRITIC_BAT_LEVEL" value="13.0" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="13.2" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="16.8" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,233 @@
|
||||
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
|
||||
|
||||
<airframe name="Quadrotor KroozSD Pwm">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="krooz_sd">
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400"/>
|
||||
</subsystem>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="imu" type="krooz_sd"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_quat"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
<subsystem name="motor_mixing"/>
|
||||
|
||||
<define name="NO_RC_THRUST_LIMIT"/>
|
||||
<define name="USE_RC_FP_BLOCK_SWITCHING"/>
|
||||
<define name="USE_ATTITUDE_REF" value="0"/>
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<!--<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="sys_mon.xml"/>
|
||||
<load name="geo_mag.xml"/>
|
||||
<load name="osd_max7456.xml"/>-->
|
||||
</modules>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="FRONT" no="0" min="1000" neutral="1190" max="1900"/>
|
||||
<servo name="BACK" no="1" min="1000" neutral="1190" max="1900"/>
|
||||
<servo name="RIGHT" no="2" min="1000" neutral="1190" max="1900"/>
|
||||
<servo name="LEFT" no="3" min="1000" neutral="1190" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
|
||||
</command_laws>
|
||||
|
||||
<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="512"/>
|
||||
<define name="ROLL_COEF" value="{ 0, MOTOR_MIXING_SCALE, 0, -MOTOR_MIXING_SCALE }"/>
|
||||
<define name="PITCH_COEF" value="{ MOTOR_MIXING_SCALE, 0, -MOTOR_MIXING_SCALE, 0 }"/>
|
||||
<define name="YAW_COEF" value="{ -MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE, -MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE }"/>
|
||||
<define name="THRUST_COEF" value="{ MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE, MOTOR_MIXING_SCALE }"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="GYRO_P_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="0"/>
|
||||
<define name="GYRO_P_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="0.5454" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="0.5454" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="-48"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="86"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-479"/>
|
||||
<define name="ACCEL_X_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="0.6131" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.6131" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-282"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-78"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="109"/>
|
||||
<define name="MAG_X_SENS" value="3.33430456557" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.53180739126" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="3.68297143457" 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_">
|
||||
<define name="PROPAGATE_LOW_PASS_RATES" value="1"/>
|
||||
<define name="GRAVITY_UPDATE_NORM_HEURISTIC" value="1"/>
|
||||
<define name="H_X" value="0.365258"/>
|
||||
<define name="H_Y" value="0.015505"/>
|
||||
<define name="H_Z" value="0.930777"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="22." integer="16"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="REF_TAU" value="4"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="75"/>
|
||||
<define name="IGAIN_Q" value="75"/>
|
||||
<define name="IGAIN_R" value="50"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300"/>
|
||||
<define name="DDGAIN_Q" value="300"/>
|
||||
<define name="DDGAIN_R" value="300"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="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(180.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="850"/>
|
||||
<define name="PHI_DGAIN" value="400"/>
|
||||
<define name="PHI_IGAIN" value="100"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="850"/>
|
||||
<define name="THETA_DGAIN" value="400"/>
|
||||
<define name="THETA_IGAIN" value="100"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="4000"/>
|
||||
<define name="PSI_DGAIN" value="1500"/>
|
||||
<define name="PSI_IGAIN" value="300"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="300"/>
|
||||
<define name="THETA_DDGAIN" value="300"/>
|
||||
<define name="PSI_DDGAIN" value="1000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="REF_MIN_ZDD" value="-0.2*9.81"/> <!-- max descent acceleration -->
|
||||
<define name="REF_MAX_ZDD" value="0.2*9.81"/> <!-- max climb acceleration -->
|
||||
<define name="REF_MIN_ZD" value="-3."/> <!-- max descent speed -->
|
||||
<define name="REF_MAX_ZD" value="3."/> <!-- max climb speed -->
|
||||
<define name="HOVER_KP" value="120"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="RC_CLIMB_COEF" value ="500"/>
|
||||
<define name="RC_DESCENT_COEF" value ="200"/>
|
||||
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="USE_REF" value="1"/>
|
||||
<define name="USE_SPEED_REF" value="1"/> <!-- using RC to control horizontal setpoint -->
|
||||
<define name="MAX_BANK" value="27" unit="deg"/>
|
||||
<define name="REF_MAX_ACCEL" value="7."/> <!-- max reference horizontal acceleration in m/s2 -->
|
||||
<define name="REF_MAX_SPEED" value="2."/> <!-- max reference horizontal speed in m/s -->
|
||||
<define name="RC_SPEED_DEAD_BAND" value="200000"/>
|
||||
<define name="PGAIN" value="100"/>
|
||||
<define name="DGAIN" value="120"/>
|
||||
<define name="IGAIN" value="10"/>
|
||||
<define name="AGAIN" value="10"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
|
||||
<define name="INITIAL_CONDITITONS" value=""reset00""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CRITIC_BAT_LEVEL" value="14.0" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="14.2" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="16.8" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user