Merge branch 'master' of github.com:paparazzi/paparazzi

Conflicts:
	sw/airborne/math/pprz_geodetic_double.h
This commit is contained in:
Antoine Drouin
2011-02-22 09:37:03 +01:00
1217 changed files with 8515 additions and 112771 deletions
+36
View File
@@ -3,6 +3,7 @@
*.out
*~
*.swp
*.pyc
@@ -16,15 +17,35 @@
*.aux
# Debian related files
*.deb
*.dsc
*.changes
*.substvars
*.debhelper.log
*-stamp
/debian/control
/debian/changelog
/debian/files
/debian/paparazzi-arm7
/debian/paparazzi-avr
/debian/paparazzi-dev
/debian/paparazzi-bin
/sw/lib/ocaml/ivy/debian/changelog
/sw/lib/ocaml/ivy/debian/files
/sw/lib/ocaml/ivy/debian/ivy-ocaml
/var
/dox
/paparazzi
# /conf/
/conf/conf.xml
/conf/conf.xml.20*
/conf/control_panel.xml
/conf/%gconf.xml
/conf/srtm_data/*
# /doc/pprz_algebra/
/doc/pprz_algebra/headfile.log
@@ -77,6 +98,7 @@
# /sw/simulator/
/sw/simulator/gaia
/sw/simulator/simhitl
/sw/simulator/launchsitl
# /sw/supervision/
/sw/supervision/gtk_process.ml
@@ -86,3 +108,17 @@
# /sw/tools/
/sw/tools/fp_parser.ml
/sw/tools/wiki_gen/wiki_gen
# /sw/ground_segment/joystick
/sw/ground_segment/joystick/test_stick
# /sw/airborne/arch/lpc21/test/bootloader
/sw/airborne/arch/lpc21/test/bootloader/bl.dmp
/sw/airborne/arch/lpc21/test/bootloader/bl.hex
/sw/airborne/arch/lpc21/test/bootloader/bl.map
/sw/airborne/arch/lpc21/test/bootloader/bl.elf
/sw/airborne/arch/lpc21/test/bootloader/bl_ram.dmp
/sw/airborne/arch/lpc21/test/bootloader/bl_ram.hex
/sw/airborne/arch/lpc21/test/bootloader/bl_ram.map
/sw/airborne/arch/lpc21/test/bootloader/bl_ram.elf
/sw/airborne/arch/lpc21/test/bootloader/crt.lst
+880 -544
View File
File diff suppressed because it is too large Load Diff
+27 -10
View File
@@ -60,14 +60,14 @@ XSENS_XML = $(CONF)/xsens_MTi-G.xml
TOOLS=$(PAPARAZZI_SRC)/sw/tools
HAVE_ARM_NONE_EABI_GCC := $(shell which arm-none-eabi-gcc)
ifeq ($(strip $(HAVE_ARM_NONE_EABI_GCC)),)
#ARMGCC=/opt/paparazzi/bin/arm-elf-gcc
ARMGCC=/usr/bin/arm-elf-gcc
ARMGCC=$(shell which arm-elf-gcc)
else
ARMGCC=$(HAVE_ARM_NONE_EABI_GCC)
endif
OCAML=$(shell which ocaml)
OCAMLRUN=$(shell which ocamlrun)
all: static conf
all: commands static conf
static : lib center tools cockpit multimon tmtc logalizer lpc21iap sim_static static_h usb_lib
@@ -211,6 +211,7 @@ clean:
rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(DL_PROTOCOL_H)
find . -mindepth 2 -name Makefile -exec sh -c '$(MAKE) -C `dirname {}` $@' \;
find . -name '*~' -exec rm -f {} \;
rm -f paparazzi sw/simulator/launchsitl
cleanspaces:
find ./sw/airborne -name '*.[ch]' -exec sed -i {} -e 's/[ \t]*$$//' \;
@@ -219,16 +220,32 @@ cleanspaces:
find ./sw -name '*.mli' -exec sed -i {} -e 's/[ \t]*$$//' ';'
find ./conf -name '*.xml' -exec sed -i {} -e 's/[ \t]*$$//' ';'
distclean : dist_clean
dist_clean : clean
rm -r conf/srtm_data
ab_clean:
find sw/airborne -name '*~' -exec rm -f {} \;
test_all_example_airframes:
$(MAKE) AIRCRAFT=BOOZ2_A2 clean_ac ap
$(MAKE) AIRCRAFT=MJ5 clean_ac ap sim
$(MAKE) AIRCRAFT=TJ1 clean_ac ap sim
$(MAKE) AIRCRAFT=HITL clean_ac ap
$(MAKE) AIRCRAFT=DM clean_ac ap sim
$(MAKE) AIRCRAFT=CSC clean_ac ap
$(MAKE) AIRCRAFT=BOOZ2_A1 clean_ac ap sim
$(MAKE) AIRCRAFT=Microjet clean_ac ap sim
$(MAKE) AIRCRAFT=Tiny_IMU clean_ac ap
$(MAKE) AIRCRAFT=EasyStar_ETS clean_ac ap sim
commands: paparazzi sw/simulator/launchsitl
paparazzi:
cat src/paparazzi | sed s#OCAMLRUN#$(OCAMLRUN)# | sed s#OCAML#$(OCAML)# > $@
chmod a+x $@
sw/simulator/launchsitl:
cat src/$(@F) | sed s#OCAMLRUN#$(OCAMLRUN)# | sed s#OCAML#$(OCAML)# > $@
chmod a+x $@
#.SUFFIXES: .hgt.zip
%.hgt.zip:
cd data/srtm; $(MAKE) $(@)
+2 -3
View File
@@ -53,14 +53,13 @@ TUNING_H=$(AC_GENERATED)/tuning.h
SUPERVISION=./paparazzi
MAKE=make PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME)
MODULES_H=$(AC_GENERATED)/modules.h
MODULES_DIR=$(PAPARAZZI_HOME)/conf/modules/
AIRCRAFT_MD5=$(AIRCRAFT_CONF_DIR)/aircraft.md5
# "make Q=''" to get full echo
Q=@
init:
@[ -d $(PAPARAZZI_HOME) ] || (echo "Copying config example in your $(PAPARAZZI_HOME) directory"; mkdir -p $(PAPARAZZI_HOME); cp -a conf $(PAPARAZZI_HOME); cp -a data $(PAPARAZZI_HOME); mkdir -p $(PAPARAZZI_HOME)/var/maps; mv $(PAPARAZZI_HOME)/data/maps/trtqtttqtsrrt*.jpg $(PAPARAZZI_HOME)/var/maps; mkdir -p $(PAPARAZZI_HOME)/var/include)
@[ -d $(PAPARAZZI_HOME) ] || (echo "Copying config example in your $(PAPARAZZI_HOME) directory"; mkdir -p $(PAPARAZZI_HOME); cp -a conf $(PAPARAZZI_HOME); cp -a data $(PAPARAZZI_HOME); mkdir -p $(PAPARAZZI_HOME)/var/maps; mkdir -p $(PAPARAZZI_HOME)/var/include)
demo:
$(SUPERVISION)
@@ -132,7 +131,7 @@ $(TUNING_H) : $(SETTINGS_XMLS) $(CONF_XML) $(TOOLS)/gen_tuning.out
$(MODULES_H) : $(CONF)/$(AIRFRAME_XML) $(TOOLS)/gen_modules.out $(CONF)/modules/*.xml
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
@echo BUILD $@
$(Q)$(TOOLS)/gen_modules.out $(MODULES_DIR) $(SETTINGS_MODULES) $< > $@
$(Q)$(TOOLS)/gen_modules.out $(SETTINGS_MODULES) $< > $@
$(Q)chmod a+r $@
$(SETTINGS_MODULES) : $(MODULES_H)
+25 -13
View File
@@ -19,13 +19,11 @@ install_data:
$(INSTALL) -d $(DESTDIR)/data/maps
$(INSTALLDATA) data/maps/muret_UTM.xml data/maps/muret_UTM.gif $(DESTDIR)/data/maps
$(INSTALL) -d $(DESTDIR)/data/pictures/gcs_icons
$(INSTALLDATA) var/maps/trtqtttqtsrrtstq*.jpg var/maps/trtqtttqtsrrttsr*.jpg $(DESTDIR)/data/maps
$(INSTALLDATA) data/pictures/*.gif data/pictures/*.svg data/pictures/*.jpg data/pictures/*.png $(DESTDIR)/data/pictures
$(INSTALLDATA) data/pictures/gcs_icons/*.png $(DESTDIR)/data/pictures/gcs_icons
$(INSTALL) -d $(PREFIX)/usr/share/pixmaps
$(INSTALLDATA) data/pictures/penguin_icon.png $(PREFIX)/usr/share/pixmaps/paparazzi.png
$(INSTALL) -d $(DESTDIR)/data/srtm
$(INSTALLDATA) data/srtm/N43E001.hgt.bz2 $(DESTDIR)/data/srtm
install_conf:
@@ -37,17 +35,27 @@ install_conf:
$(INSTALLDATA) conf/gui.xml $(DESTDIR)/conf/
$(INSTALL) -d $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/airframe.dtd $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/microjet5.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/twinstar1.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/twinjet1.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/tiny_hitl.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/booz2_a2.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/microjet_example.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/twinstar_example.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/twinjet_example.xml $(DESTDIR)/conf/airframes
$(INSTALLDATA) conf/airframes/example_twog_analogimu.xml $(DESTDIR)/conf/airframes
$(INSTALL) -d $(DESTDIR)/conf/autopilot
$(INSTALLDATA) conf/autopilot/*.makefile $(DESTDIR)/conf/autopilot
$(INSTALLDATA) conf/autopilot/*.h $(DESTDIR)/conf/autopilot
$(INSTALL) -d $(DESTDIR)/conf/autopilot/subsystems
$(INSTALLDATA) conf/autopilot/subsystems/*.makefile $(DESTDIR)/conf/autopilot/subsystems
$(INSTALL) -d $(DESTDIR)/conf/autopilot/subsystems/fixedwing
$(INSTALLDATA) conf/autopilot/subsystems/fixedwing/*.makefile $(DESTDIR)/conf/autopilot/subsystems/fixedwing
$(INSTALL) -d $(DESTDIR)/conf/autopilot/subsystems/rotorcraft
$(INSTALLDATA) conf/autopilot/subsystems/rotorcraft/*.makefile $(DESTDIR)/conf/autopilot/subsystems/rotorcraft
$(INSTALL) -d $(DESTDIR)/conf/autopilot/subsystems/shared
$(INSTALLDATA) conf/autopilot/subsystems/shared/*.makefile $(DESTDIR)/conf/autopilot/subsystems/shared
$(INSTALL) -d $(DESTDIR)/conf/flight_plans
$(INSTALLDATA) conf/flight_plans/*.dtd $(DESTDIR)/conf/flight_plans
$(INSTALLDATA) conf/flight_plans/*.xml $(DESTDIR)/conf/flight_plans
$(INSTALL) -d $(DESTDIR)/conf/modules
$(INSTALLDATA) conf/modules/*.dtd $(DESTDIR)/conf/modules
$(INSTALLDATA) conf/modules/*.xml $(DESTDIR)/conf/modules
$(INSTALL) -d $(DESTDIR)/conf/gps
$(INSTALLDATA) conf/gps/Makefile $(DESTDIR)/conf/gps
$(INSTALLDATA) conf/gps/ublox_conf.c $(DESTDIR)/conf/gps
@@ -111,16 +119,12 @@ install_libs:
install_tools:
$(INSTALLDATA) Makefile.ac $(DESTDIR)
$(INSTALL) -d $(DESTDIR)/sw/tools/
$(INSTALLDATA) conf/Makefile* $(DESTDIR)/conf
$(INSTALL) -d $(DESTDIR)/sw/tools/
$(INSTALL) sw/tools/*.out $(DESTDIR)/sw/tools/
rm -f $(DESTDIR)/sw/tools/gen_flight_plan.out
$(INSTALLDATA) sw/tools/fp_syntax.cmo $(DESTDIR)/sw/tools
$(INSTALLDATA) sw/tools/fp_parser.cmo $(DESTDIR)/sw/tools
$(INSTALLDATA) sw/tools/fp_lexer.cmo $(DESTDIR)/sw/tools
$(INSTALLDATA) sw/tools/fp_proc.cmo $(DESTDIR)/sw/tools
$(INSTALLDATA) sw/tools/gen_flight_plan.cmo $(DESTDIR)/sw/tools
$(INSTALLDATA) sw/tools/extract_makefile.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_aircraft.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_airframe.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_messages.ml $(DESTDIR)/sw/tools/
@@ -130,6 +134,14 @@ install_tools:
$(INSTALLDATA) sw/tools/gen_settings.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_tuning.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_ubx.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_xsens.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_modules.ml $(DESTDIR)/sw/tools/
$(INSTALLDATA) sw/tools/gen_common.cmo $(DESTDIR)/sw/tools/
$(INSTALL) -d $(DESTDIR)/sw/tools/calibration
$(INSTALLDATA) sw/tools/calibration/calibrate.py $(DESTDIR)/sw/tools/calibration
$(INSTALLDATA) sw/tools/calibration/calibrate_gyro.py $(DESTDIR)/sw/tools/calibration
$(INSTALLDATA) sw/tools/calibration/calibration_utils.py $(DESTDIR)/sw/tools/calibration
$(INSTALLDATA) sw/tools/calibration/README $(DESTDIR)/sw/tools/calibration
$(INSTALL) -d $(DESTDIR)/sw/ground_segment/lpc21iap
$(INSTALL) sw/ground_segment/lpc21iap/lpc21iap $(DESTDIR)/sw/ground_segment/lpc21iap/
$(INSTALL) -d $(DESTDIR)/sw/simulator
@@ -142,7 +154,7 @@ install_tools:
install_airborne_sources:
$(INSTALL) -d $(DESTDIR)/sw/
tar --exclude=CVS -cf - sw/airborne/ | tar -C $(DESTDIR) -xf -
tar -cf - sw/airborne/ | tar -C $(DESTDIR) -xf -
$(INSTALL) -d $(DESTDIR)/sw/include
$(INSTALLDATA) sw/include/std.h $(DESTDIR)/sw/include
$(INSTALLDATA) var/include/*.h $(DESTDIR)/sw/include
+1 -1
View File
@@ -35,7 +35,7 @@ CC = g++
endif
OCAMLC = ocamlc
SIMDIR = $(PAPARAZZI_SRC)/sw/simulator
CAMLINCLUDES = -I +lablgtk2 -I $(PAPARAZZI_SRC)/sw/lib/ocaml -I $(SIMDIR) -I +xml-light
CAMLINCLUDES = $(shell ocamlfind query -r -i-format lablgtk2) -I $(PAPARAZZI_SRC)/sw/lib/ocaml -I $(SIMDIR) $(shell ocamlfind query -r -i-format xml-light)
SIMSITLML = $(OBJDIR)/simsitl.ml
MYGTKINITCMO = myGtkInit.cmo
SITLCMA = $(SIMDIR)/sitl.cma
+49 -12
View File
@@ -53,6 +53,18 @@ SIZE = $(GCC_BIN_PREFIX)-size
RM = rm
OOCD = $(TOOLCHAIN_DIR)/bin/openocd
# If we can't find the toolchain then try picking up the compilers from the path
ifeq ($(TOOLCHAIN_DIR),)
CC = $(shell which arm-none-eabi-gcc)
LD = $(shell which arm-none-eabi-gcc)
CP = $(shell which arm-none-eabi-objcopy)
DMP = $(shell which arm-none-eabi-objdump)
NM = $(shell which arm-none-eabi-nm)
SIZE = $(shell which arm-none-eabi-size)
OOCD = $(shell which openocd)
GCC_LIB_DIR=$(shell dirname `which arm-none-eabi-gcc`)/../arm-none-eabi/lib
endif
LOADER=/home/poine/work/stm32/stm32loader-a3c51c26ad6c/stm32loader.py
ifndef $(TARGET).OOCD_INTERFACE
@@ -87,14 +99,20 @@ LDSCRIPT = $($(TARGET).LDSCRIPT)
endif
endif
CFLAGS = -I. -I./$(ARCH) $(INCLUDES) -D__thumb2__ -Wall -c -msoft-float -O$(OPT)
UNAME = $(shell uname -s)
CFLAGS = -I. -I./$(ARCH) $(INCLUDES) -D__thumb2__ -Wall -msoft-float -O$(OPT)
CFLAGS += -Wl,gc-sections
CFLAGS += -mcpu=$(MCU) -mthumb -ansi
ifeq ("$(UNAME)","Darwin")
CFLAGS += -mfix-cortex-m3-ldrd
endif
CFLAGS += -std=gnu99
#CFLAGS += -malignment-traps
CFLAGS += -fno-common -g$(DEBUG)
CFLAGS += -fno-common
CFLAGS += -g$(DEBUG)
CFLAGS += -ffunction-sections -fdata-sections
CFLAGS += -Wall -Wimplicit
CFLAGS += -Wimplicit
CFLAGS += -Wcast-align
CFLAGS += -Wpointer-arith -Wswitch
CFLAGS += -Wredundant-decls -Wreturn-type -Wshadow -Wunused
@@ -108,9 +126,16 @@ CFLAGS += -Wswitch-default
CFLAGS += $($(TARGET).CFLAGS)
AFLAGS = -ahls -mapcs-32
ifeq ("$(UNAME)","Darwin")
AFLAGS += -mcpu=$(MCU) -mthumb
endif
AFLAGS += -x assembler-with-cpp -Wa,-adhlns=$(OBJDIR)/$(<:.S=.lst),--g$(DEBUG)
ifeq ("$(UNAME)","Darwin")
LDFLAGS = -T$(LDSCRIPT) -nostartfiles -O$(OPT) --gc-sections -mthumb -march=armv7 -mfix-cortex-m3-ldrd -msoft-float
else
LDFLAGS = -D__thumb2__ -T$(LDSCRIPT) -nostartfiles -L$(GCC_LIB_DIR) -O$(OPT) --gc-sections
endif
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(TARGET).map,--cref,--gc-sections
LDLIBS += -lc -lm -lgcc -lcmsis -lstm32
@@ -123,7 +148,17 @@ ODFLAGS = -S
# Default target.
all: sizebefore build sizeafter
all: printcommands sizebefore build sizeafter
printcommands:
@echo "Using CC = $(CC)"
@echo "Using LD = $(LD)"
@echo "Using CP = $(CP)"
@echo "Using DMP = $(DMP)"
@echo "Using NM = $(NM)"
@echo "Using SIZE = $(SIZE)"
@echo "Using RM = $(RM)"
@echo "Using OOCD = $(OOCD)"
build: elf bin hex
# lss sym
@@ -188,15 +223,17 @@ ifeq ($(FLASH_MODE),SERIAL)
upload: $(OBJDIR)/$(TARGET).bin
$(LOADER) -p /dev/ttyUSB0 -b 115200 -e -w -v $^
else ifeq ($(FLASH_MODE),JTAG)
upload: $(OBJDIR)/$(TARGET).bin
@echo -e " OOCD\t$<"
upload: $(OBJDIR)/$(TARGET).elf
@echo " OOCD\t$<"
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg \
-c init \
-c "reset halt" \
-c "flash write_image erase $(OBJDIR)/$(TARGET).bin 0x08000000" \
-c reset \
-c shutdown
-f board/$(OOCD_BOARD).cfg \
-c init \
-c "reset halt" \
-c "reset init" \
-c "stm32x mass_erase 0" \
-c "flash write_image $<" \
-c reset \
-c shutdown
else
upload:
@echo unknown flash_mode $(FLASH_MODE)
+11 -11
View File
@@ -166,10 +166,10 @@
<modules>
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="3"/>
<param name="LIGHT_LED_NAV" value="4"/>
<param name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<param name="NAV_LIGHT_MODE_DEFAULT" value="0"/>
<define name="LIGHT_LED_STROBE" value="3"/>
<define name="LIGHT_LED_NAV" value="4"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="NAV_LIGHT_MODE_DEFAULT" value="0"/>
</load>
</modules>
@@ -185,8 +185,8 @@
<!-- Communication -->
<subsystem name="telemetry" type="transparent">
<param name="MODEM_UART_NR" value="2"/>
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART2"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<!-- Actuators -->
@@ -194,14 +194,14 @@
<!-- Sensors -->
<subsystem name="radio_control" type="ppm"/>
<!--<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_1"/>
<param name="ADC_IR2" value="ADC_2"/>
<param name="ADC_IR_TOP" value="ADC_0"/>
<param name="ADC_IR_NB_SAMPLES" value="16"/>
<configure name="ADC_IR1" value="ADC_1"/>
<configure name="ADC_IR2" value="ADC_2"/>
<configure name="ADC_IR_TOP" value="ADC_0"/>
<configure name="ADC_IR_NB_SAMPLES" value="16"/>
</subsystem>-->
<subsystem name="gps" type="ublox_lea4p">
<param name="GPS_UART_NR" value="1"/>
<configure name="GPS_PORT" value="UART1"/>
</subsystem>
</firmware>
+5 -5
View File
@@ -161,10 +161,10 @@
<modules>
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="3"/>
<param name="LIGHT_LED_NAV" value="4"/>
<param name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<param name="NAV_LIGHT_MODE_DEFAULT" value="0"/>
<define name="LIGHT_LED_STROBE" value="3"/>
<define name="LIGHT_LED_NAV" value="4"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="NAV_LIGHT_MODE_DEFAULT" value="0"/>
</load>
</modules>
@@ -179,7 +179,7 @@
<!-- Communication -->
<subsystem name="telemetry" type="transparent">
<param name="MODEM_BAUD" value="B9600"/>
<configure name="MODEM_BAUD" value="B9600"/>
</subsystem>
<!-- Actuators -->
+4 -4
View File
@@ -221,7 +221,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -233,11 +233,11 @@ ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_AUTO1
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
#TRANSPARENT
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B9600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
@@ -269,7 +269,7 @@ ap.srcs += subsystems/navigation/snav.c
# include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_h_ctl_a.c fw_v_ctl.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c
+3 -3
View File
@@ -213,7 +213,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -225,7 +225,7 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
@@ -262,7 +262,7 @@ ap.CFLAGS += -DUSE_MODULES
# Config for SITL simulation
#include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_h_ctl.c fw_v_ctl.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
+6 -6
View File
@@ -232,7 +232,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -244,11 +244,11 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B9600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
#TRANSPARENT
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
@@ -298,7 +298,7 @@ ap.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150
# Config for SITL simulation
#include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_h_ctl.c fw_v_ctl.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
@@ -317,8 +317,8 @@ sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_re
# a test program to setup actuators
setup_actuators.ARCHDIR = $(ARCHI)
setup_actuators.CFLAGS += -DFBW -DBOARD_CONFIG=\"tiny.h\" -DLED -DTIME_LED=1 -DACTUATORS=\"servos_4015_hw.h\" -DSERVOS_4015 -DUSE_UART1 -DUART1_BAUD=B9600 -DDATALINK=PPRZ -DPPRZ_UART=Uart1
setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c setup_actuators.c $(SRC_ARCH)/uart_hw.c $(SRC_ARCH)/servos_4015_hw.c main.c
setup_actuators.CFLAGS += -DFBW -DBOARD_CONFIG=\"tiny.h\" -DUSE_LED -DTIME_LED=1 -DACTUATORS=\"servos_4015_hw.h\" -DSERVOS_4015 -DUSE_UART1 -DUART1_BAUD=B9600 -DDATALINK=PPRZ -DPPRZ_UART=Uart1
setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c setup_actuators.c $(SRC_ARCH)/mcu_periph/uart_arch.c $(SRC_ARCH)/servos_4015_hw.c main.c
</makefile>
</airframe>
+10 -10
View File
@@ -14,15 +14,15 @@
<modules>
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="5"/>
<param name="LIGHT_LED_NAV" value="3"/>
<define name="LIGHT_LED_STROBE" value="5"/>
<define name="LIGHT_LED_NAV" value="3"/>
</load>
<load name="infrared_i2c.xml"/>
<load name="pbn.xml"/>
<!--load name="airspeed_adc.xml">
<define name="ADC_AIRSPEED" value="ADC_4"/>
<flag name="AIRSPEED_SCALE" value="1"/>
<flag name="AIRSPEED_BIAS" value="0"/>
<configure name="ADC_AIRSPEED" value="ADC_4"/>
<define name="AIRSPEED_SCALE" value="1"/>
<define name="AIRSPEED_BIAS" value="0"/>
</load-->
<!--load name="airspeed_ets.xml"/>
<load name="baro_ets.xml"/-->
@@ -36,7 +36,7 @@
<target name="sim" board="pc"/>
<target name="ap" board="tiny_2.11">
<param name="FLASH_MODE" value="IAP"/>
<configure name="FLASH_MODE" value="IAP"/>
</target>
<subsystem name="radio_control" type="ppm"/>
@@ -51,11 +51,11 @@
<!-- Sensors -->
<subsystem name="gps" type="ublox_lea5h"/>
<subsystem name="gyro" type="roll">
<param name="ADC_GYRO_ROLL" value="ADC_5"/>
<configure name="ADC_GYRO_ROLL" value="ADC_5"/>
</subsystem>
<subsystem name="current_sensor">
<param name="ADC_CURRENT_SENSOR" value="ADC_3"/>
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
</subsystem>
<subsystem name="navigation"/>
@@ -106,8 +106,8 @@
<section name="INFRARED" prefix="IR_">
<define name="IR1_NEUTRAL" value="-15"/>
<define name="IR2_NEUTRAL" value="0"/>
<define name="TOP_NEUTRAL" value="-20"/>
<define name="IR2_NEUTRAL" value="10"/>
<define name="TOP_NEUTRAL" value="-15"/>
<define name="I2C_DEFAULT_CONF" value="1"/>
<define name="LATERAL_CORRECTION" value="1"/>
+12 -17
View File
@@ -14,8 +14,8 @@
<modules>
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="5"/>
<param name="LIGHT_LED_NAV" value="3"/>
<define name="LIGHT_LED_STROBE" value="5"/>
<define name="LIGHT_LED_NAV" value="3"/>
</load>
<load name="infrared_i2c.xml"/>
<load name="pbn.xml"/>
@@ -23,20 +23,15 @@
</modules>
<firmware name="fixedwing">
<target name="sim" board="pc">
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<define name="PITCH_TRIM"/>
<define name="USE_I2C0"/>
<define name="USE_AIRSPEED"/>
</target>
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<define name="PITCH_TRIM"/>
<define name="USE_I2C0"/>
<define name="USE_AIRSPEED"/>
<target name="sim" board="pc"/>
<target name="ap" board="tiny_2.11">
<param name="FLASH_MODE" value="IAP"/>
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<define name="PITCH_TRIM"/>
<define name="USE_I2C0"/>
<define name="USE_AIRSPEED"/>
<configure name="FLASH_MODE" value="IAP"/>
<define name="SPI_MASTER"/>
<define name="USE_SPI_SLAVE0"/>
</target>
@@ -54,11 +49,11 @@
<!-- Sensors -->
<subsystem name="gps" type="ublox_lea5h"/>
<subsystem name="gyro" type="roll">
<param name="ADC_GYRO_ROLL" value="ADC_5"/>
<configure name="ADC_GYRO_ROLL" value="ADC_5"/>
</subsystem>
<subsystem name="current_sensor">
<param name="ADC_CURRENT_SENSOR" value="ADC_3"/>
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
</subsystem>
<subsystem name="navigation"/>
@@ -0,0 +1,234 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<!-- Funjet Multiplex (http://www.multiplex-rc.de/)
Tiny 2.11 board (http://paparazzi.enac.fr/wiki/Tiny_v2)
IR i2c
Tilted infrared sensor (http://paparazzi.enac.fr/wiki/Image:Tiny_v2_1_Funjet.jpg)
Radiotronix modem
LEA 5H GPS
Airspeed sensor
Digital camera
-->
<airframe name="Funjet Tiny 2.11">
<modules>
<load name="light.xml">
<define name="LIGHT_LED_STROBE" value="5"/>
<define name="LIGHT_LED_NAV" value="3"/>
</load>
<load name="infrared_i2c.xml"/>
<load name="pbn.xml"/>
<load name="ins_vn100.xml"/>
</modules>
<firmware name="fixedwing">
<define name="AGR_CLIMB"/>
<define name="ALT_KALMAN"/>
<define name="PITCH_TRIM"/>
<define name="USE_I2C0"/>
<define name="USE_AIRSPEED"/>
<target name="sim" board="pc"/>
<target name="ap" board="tiny_2.11">
<configure name="FLASH_MODE" value="IAP"/>
<define name="SPI_MASTER"/>
<define name="USE_SPI_SLAVE0"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<!--subsystem name="joystick"/-->
<subsystem name="i2c"/>
<subsystem name="spi"/>
<!-- Communication -->
<subsystem name="telemetry" type="transparent"/>
<!-- Actuators are automatically chosen according to board-->
<subsystem name="control" type="new"/>
<!-- Sensors -->
<subsystem name="gps" type="ublox_lea5h"/>
<subsystem name="gyro" type="roll">
<configure name="ADC_GYRO_ROLL" value="ADC_5"/>
</subsystem>
<subsystem name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
</subsystem>
<subsystem name="navigation"/>
</firmware>
<firmware name="setup">
<target name="tunnel" board="tiny_2.11"/>
<target name="setup_actuators" board="tiny_2.11"/>
</firmware>
<!-- commands section -->
<servos>
<servo name="MOTOR" no="0" min="1040" neutral="1040" max="2000"/>
<servo name="AILEVON_LEFT" no="2" min="1900" neutral="1500" max="1050"/>
<servo name="AILEVON_RIGHT" no="6" min="1120" neutral="1540" max="1980"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
</rc_commands>
<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.75"/>
</section>
<command_laws>
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/>
<set servo="AILEVON_RIGHT" value="$elevator - $aileron"/>
</command_laws>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.85"/>
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="INFRARED" prefix="IR_">
<define name="IR1_NEUTRAL" value="-5"/>
<define name="IR2_NEUTRAL" value="0"/>
<define name="TOP_NEUTRAL" value="-10"/>
<define name="I2C_DEFAULT_CONF" value="1"/>
<define name="LATERAL_CORRECTION" value="1"/>
<define name="LONGITUDINAL_CORRECTION" value="1"/>
<define name="VERTICAL_CORRECTION" value="1"/>
<define name="HORIZ_SENSOR_TILTED" value="1"/>
<define name="IR1_SIGN" value="1"/>
<define name="IR2_SIGN" value="1"/>
<define name="TOP_SIGN" value="1"/>
<define name="ROLL_NEUTRAL_DEFAULT" value="2." unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="2." unit="deg"/>
</section>
<section name="GYRO" prefix="GYRO_">
<define name="ADC_ROLL_NEUTRAL" value="487"/>
<define name="ADXRS300_RESISTOR_BRIDGE" value="(3.3/(3.3+1.8))"/>
<define name="ADXRS300_SENSITIVITY" value="5" unit="mV/(deg/s)"/>
<define name="ROLL_SCALE" value="3.3*1000./1024./(GYRO_ADXRS300_SENSITIVITY*GYRO_ADXRS300_RESISTOR_BRIDGE)" unit="deg/s/adc_unit"/>
<define name="ROLL_DIRECTION" value="1."/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="10000."/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MilliAmpereOfAdc(_adc)" value="(_adc-156)*17.4"/>
</section>
<section name="MISC">
<define name="NOMINAL_AIRSPEED" value="16." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_RATE" value="60" unit="Hz"/>
<define name="ALT_KALMAN_ENABLED" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!--define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/-->
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="-0.06"/> <!-- -0.024 -->
<!-- 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="-1000"/-->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.2" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="-0.02"/>
<define name="AUTO_THROTTLE_IGAIN" value="-0.01"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.1"/>
<!-- auto pitch inner loop -->
<define name="AUTO_PITCH_PGAIN" value="-0.05"/>
<define name="AUTO_PITCH_DGAIN" value="-0.0"/>
<define name="AUTO_PITCH_IGAIN" value="-0.01"/>
<!--define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.14"/-->
<define name="AUTO_PITCH_MAX_PITCH" value="0.35"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
<!-- airspeed control -->
<define name="AUTO_AIRSPEED_SETPOINT" value="16."/>
<define name="AUTO_AIRSPEED_PGAIN" value="0.08"/>
<define name="AUTO_AIRSPEED_IGAIN" value="0.001"/>
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
<define name="AIRSPEED_MAX" value="22"/>
<define name="AIRSPEED_MIN" value="12"/>
<!-- pitch trim -->
<define name="PITCH_LOITER_TRIM" value="RadOfDeg(5.)"/>
<define name="PITCH_DASH_TRIM" value="RadOfDeg(-5.)"/>
<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="-9000."/>
<define name="ROLL_RATE_GAIN" value="-3000."/>
<define name="ROLL_IGAIN" value="-0"/>
<define name="ROLL_KFFA" value="0"/>
<define name="ROLL_KFFD" value="0"/>
<define name="PITCH_PGAIN" value="-20000."/>
<define name="PITCH_DGAIN" value="-1000"/>
<define name="PITCH_IGAIN" value="-300"/>
<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="0"/>
</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"/>
</section>
</airframe>
+11 -10
View File
@@ -10,20 +10,16 @@
<airframe name="Merlin">
<firmware name="fixedwing">
<target name="ap" board="tiny_2.11">
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
</target>
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
<target name="sim" board="pc">
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
</target>
<target name="ap" board="tiny_2.11"/>
<target name="sim" board="pc"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="control_new"/>
<subsystem name="attitude" type="infrared"/>
<subsystem name="control"/>
<!--subsystem name="attitude" type="infrared"/-->
<subsystem name="gps" type="ublox_lea5h"/>
<subsystem name="navigation"/>
</firmware>
@@ -33,6 +29,10 @@
<target name="setup_actuators" board="tiny_2.11" />
</firmware>
<modules>
<load name="infrared_adc.xml"/>
</modules>
<!-- commands section -->
<servos>
<servo name="AILERON_RIGHT" no="0" min="1900" neutral="1500" max="1100"/>
@@ -169,6 +169,7 @@
<define name="PITCH_KFFD" value="0."/>
<define name="PITCH_OF_ROLL" value="RadOfDeg(0.2)"/>
<define name="ELEVATOR_OF_ROLL" value="0"/>
</section>
<section name="NAV">
+46 -66
View File
@@ -1,19 +1,54 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">
<airframe name="MiniMag Tiny 0.99">
<airframe name="MiniMag Tiny 2.11">
<firmware name="fixedwing">
<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />
<define name="ALT_KALMAN" />
<target name="sim" board="pc" />
<target name="ap" board="tiny_2.11">
<define name="SPI_MASTER"/>
<define name="USE_SPI_SLAVE0"/>
</target>
<subsystem name="spi"/>
<!--subsystem name="i2c">
<define name="USE_I2C0"/>
</subsystem-->
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600" />
</subsystem>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="navigation" />
<!-- <subsystem name="attitude" type="infrared"/>-->
<subsystem name="control"/>
<subsystem name="gps" type="ublox_lea5h"/>
</firmware>
<firmware name="setup">
<target name="tunnel" board="tiny_2.11" />
<target name="setup_actuators" board="tiny_2.11" />
</firmware>
<modules>
<load name="ins_vn100.xml" />
</modules>
<!-- commands section -->
<servos>
<servo name="THROTTLE" no="0" min="1200" neutral="1200" max="2000"/>
<!-- Servo aileron gauche = couleur blanche -->
<!-- Aileron gauche oppose de l'aileron droit -->
<servo name="AILERON_LEFT" no="1" min="1775" neutral="1500" max="1050"/>
<servo name="AILERON_LEFT" no="4" min="1775" neutral="1500" max="1050"/>
<!-- max = valeur aileron vers le bas-->
<servo name="AILERON_RIGHT" no="3" min="1875" neutral="1475" max="1225"/>
<!-- Rudder = Couleur rouge droite gauche -->
<servo name="RUDDER" no="4" min="1875" neutral="1500" max="1250"/>
<servo name="ELEVATOR" no="5" min="1850" neutral="1586" max="1150"/>
<servo name="RUDDER" no="6" min="1875" neutral="1500" max="1250"/>
<servo name="ELEVATOR" no="7" min="1850" neutral="1586" max="1150"/>
</servos>
<commands>
@@ -51,11 +86,9 @@
<define name="MAX_PITCH" value="0.6"/>
</section>
<section name="adc" prefix="ADC_CHANNEL_">
<define name="IR1" value="ADC_0"/>
<define name="IR2" value="ADC_1"/>
<define name="IR_TOP" value="ADC_4"/>
<define name="IR_NB_SAMPLES" value="16"/>
<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="INFRARED" prefix="IR_">
@@ -98,7 +131,6 @@
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="-0.07"/>
@@ -123,7 +155,6 @@
<define name="AUTO_PITCH_MIN_PITCH" value="-0.35"/>
<define name="THROTTLE_SLEW" value="0.05"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
@@ -138,7 +169,6 @@
<define name="PITCH_PGAIN" value="-9000."/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="1250"/>
</section>
<section name="NAV">
@@ -155,64 +185,14 @@
<define name="DESCENT_PITCH" value="-0.25"/><!-- Pitch for Aggressive Decent -->
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
<define name="DESCENT_NAV_RATIO" value="1.0"/>
</section>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="1" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
</section>
<section name="DATALINK" prefix="DATALINK_">
<define name="DEVICE_TYPE" value="XBEE"/>
<define name="DEVICE_ADDRESS" value="...."/>
</section>
<makefile>
include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_0_99.h\" -DLED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
ap.CFLAGS += -DACTUATORS=\"servos_4015_MAT_hw.h\" -DSERVOS_4015_MAT
ap.srcs += $(SRC_ARCH)/servos_4015_MAT_hw.c actuators.c
ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DXBEE_UART=Uart0 -DDATALINK=XBEE -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
#TRANSPARENT ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
#TRANSPARENT ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_4
ap.srcs += $(SRC_ARCH)/adc_hw.c
ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B19200
ap.srcs += gps_ubx.c gps.c latlong.c
ap.CFLAGS += -DUSE_INFRARED -DALT_KALMAN
ap.srcs += infrared.c estimator.c
ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM
ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c subsystems/navigation/nav_survey_rectangle.c subsystems/navigation/nav_line.c
# Config for SITL simulation
include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
sim.srcs += subsystems/navigation/nav_survey_rectangle.c subsystems/navigation/nav_line.c
</makefile>
</airframe>
+5 -5
View File
@@ -201,7 +201,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_0_99.h\" -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_0_99.h\" -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -213,7 +213,7 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
#ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DXBEE_UART=Uart0 -DDATALINK=XBEE -DUART0_BAUD=B9600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
# AEROCOMM
# ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B57600
@@ -221,7 +221,7 @@ ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
# RADIOTRONIX
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
@@ -241,7 +241,7 @@ ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM
ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c subsystems/navigation/nav_survey_rectangle.c subsystems/navigation/traffic_info.c subsystems/navigation/nav_line.c
# Camera power switch on ADC_7 pin
ap.CFLAGS += -DLED_3_BANK=0 -DLED_3_PIN=10 -DPOWER_SWITCH_LED=3
ap.CFLAGS += -DUSE_LED_3_BANK=0 -DUSE_LED_3_PIN=10 -DPOWER_SWITCH_LED=3
ap.CFLAGS += -DUSE_GYRO -DADXRS150
@@ -271,7 +271,7 @@ ap.CFLAGS += -D BARO_MS5534A_W1=0xAC20 -D BARO_MS5534A_W2=0x87D9 -D BARO_MS5534A
# Config for SITL simulation
#include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_v_ctl.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN -DUSE_BARO_MS5534A
+3 -3
View File
@@ -179,7 +179,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_0_99.h\" -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_0_99.h\" -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -191,10 +191,10 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
#XBEE ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DXBEE_UART=Uart0 -DDATALINK=XBEE -DUART0_BAUD=B9600
#XBEE ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
#XBEE ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
@@ -206,7 +206,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -218,7 +218,7 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
@@ -253,7 +253,7 @@ ap.CFLAGS += -DUSE_MODULES
# Config for SITL simulation
#include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_h_ctl_a.c fw_v_ctl.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
+5 -5
View File
@@ -212,7 +212,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -225,7 +225,7 @@ ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
#TRANSPARENT
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B57600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
@@ -253,7 +253,7 @@ ap.CFLAGS += -DUSE_ADC_3 -DADC_CHANNEL_CURRENT=ADC_3
# Config for SITL simulation
#include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_h_ctl.c fw_v_ctl.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN
@@ -274,8 +274,8 @@ jsbsim.srcs += $(SIMDIR)/sim_ac_fw.c
# a test program to setup actuators
setup_actuators.ARCHDIR = $(ARCHI)
setup_actuators.CFLAGS += -DFBW -DBOARD_CONFIG=\"tiny.h\" -DLED -DTIME_LED=1 -DACTUATORS=\"servos_4015_hw.h\" -DSERVOS_4015 -DUSE_UART1 -DUART1_BAUD=B9600 -DDATALINK=PPRZ -DPPRZ_UART=Uart1
setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c setup_actuators.c $(SRC_ARCH)/uart_hw.c $(SRC_ARCH)/servos_4015_hw.c main.c
setup_actuators.CFLAGS += -DFBW -DBOARD_CONFIG=\"tiny.h\" -DUSE_LED -DTIME_LED=1 -DACTUATORS=\"servos_4015_hw.h\" -DSERVOS_4015 -DUSE_UART1 -DUART1_BAUD=B9600 -DDATALINK=PPRZ -DPPRZ_UART=Uart1
setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c setup_actuators.c $(SRC_ARCH)/mcu_periph/uart_arch.c $(SRC_ARCH)/servos_4015_hw.c main.c
</makefile>
</airframe>
+11 -16
View File
@@ -15,25 +15,20 @@
<!--load name="max3100.xml"/>
<load name="gsm.xml"/-->
<load name="demo_module.xml">
<flag name="TEST" value="1"/>
<flag name="TEST_FLAG"/>
<define name="TEST" value="1"/>
<define name="TEST_FLAG"/>
</load>
<!--load name="enose.xml"/-->
<load name="light.xml"/>
</modules>
<firmware name="fixedwing">
<target name="ap" board="tiny_2.11">
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="USE_I2C0"/>
</target>
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="USE_I2C0"/>
<target name="sim" board="pc">
<define name="PITCH_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="USE_I2C0"/>
</target>
<target name="ap" board="tiny_2.11"/>
<target name="sim" board="pc"/>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="xbee_api"/>
@@ -230,7 +225,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.CFLAGS += -DINTER_MCU
@@ -247,11 +242,11 @@ ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
########## Modems
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
#TRANSPARENT
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B9600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
########## ADC
ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 -DUSE_ADC_3
@@ -303,7 +298,7 @@ ap.CFLAGS += -DUSE_MODULES
#include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
sim.ARCHDIR = $(ARCHI)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DUSE_LED -DWIND_INFO
sim.srcs = latlong.c radio_control.c downlink.c commands.c gps.c inter_mcu.c infrared.c fw_h_ctl_a.c fw_v_ctl_n.c subsystems/nav.c estimator.c sys_time.c main_fbw.c main_ap.c datalink.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/ivy_transport.c $(SRC_ARCH)/sim_adc_generic.c $(SRC_ARCH)/led_hw.c
sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DPITCH_TRIM -DALT_KALMAN
+15 -19
View File
@@ -1,20 +1,34 @@
<airframe name="Blender">
<modules main_freq="512">
<load name="booz_pwm.xml">
<define name="USE_PWM1"/>
</load>
<load name="booz_drop.xml"/>
<load name="booz_cam.xml"/>
<!--load name="sonar_maxbotix_booz.xml"/-->
</modules>
<firmware name="rotorcraft">
<define name="USE_INS_NAV_INIT"/>
<define name="USE_ADAPT_HOVER"/>
<define name="NO_FUCKING_STARTUP_DELAY"/>
<!--define name="GUIDANCE_H_USE_REF"/-->
<target name="ap" board="booz_1.0">
<define name="FAILSAFE_GROUND_DETECT"/>
<define name="USE_GPS_ACC4R"/>
<define name="BOOZ_START_DELAY" value="3"/>
<!--define name="BOOZ_ACTUATORS_MAX_THRUST" value="160"/-->
<!--define name="BOOZ_THRUST_LOWPASS" value="17"/-->
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<!--define name="NPS_NO_SUPERVISION"/-->
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="asctec"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
@@ -218,7 +232,7 @@
<define name="BOOZ_ANALOG_BARO_THRESHOLD" value="800"/>
<define name="FACE_REINJ_1" value="1024"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="10."/>
<define name="BoozDropPwm(_v)" value="Booz2SetPwm1Value(_v)"/>
<define name="BoozDropPwm(_v)" value="BoozSetPwm1Value(_v)"/>
<define name="IMU_MAG_OFFSET" value="-9."/>
</section>
@@ -228,22 +242,4 @@
<define name="ALT_SHIFT_MINUS" value="-1"/>
</section>
<makefile location="after">
ap.CFLAGS += -DGUIDANCE_H_USE_REF
ap.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT -DBOOZ_START_DELAY=3 -DUSE_PWM1
ap.CFLAGS += -DBOOZ_ACTUATORS_MAX_THRUST=160 -DBOOZ_THRUST_LOWPASS=17
ap.srcs += $(SRC_BOOZ_ARCH)/booz2_pwm_hw.c
sim.CFLAGS += -DBSM_PARAMS=\"booz_sensors_model_params_booz2_a2.h\"
sim.CFLAGS += -DNPS_NO_SUPERVISION
sim.CFLAGS += -DGUIDANCE_H_USE_REF
sim.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT -DBOOZ_START_DELAY=3
sim.srcs += $(SRC_BOOZ_SIM)/booz2_pwm_hw.c
</makefile>
</airframe>
+14 -19
View File
@@ -1,6 +1,7 @@
<airframe name="BOOZ2_G1">
<modules main_freq="512">
<!--load name="booz_pwm.xml"/-->
<!--load name="booz_drop.xml"/-->
<!--load name="booz_cam.xml"/-->
<!--load name="sonar_maxbotix_booz.xml"/-->
@@ -9,17 +10,28 @@
</modules>
<firmware name="rotorcraft">
<define name="USE_INS_NAV_INIT"/>
<define name="USE_ADAPT_HOVER"/>
<define name="NO_FUCKING_STARTUP_DELAY"/>
<!--define name="GUIDANCE_H_USE_REF"/-->
<target name="ap" board="booz_1.0">
<define name="BOOZ_FAILSAFE_GROUND_DETECT"/>
<define name="FAILSAFE_GROUND_DETECT"/>
<define name="USE_GPS_ACC4R"/>
<define name="BOOZ_START_DELAY" value="3"/>
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
<!--define name="NPS_NO_SUPERVISION"/-->
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="asctec"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_BAUD" value="B57600"/>
</subsystem>
<subsystem name="ahrs" type="cmpl"/>
<subsystem name="ins" type="hff"/>
</firmware>
@@ -220,21 +232,4 @@
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
<makefile location="after">
ap.CFLAGS += -DGUIDANCE_H_USE_REF
ap.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT -DBOOZ_START_DELAY=3
ap.srcs += $(SRC_BOOZ_ARCH)/booz2_pwm_hw.c
sim.CFLAGS += -DBSM_PARAMS=\"booz_sensors_model_params_booz2_a2.h\"
sim.CFLAGS += -DNPS_NO_SUPERVISION
sim.CFLAGS += -DGUIDANCE_H_USE_REF
sim.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT -DBOOZ_START_DELAY=3
sim.srcs += $(SRC_BOOZ_SIM)/booz2_pwm_hw.c
</makefile>
</airframe>
+243
View File
@@ -0,0 +1,243 @@
<!--DOCTYPE airframe SYSTEM "../../airframe.dtd"-->
<airframe name="BOOZ2_G1">
<modules main_freq="512">
<!--load name="vision_cmucam.xml"/-->
<load name="sonar_maxbotix_booz.xml"/>
<load name="booz_extra_dl.xml"/>
<load name="booz_gumstix_com.xml"/>
</modules>
<servos min="0" neutral="0" max="0xff">
<servo name="PITCH" no="0" min="0" neutral="0" max="255"/>
<servo name="ROLL" no="1" min="0" neutral="0" max="255"/>
<servo name="YAW" no="2" min="0" neutral="0" max="255"/>
<servo name="THRUST" no="3" min="0" neutral="0" max="255"/>
</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="SUPERVISION" prefix="SUPERVISION_">
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="6"/>
<define name="TRIM_R" value="0"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_CHAN" value="1"/>
<define name="GYRO_Q_CHAN" value="0"/>
<define name="GYRO_R_CHAN" value="2"/>
<define name="GYRO_P_NEUTRAL" value="32238"/>
<define name="GYRO_Q_NEUTRAL" value="32391"/>
<define name="GYRO_R_NEUTRAL" value="32853"/>
<define name="GYRO_P_SENS" value="1.00" integer="16"/>
<define name="GYRO_Q_SENS" value="1.00" integer="16"/>
<define name="GYRO_R_SENS" value="1.00" integer="16"/>
<define name="ACCEL_X_CHAN" value="5"/>
<define name="ACCEL_Y_CHAN" value="3"/>
<define name="ACCEL_Z_CHAN" value="4"/>
<define name="ACCEL_X_SENS" value="2.55975587" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.55643340" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.57178460" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="33067"/>
<define name="ACCEL_Y_NEUTRAL" value="32778"/>
<define name="ACCEL_Z_NEUTRAL" value="32140"/>
<define name="MAG_X_CHAN" value="0"/>
<define name="MAG_Y_CHAN" value="1"/>
<define name="MAG_Z_CHAN" value="2"/>
<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_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="BODY_TO_IMU_PHI" value="RadOfDeg(1.3)"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg(-2.6)"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg(0.)"/>
</section>
<section name="STABILIZATION_RATE" prefix="BOOZ_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="BOOZ_STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_THETA" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="RadOfDeg(800)"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="RadOfDeg(300.)"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="RadOfDeg(800)"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="RadOfDeg(300.)"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="RadOfDeg(500)"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="RadOfDeg(90.)"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="-2000"/>
<define name="PHI_DGAIN" value="-400"/>
<define name="PHI_IGAIN" value="-200"/>
<define name="THETA_PGAIN" value="-2000"/>
<define name="THETA_DGAIN" value="-400"/>
<define name="THETA_IGAIN" value="-200"/>
<define name="PSI_PGAIN" value="-1000"/>
<define name="PSI_DGAIN" value="-350"/>
<define name="PSI_IGAIN" value="-10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 300"/>
<define name="THETA_DDGAIN" value=" 300"/>
<define name="PSI_DDGAIN" value=" 300"/>
</section>
<section name="INS" prefix="BOOZ_INS_">
<define name="BARO_SENS" value="15." integer="16"/>
<define name="UNTILT_ACCEL" value="1"/>
<define name="SONAR_SENS" value="2.146" integer="16"/>
</section>
<section name="HORIZONTAL_FILTER" prefix="B2_HFF_">
<define name="ACCEL_NOISE" value="10."/>
<define name="R_POS" value="0.05"/>
<define name="R_POS_MIN" value="0."/>
<define name="R_SPEED" value="1."/>
<define name="R_SPEED_MIN" value="0."/>
</section>
<section name="GUIDANCE_V" prefix="BOOZ2_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="-1.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="-150"/>
<define name="HOVER_KD" value="-80"/>
<define name="HOVER_KI" value="0"/>
<!-- 1.5m/s for full stick : SPEED_BFP_OF_REAL(1.5) / (MAX_PPRZ/2) -->
<define name="RC_CLIMB_COEF" value ="163"/>
<!-- SPEED_BFP_OF_REAL(1.5) * 20% -->
<define name="RC_CLIMB_DEAD_BAND" value ="160000"/>
<!-- <define name="INV_M" value="0.118"/> -->
</section>
<section name="GUIDANCE_H" prefix="BOOZ2_GUIDANCE_H_">
<define name="PGAIN" value="-50"/>
<define name="DGAIN" value="-60"/>
<define name="IGAIN" value="-0"/>
<define name="NGAIN" value="-0"/>
<!-- feedforward -->
<define name="AGAIN" value="50"/>
</section>
<section name="BAT">
<define name="MILLIAMP_PER_PERCENT" value="0.86"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="BATTERY_SENS" value="0.183" integer="16"/>
</section>
<section name="AUTOPILOT">
<define name="BOOZ2_MODE_MANUAL" value="BOOZ2_AP_MODE_ATTITUDE_DIRECT"/>
<define name="BOOZ2_MODE_AUTO1" value="BOOZ2_AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="BOOZ2_MODE_AUTO2" value="BOOZ2_AP_MODE_NAV"/>
</section>
<section name="FMS">
</section>
<section name="MISC">
<define name="BOOZ_ANALOG_BARO_THRESHOLD" value="800"/>
<define name="BOOZ2_FACE_REINJ_1" value="1024"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="10."/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<!--define name="INITIAL_CONDITITONS" value="&quot;reset_enac&quot;"/-->
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
<makefile>
ARCH=lpc21
ARCHI=arm7
BOARD_CFG = \"boards/booz2_v1_0.h\"
FLASH_MODE=IAP
# prevents motors from ever starting
#ap.CFLAGS += -DKILL_MOTORS
include $(PAPARAZZI_SRC)/conf/autopilot/booz2_common.makefile
include $(CFG_BOOZ)/booz2_autopilot.makefile
include $(CFG_BOOZ)/booz2_test_progs.makefile
ap.CFLAGS += -DBOOZ_FAILSAFE_GROUND_DETECT
sim.CFLAGS += -DBSM_PARAMS=\"booz_sensors_model_params_booz2_a2.h\"
sim.CFLAGS += -DNPS_NO_SUPERVISION
include $(CFG_BOOZ)/booz2_simulator_nps.makefile
ap.CFLAGS += -DMODEM_BAUD=B57600
include $(CFG_BOOZ)/subsystems/booz2_actuators_asctec.makefile
include $(CFG_BOOZ)/subsystems/booz2_radio_control_ppm.makefile
include $(CFG_BOOZ)/subsystems/booz2_imu_b2v1_1.makefile
#include $(CFG_BOOZ)/subsystems/booz2_gps.makefile
include $(CFG_BOOZ)/subsystems/booz2_analog_bat_baro.makefile
include $(CFG_BOOZ)/subsystems/booz2_fms_datalink.makefile
include $(CFG_BOOZ)/subsystems/booz2_ahrs_cmpl.makefile
#include $(CFG_BOOZ)/subsystems/booz2_ins_hff.makefile
#ap.CFLAGS += -DR_POS=0.1
ap.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT -DBOOZ_START_DELAY=3
sim.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT -DBOOZ_START_DELAY=3
ap.CFLAGS += -DUSE_MODULES
</makefile>
</airframe>
@@ -0,0 +1,278 @@
<!--DOCTYPE airframe SYSTEM "../../airframe.dtd"-->
<airframe name="Booz Mkk1 Enac">
<modules main_freq="512">
<load name="vision_cmucam.xml"/>
<load name="sonar_maxbotix_booz.xml"/>
</modules>
<servos min="0" neutral="0" max="0xff">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/>
<servo name="RIGHT" no="2" min="0" neutral="0" max="255"/>
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
</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="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x58, 0x52, 0x54, 0x56 }"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<define name="MAX_MOTOR" value="210"/>
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="0"/>
<define name="TRIM_R" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0, 0, -256, 256}"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0}"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256}"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_CHAN" value="1"/>
<define name="GYRO_Q_CHAN" value="0"/>
<define name="GYRO_R_CHAN" value="2"/>
<define name="GYRO_P_NEUTRAL" value="30907"/>
<define name="GYRO_Q_NEUTRAL" value="33253"/>
<define name="GYRO_R_NEUTRAL" value="32329"/>
<define name="GYRO_P_SENS" value="1.00" integer="16"/>
<define name="GYRO_Q_SENS" value="1.00" integer="16"/>
<define name="GYRO_R_SENS" value="1.00" integer="16"/>
<define name="ACCEL_X_CHAN" value="5"/>
<define name="ACCEL_Y_CHAN" value="3"/>
<define name="ACCEL_Z_CHAN" value="4"/>
<define name="ACCEL_X_NEUTRAL" value="32913"/>
<define name="ACCEL_Y_NEUTRAL" value="33032"/>
<define name="ACCEL_Z_NEUTRAL" value="32843"/>
<define name="ACCEL_X_SENS" value="2.5749914646" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.56940516083" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.56940374188" integer="16"/>
<define name="MAG_X_CHAN" value="0"/>
<define name="MAG_Y_CHAN" value="1"/>
<define name="MAG_Z_CHAN" value="2"/>
<define name="MAG_X_NEUTRAL" value="-62"/>
<define name="MAG_Y_NEUTRAL" value="-13"/>
<define name="MAG_Z_NEUTRAL" value="-95"/>
<define name="MAG_X_SENS" value="6.42348671436" integer="16"/>
<define name="MAG_Y_SENS" value="6.95371185551" integer="16"/>
<define name="MAG_Z_SENS" value="3.12322557454" 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_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="BODY_TO_IMU_PHI" value="RadOfDeg(0.)"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg(0.)"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg(0.)"/>
</section>
<section name="STABILIZATION_RATE" prefix="BOOZ_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_RATE" prefix="BOOZ_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="BOOZ_STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="RadOfDeg(45.)"/>
<define name="SP_MAX_THETA" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="RadOfDeg(800)"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="RadOfDeg(300.)"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="RadOfDeg(800)"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="RadOfDeg(300.)"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="RadOfDeg(500)"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="RadOfDeg(90.)"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="-650"/>
<define name="PHI_DGAIN" value="-200"/>
<define name="PHI_IGAIN" value="-100"/>
<define name="THETA_PGAIN" value="-650"/>
<define name="THETA_DGAIN" value="-200"/>
<define name="THETA_IGAIN" value="-100"/>
<define name="PSI_PGAIN" value="-800"/>
<define name="PSI_DGAIN" value="-320"/>
<define name="PSI_IGAIN" value="-20"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 300"/>
<define name="THETA_DDGAIN" value=" 300"/>
<define name="PSI_DDGAIN" value=" 300"/>
</section>
<section name="INS" prefix="BOOZ_INS_">
<define name="BARO_SENS" value="15." integer="16"/>
<define name="UNTILT_ACCEL" value="1"/>
<!--define name="SONAR_SENS" value="2.146" integer="16"/-->
<define name="SONAR_SENS" value="3." integer="16"/>
</section>
<section name="HORIZONTAL_FILTER" prefix="B2_HFF_">
<define name="ACCEL_NOISE" value="10."/>
<define name="R_POS" value="0.01"/>
<define name="R_POS_MIN" value="0."/>
<define name="R_SPEED" value="0.01"/>
<define name="R_SPEED_MIN" value="0."/>
</section>
<section name="GUIDANCE_V" prefix="BOOZ2_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="-1.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="-200"/>
<define name="HOVER_KD" value="-100"/>
<define name="HOVER_KI" value="0"/>
<!-- 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="BOOZ2_GUIDANCE_H_">
<define name="PGAIN" value="-250"/>
<define name="DGAIN" value="-150"/>
<define name="IGAIN" value="-35"/>
<define name="NGAIN" value="-0"/>
<!-- feedforward -->
<define name="AGAIN" value="100"/>
</section>
<section name="BAT">
<define name="MILLIAMP_PER_PERCENT" value="0.86"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9." unit="V"/>
<define name="BATTERY_SENS" value="0.183" integer="16"/>
</section>
<section name="AUTOPILOT">
<define name="BOOZ2_MODE_MANUAL" value="BOOZ2_AP_MODE_ATTITUDE_DIRECT"/>
<define name="BOOZ2_MODE_AUTO1" value="BOOZ2_AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="BOOZ2_MODE_AUTO2" value="BOOZ2_AP_MODE_NAV"/>
</section>
<section name="FMS">
<define name="BOOZ_FMS_TIMEOUT" value="0"/>
</section>
<section name="MISC">
<define name="BOOZ2_FACE_REINJ_1" value="1024"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
<makefile>
ARCH=lpc21
ARCHI=arm7
BOARD_CFG = \"boards/booz2_v1_0.h\"
FLASH_MODE=IAP
# prevents motors from ever starting
#ap.CFLAGS += -DKILL_MOTORS
include $(PAPARAZZI_SRC)/conf/autopilot/booz2_common.makefile
include $(CFG_BOOZ)/booz2_autopilot.makefile
include $(CFG_BOOZ)/booz2_test_progs.makefile
ap.CFLAGS += -DBOOZ_FAILSAFE_GROUND_DETECT
ap.CFLAGS += -DMODEM_BAUD=B57600
include $(CFG_BOOZ)/subsystems/booz2_actuators_mkk.makefile
include $(CFG_BOOZ)/subsystems/booz2_radio_control_ppm.makefile
include $(CFG_BOOZ)/subsystems/booz2_imu_b2v1_1.makefile
#include $(CFG_BOOZ)/subsystems/booz2_gps.makefile
include $(CFG_BOOZ)/subsystems/booz2_analog_bat_baro.makefile
#ap.CFLAGS += -DBOOZ2_SONAR -DUSE_SONAR_1
#include $(CFG_BOOZ)/subsystems/booz2_analog_bat_baro_sonar.makefile
include $(CFG_BOOZ)/subsystems/booz2_fms_datalink.makefile
include $(CFG_BOOZ)/subsystems/booz2_ahrs_cmpl.makefile
#include $(CFG_BOOZ)/subsystems/booz2_ins_hff.makefile
ap.CFLAGS += -DB2_GUIDANCE_H_USE_REF
ap.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT
ap.CFLAGS += -DUSE_MODULES
include $(CFG_BOOZ)/booz2_simulator_nps.makefile
#sim.CFLAGS += -DB2_GUIDANCE_H_USE_REF
sim.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT
sim.CFLAGS += -DUSE_MODULES
</makefile>
</airframe>
+1
View File
@@ -12,6 +12,7 @@
<subsystem name="fdm" type="nps"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
+243
View File
@@ -0,0 +1,243 @@
<!--DOCTYPE airframe SYSTEM "../../airframe.dtd"-->
<airframe name="Nova+Lisa_L Enac">
<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.0">
<define name="BOOZ_FAILSAFE_GROUND_DETECT"/>
<define name="USE_GPS_ACC4R"/>
</target>
<target name="sim" board="pc">
<subsystem name="fdm" type="nps"/>
</target>
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="ahrs" type="cmpl"/>
<subsystem name="ins" type="hff"/>
</firmware>
<firmware name="lisa_l_test_progs">
<target name="test_imu_b2" board="lisa_l_1.0"/>
<target name="test_telemetry" board="lisa_l_1.0"/>
<target name="test_baro" board="lisa_l_1.0"/>
<target name="test_rc_spektrum" board="lisa_l_1.0"/>
<target name="test_rc_ppm" board="lisa_l_1.0"/>
<target name="test_actuators_mkk" board="lisa_l_1.0"/>
</firmware>
<servos min="0" neutral="0" max="0xff">
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/>
<servo name="BACK" no="1" min="0" neutral="0" max="255"/>
<servo name="RIGHT" no="2" min="0" neutral="0" max="255"/>
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
</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="ACTUATORS_MKK" prefix="ACTUATORS_MKK_">
<define name="NB" value="4"/>
<define name="ADDR" value="{ 0x58, 0x52, 0x54, 0x56 }"/>
</section>
<section name="SUPERVISION" prefix="SUPERVISION_">
<define name="MIN_MOTOR" value="2"/>
<define name="MAX_MOTOR" value="210"/>
<define name="TRIM_A" value="0"/>
<define name="TRIM_E" value="0"/>
<define name="TRIM_R" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ 0, 0, -256, 256}"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0}"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256}"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256}"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="30907"/>
<define name="GYRO_Q_NEUTRAL" value="33253"/>
<define name="GYRO_R_NEUTRAL" value="32329"/>
<define name="GYRO_P_SENS" value="1.00" integer="16"/>
<define name="GYRO_Q_SENS" value="1.00" integer="16"/>
<define name="GYRO_R_SENS" value="1.00" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="32913"/>
<define name="ACCEL_Y_NEUTRAL" value="33032"/>
<define name="ACCEL_Z_NEUTRAL" value="32843"/>
<define name="ACCEL_X_SENS" value="2.5749914646" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.56940516083" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.56940374188" integer="16"/>
<define name="MAG_X_NEUTRAL" value="-62"/>
<define name="MAG_Y_NEUTRAL" value="-13"/>
<define name="MAG_Z_NEUTRAL" value="-95"/>
<define name="MAG_X_SENS" value="6.42348671436" integer="16"/>
<define name="MAG_Y_SENS" value="6.95371185551" integer="16"/>
<define name="MAG_Z_SENS" value="3.12322557454" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="RadOfDeg(0.)"/>
<define name="BODY_TO_IMU_THETA" value="RadOfDeg(0.)"/>
<define name="BODY_TO_IMU_PSI" value="RadOfDeg(-135.)"/>
</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="-400"/>
<define name="GAIN_Q" value="-400"/>
<define name="GAIN_R" value="-350"/>
</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="-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="RadOfDeg(45.)"/>
<define name="SP_MAX_THETA" value="RadOfDeg(45.)"/>
<define name="SP_MAX_R" value="RadOfDeg(90.)"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="RadOfDeg(800)"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="RadOfDeg(300.)"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="RadOfDeg(800)"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="RadOfDeg(300.)"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="RadOfDeg(500)"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="RadOfDeg(90.)"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="-650"/>
<define name="PHI_DGAIN" value="-200"/>
<define name="PHI_IGAIN" value="-100"/>
<define name="THETA_PGAIN" value="-650"/>
<define name="THETA_DGAIN" value="-200"/>
<define name="THETA_IGAIN" value="-100"/>
<define name="PSI_PGAIN" value="-800"/>
<define name="PSI_DGAIN" value="-320"/>
<define name="PSI_IGAIN" value="-20"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 300"/>
<define name="THETA_DDGAIN" value=" 300"/>
<define name="PSI_DDGAIN" value=" 300"/>
</section>
<section name="INS" prefix="INS_">
<define name="BARO_SENS" value="15." integer="16"/>
<define name="UNTILT_ACCEL" value="1"/>
</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="-1.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="-200"/>
<define name="HOVER_KD" value="-100"/>
<define name="HOVER_KI" value="0"/>
<!-- 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="-60"/>
<define name="DGAIN" value="-120"/>
<define name="IGAIN" value="-10"/>
<define name="NGAIN" value="-0"/>
<!-- feedforward -->
<define name="AGAIN" value="100"/>
</section>
<section name="BAT">
<define name="MILLIAMP_PER_PERCENT" value="0.86"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9." unit="V"/>
<define name="BATTERY_SENS" value="0.183" integer="16"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<section name="FMS">
</section>
<section name="MISC">
<define name="FACE_REINJ_1" value="1024"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;front_motor&quot;, &quot;back_motor&quot;, &quot;right_motor&quot;, &quot;left_motor&quot;}"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_booz2_a1.h&quot;"/>
</section>
<makefile>
# prevents motors from ever starting
#ap.CFLAGS += -DKILL_MOTORS
#set GPS lag for horizontal filter
#ap.CFLAGS += -DUSE_GPS_ACC4R
#ap.CFLAGS += -DGUIDANCE_H_USE_REF
ap.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT
#sim.CFLAGS += -DGUIDANCE_H_USE_REF
sim.CFLAGS += -DUSE_ADAPT_HOVER -DUSE_INS_NAV_INIT
</makefile>
</airframe>
+4 -4
View File
@@ -18,15 +18,15 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_0"/>
<param name="ADC_IR2" value="ADC_1"/>
<param name="ADC_IR_TOP" value="ADC_2"/>
<configure name="ADC_IR1" value="ADC_0"/>
<configure name="ADC_IR2" value="ADC_1"/>
<configure name="ADC_IR_TOP" value="ADC_2"/>
</subsystem>
<subsystem name="gps" type="ublox_lea4p"/>
<subsystem name="navigation"/>
+4 -4
View File
@@ -18,15 +18,15 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_0"/>
<param name="ADC_IR2" value="ADC_1"/>
<param name="ADC_IR_TOP" value="ADC_2"/>
<configure name="ADC_IR1" value="ADC_0"/>
<configure name="ADC_IR2" value="ADC_1"/>
<configure name="ADC_IR_TOP" value="ADC_2"/>
</subsystem>
<subsystem name="gps" type="ublox_lea4p"/>
<subsystem name="navigation"/>
+4 -4
View File
@@ -18,15 +18,15 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
<!-- Sensors -->
<subsystem name="attitude" type="infrared">
<param name="ADC_IR1" value="ADC_0"/>
<param name="ADC_IR2" value="ADC_1"/>
<param name="ADC_IR_TOP" value="ADC_2"/>
<configure name="ADC_IR1" value="ADC_0"/>
<configure name="ADC_IR2" value="ADC_1"/>
<configure name="ADC_IR_TOP" value="ADC_2"/>
</subsystem>
<subsystem name="gps" type="ublox_lea4p"/>
<subsystem name="navigation"/>
@@ -156,7 +156,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1 -DUSE_MODULES
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1 -DUSE_MODULES
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -171,7 +171,7 @@ ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
# Telemetry configuration
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B57600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
+2 -2
View File
@@ -176,7 +176,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_2_1_1.h\" -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_2_1_1.h\" -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -188,7 +188,7 @@ ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE=RC_FUTABA
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B57600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
+2 -2
View File
@@ -23,10 +23,10 @@ ant.LOCK_FUSE = ff
ant.CFLAGS += -DBOARD_CONFIG=\"antenna.h\"
ant.srcs = main_antenna.c sys_time.c $(SRC_ARCH)/sys_time_hw.c
ant.CFLAGS += -DLED
ant.CFLAGS += -DUSE_LED
ant.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
ant.srcs += $(SRC_ARCH)/uart_hw.c
ant.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
ant.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0
ant.srcs += downlink.c pprz_transport.c
+3 -3
View File
@@ -16,17 +16,17 @@ test_usb.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) $(BOOZ_CFLAGS)
test_usb.srcs += $(SRC_BOOZ_TEST)/atpt_main.c
test_usb.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))'
# -DTIME_LED=1
test_usb.CFLAGS += -DLED
test_usb.CFLAGS += -DUSE_LED
test_usb.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c
#test_usb.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600
#test_usb.srcs += $(SRC_ARCH)/uart_hw.c
#test_usb.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
#test_usb.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1
#test_usb.srcs += downlink.c pprz_transport.c
test_usb.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DUSE_USB_SERIAL
test_usb.CFLAGS += -DDOWNLINK_DEVICE=UsbS -DPPRZ_UART=UsbS -DDATALINK=PPRZ
test_usb.srcs += downlink.c $(SRC_ARCH)/uart_hw.c $(SRC_ARCH)/usb_ser_hw.c pprz_transport.c
test_usb.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c $(SRC_ARCH)/usb_ser_hw.c pprz_transport.c
# datalink.c
test_usb.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbcontrol.c
test_usb.srcs += $(SRC_ARCH)/lpcusb/usbstdreq.c $(SRC_ARCH)/lpcusb/usbinit.c
+4 -4
View File
@@ -114,7 +114,7 @@ main_stm32.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)'
main_stm32.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
main_stm32.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600
main_stm32.srcs += $(SRC_ARCH)/uart_hw.c
main_stm32.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main_stm32.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2
main_stm32.srcs += downlink.c pprz_transport.c
@@ -126,12 +126,12 @@ main_stm32.srcs += lisa/lisa_overo_link.c lisa/arch/stm32/lisa_overo_link_arch.c
#booz IMU
#main_stm32.CFLAGS += -DIMU_TYPE_H=\"imu/imu_b2.h\"
#main_stm32.CFLAGS += -DIMU_B2_MAG_TYPE=IMU_B2_MAG_MS2001
#main_stm32.CFLAGS += -DIMU_B2_MAG_TYPE=IMU_B2_MAG_MS2100
#main_stm32.srcs += $(SRC_FIRMWARE)/imu.c
#main_stm32.CFLAGS += -DUSE_SPI2 -DUSE_DMA1_C4_IRQ -DUSE_EXTI2_IRQ -DUSE_SPI2_IRQ
#main_stm32.srcs += $(SRC_FIRMWARE)/imu/imu_b2.c $(SRC_FIRMWARE)/imu/arch/$(ARCH)/imu_b2_arch.c
#main_stm32.srcs += peripherals/max1168.c $(SRC_ARCH)/peripherals/max1168_arch.c
#main_stm32.srcs += peripherals/ms2001.c $(SRC_ARCH)/peripherals/ms2001_arch.c
#main_stm32.srcs += peripherals/ms2100.c $(SRC_ARCH)/peripherals/ms2100_arch.c
#main_stm32.srcs += math/pprz_trig_int.c
#crista IMU
@@ -186,7 +186,7 @@ main_coders.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)'
main_coders.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
main_coders.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600
main_coders.srcs += $(SRC_ARCH)/uart_hw.c
main_coders.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main_coders.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1
main_coders.srcs += downlink.c pprz_transport.c
+2 -2
View File
@@ -26,11 +26,11 @@ main.srcs = main_bl_mc.c
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1e-2)'
main.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
main.CFLAGS += -DLED
main.CFLAGS += -DUSE_LED
#-DTIME_LED=1
main.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B38400
main.srcs += $(SRC_ARCH)/uart_hw.c
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1
main.srcs += downlink.c pprz_transport.c
+1
View File
@@ -202,6 +202,7 @@
<subsystem name="fdm" type="nps"/>
</target>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="actuators" type="mkk"/>
<subsystem name="imu" type="b2_v1.0"/>
<subsystem name="gps" type="ublox"/>
+1 -1
View File
@@ -181,7 +181,7 @@
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="telemetry" type="transparent"/>
<!-- <subsystem name="imu" type="b2_v1.1"/> -->
<subsystem name="imu" type="aspirin"/>
<subsystem name="gps" type="ublox"/>
+1 -1
View File
@@ -199,7 +199,7 @@
<subsystem name="radio_control" type="ppm"/>
<subsystem name="actuators" type="mkk"/>
</target>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="ahrs" type="cmpl"/>
+2 -2
View File
@@ -163,7 +163,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -177,7 +177,7 @@ ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
# transparent
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
+4 -4
View File
@@ -17,12 +17,12 @@ main.CFLAGS += -DPERIODIC_TASK_FREQ='250.'
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./PERIODIC_TASK_FREQ)'
main.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
main.CFLAGS += -DLED
main.CFLAGS += -DUSE_LED
main.srcs += $(SRC_ARCH)/armVIC.c
main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200
main.srcs += $(SRC_ARCH)/uart_hw.c
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0
main.srcs += downlink.c pprz_transport.c
@@ -61,7 +61,7 @@ foo.CFLAGS += -DPERIODIC_TASK_FREQ='250.'
foo.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./PERIODIC_TASK_FREQ)'
foo.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
foo.CFLAGS += -DLED
foo.CFLAGS += -DUSE_LED
foo.srcs += $(SRC_ARCH)/armVIC.c
foo.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 -DI2C0_VIC_SLOT=9
@@ -80,7 +80,7 @@ bar.CFLAGS += -DPERIODIC_TASK_FREQ='250.'
bar.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./PERIODIC_TASK_FREQ)'
bar.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
bar.CFLAGS += -DLED
bar.CFLAGS += -DUSE_LED
bar.srcs += $(SRC_ARCH)/armVIC.c
bar.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 -DI2C0_VIC_SLOT=9
+3 -3
View File
@@ -10,7 +10,7 @@
tunnel.ARCHDIR = $(ARCH)
tunnel.CFLAGS += -DFBW -DBOARD_CONFIG=\"conf_demo.h\" -DLED -DTIME_LED=1
tunnel.CFLAGS += -DFBW -DBOARD_CONFIG=\"conf_demo.h\" -DUSE_LED -DTIME_LED=1
tunnel.srcs += $(SRC_ARCH)/uart_tunnel.c
ARCH=lpc21
@@ -26,12 +26,12 @@ main.srcs = $(PT_ANT)/pt_ant_main.c
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1.66666667e-2)'
main.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
main.CFLAGS += -DLED
main.CFLAGS += -DUSE_LED
main.srcs += $(SRC_ARCH)/armVIC.c
main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
main.srcs += $(SRC_ARCH)/uart_hw.c
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0
main.srcs += downlink.c pprz_transport.c $(PT_ANT)/pt_ant_telemetry.c
+1 -1
View File
@@ -25,7 +25,7 @@ main.srcs += sys_time.c $(MB)/turntable_systime.c
#main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=UsbS
main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200
main.srcs += $(SRC_ARCH)/uart_hw.c
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0
main.srcs += downlink.c pprz_transport.c
+4 -4
View File
@@ -229,8 +229,8 @@
<modules>
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="3"/>
<param name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="LIGHT_LED_STROBE" value="3"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
</load>
</modules>
@@ -253,12 +253,12 @@
<!-- Communication -->
<subsystem name="telemetry" type="transparent">
<param name="MODEM_BAUD" value="57600"/>
<configure name="MODEM_BAUD" value="57600"/>
</subsystem>
<!-- Sensors -->
<!-- <subsystem name="gyro" type="roll">
<param name="ADC_GYRO_ROLL" value="ADC_3" />
<configure name="ADC_GYRO_ROLL" value="ADC_3" />
</subsystem>
--> <subsystem name="attitude" type="infrared"/>
<subsystem name="gps" type="ublox_lea4p"/>
+53 -38
View File
@@ -4,9 +4,9 @@
<!-- commands section -->
<servos>
<servo name="THROTTLE" no="0" min="1110" neutral="1110" max="1900"/>
<servo name="AILEVON_LEFT" no="1" min="1000" neutral="1450" max="2000"/>
<servo name="AILEVON_RIGHT" no="2" min="2000" neutral="1450" max="1000"/>
<servo name="THROTTLE" no="0" min="1050" neutral="1050" max="1900"/>
<servo name="AILEVON_RIGHT" no="1" min="1850" neutral="1480" max="1100"/> <!-- 400 - 380 -->
<servo name="AILEVON_LEFT" no="2" min="1250" neutral="1580" max="1980"/> <!-- 300 - 400 -->
</servos>
<commands>
@@ -22,8 +22,8 @@
</rc_commands>
<section name="MIXER">
<define name="AILEVON_AILERON_RATE" value="0.4"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.7"/>
<define name="AILEVON_AILERON_RATE" value="0.75"/>
<define name="AILEVON_ELEVATOR_RATE" value="0.9"/>
</section>
<command_laws>
@@ -52,37 +52,46 @@
<define name="ACCEL_Z_CHAN" value="5"/>
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="33924"/>
<define name="GYRO_Q_NEUTRAL" value="33417"/>
<define name="GYRO_R_NEUTRAL" value="32809"/>
<define name="GYRO_P_NEUTRAL" value="21480"/>
<define name="GYRO_Q_NEUTRAL" value="21410"/>
<define name="GYRO_R_NEUTRAL" value="21940"/>
<define name="GYRO_P_SENS" value=" 1.00" integer="16"/>
<define name="GYRO_Q_SENS" value=" 1.00" integer="16"/>
<define name="GYRO_R_SENS" value=" 1.00" integer="16"/>
<!-- SENS = 2mV/deg/sec * 57.6 deg/rad = 114.59 mV/rad/sec * 16 LSB/mV = 1833.465 LSB/rad/sec / 12bit FRAC -->
<define name="GYRO_P_SENS" value="2.234" integer="16"/>
<define name="GYRO_Q_SENS" value="2.234" integer="16"/>
<define name="GYRO_R_SENS" value="2.234" integer="16"/>
<define name="GYRO_P_Q" value="0." />
<define name="GYRO_P_R" value="(1.0f/75.0f)" />
<define name="GYRO_Q_P" value="0." />
<define name="GYRO_Q_R" value="0." />
<define name="GYRO_R_P" value="0." />
<define name="GYRO_R_Q" value="0." />
<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="1"/>
<define name="GYRO_R_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="-1"/>
<define name="ACCEL_X_NEUTRAL" value="26000"/>
<define name="ACCEL_Y_NEUTRAL" value="26000"/>
<define name="ACCEL_Z_NEUTRAL" value="26000"/>
<define name="ACCEL_X_NEUTRAL" value="26424"/>
<define name="ACCEL_Y_NEUTRAL" value="26640"/>
<define name="ACCEL_Z_NEUTRAL" value="26732"/>
<define name="ACCEL_X_SENS" value="-2.50411474" integer="16"/>
<define name="ACCEL_Y_SENS" value="-2.48126183" integer="16"/>
<define name="ACCEL_Z_SENS" value="-2.51396167" integer="16"/>
<!-- SENS = 660mV/g / 9.81 ms2/g = 67.27 mV/ms2 * 16 LSB/mV = 1076 LSB/ms2 / 10bit FRAC -->
<define name="ACCEL_X_SENS" value="0.9372" integer="16"/>
<define name="ACCEL_Y_SENS" value="0.9346" integer="16"/>
<define name="ACCEL_Z_SENS" value="0.9178" integer="16"/>
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_X_SIGN" value="-1"/>
<define name="ACCEL_Y_SIGN" value="1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="1"/>
<define name="MAG_X_NEUTRAL" value="2358"/>
<define name="MAG_Y_NEUTRAL" value="2362"/>
<define name="MAG_Z_NEUTRAL" value="2119"/>
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="-3.4936416" integer="16"/>
<define name="MAG_Y_SENS" value=" 3.607713" integer="16"/>
<define name="MAG_Z_SENS" value="-4.90788848" integer="16"/>
<define name="MAG_X_SENS" value="1" integer="16"/>
<define name="MAG_Y_SENS" value="1" integer="16"/>
<define name="MAG_Z_SENS" value="1" integer="16"/>
<!-- <define name="MAG_45_HACK" value="1"/> -->
@@ -143,18 +152,18 @@
<define name="COURSE_PGAIN" value="-1.4"/>
<define name="ROLL_MAX_SETPOINT" value="0.6" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
<define name="PITCH_MAX_SETPOINT" value="0.4" unit="radians"/>
<define name="PITCH_MIN_SETPOINT" value="-0.4" unit="radians"/>
<define name="PITCH_PGAIN" value="0."/>
<define name="PITCH_DGAIN" value="0."/>
<define name="PITCH_PGAIN" value="-6000."/>
<define name="PITCH_DGAIN" value="5."/>
<define name="ELEVATOR_OF_ROLL" value="0."/>
<define name="ELEVATOR_OF_ROLL" value="1200."/>
<define name="ROLL_SLEW" value="0."/>
<define name="ROLL_ATTITUDE_GAIN" value="0."/>
<define name="ROLL_RATE_GAIN" value="0."/>
<define name="ROLL_ATTITUDE_GAIN" value="-5000."/>
<define name="ROLL_RATE_GAIN" value="500."/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
@@ -181,7 +190,13 @@
</section>
<firmware name="fixedwing">
<target name="ap" board="tiny_1.1"/>
<target name="ap" board="tiny_1.1">
<configure name="PERIODIC_FREQUENCY" value="960" /> <!-- IMU FREQ -->
<configure name="AHRS_PROPAGATE_FREQUENCY" value="240" />
<configure name="AHRS_CORRECT_FREQUENCY" value="60" />
<configure name="AHRS_ALIGNER_LED" value="1" />
<configure name="CPU_LED" value="2" />
</target>
<target name="sim" board="pc" />
<define name="AGR_CLIMB" />
@@ -192,7 +207,7 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_BAUD" value="B57600"/>
</subsystem>
<subsystem name="control"/>
@@ -212,8 +227,8 @@
<modules>
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="2"/>
<param name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="LIGHT_LED_STROBE" value="2"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
</load>
</modules>
+4 -4
View File
@@ -249,7 +249,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=2
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=2
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -261,15 +261,15 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
#TRANSPARENT
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -#DDATALINK=PPRZ -DUART1_BAUD=B9600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
# Maxstream API protocol
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
+4 -4
View File
@@ -254,7 +254,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=2
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=2
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
ap.srcs += commands.c
@@ -266,15 +266,15 @@ ap.CFLAGS += -DRADIO_CONTROL
ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
#TRANSPARENT
#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -#DDATALINK=PPRZ -DUART1_BAUD=B9600
#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
# Maxstream API protocol
ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B9600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c
ap.CFLAGS += -DINTER_MCU
ap.srcs += inter_mcu.c
+2 -2
View File
@@ -248,7 +248,7 @@ include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
FLASH_MODE=IAP
# main files (including the 60Hz timing)
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_1_1.h\" -DLED -DTIME_LED=1
ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_1_1.h\" -DUSE_LED -DTIME_LED=1
ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c
# Command allocation and Radio Mixers
@@ -264,7 +264,7 @@ ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c
# Paparazzi protocol on UART0 at 57600
ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B57600
ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c
# communication from FBW and AP
ap.CFLAGS += -DINTER_MCU
+6 -6
View File
@@ -171,14 +171,14 @@
<modules>
<!--
<load name="light.xml">
<param name="LIGHT_LED_STROBE" value="3"/>
<param name="LIGHT_LED_NAV" value="4"/>
<param name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<param name="NAV_LIGHT_MODE_DEFAULT" value="0"/>
<define name="LIGHT_LED_STROBE" value="3"/>
<define name="LIGHT_LED_NAV" value="4"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="NAV_LIGHT_MODE_DEFAULT" value="0"/>
</load>-->
<load name="digital_cam_i2c.xml"/>
<!-- <load name="digital_cam.xml" >
<param name="DC_SHUTTER_LED" value="3"/>
<define name="DC_SHUTTER_LED" value="3"/>
</load>
--> </modules>
@@ -193,7 +193,7 @@
<!-- Communication -->
<subsystem name="telemetry" type="xbee_api">
<param name="MODEM_BAUD" value="B9600"/>
<configure name="MODEM_BAUD" value="B9600"/>
</subsystem>
<!-- Actuators -->

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