diff --git a/.gitignore b/.gitignore index 22b80c9dc3..4e3b07d886 100644 --- a/.gitignore +++ b/.gitignore @@ -47,6 +47,8 @@ /conf/%gconf.xml /conf/srtm_data/* /conf/maps_data/* +/conf/maps.xml +/conf/gps/ublox_conf # /doc/pprz_algebra/ /doc/pprz_algebra/headfile.log @@ -99,6 +101,7 @@ /sw/logalizer/plotter /sw/logalizer/gtk_export.ml /sw/logalizer/sd2log +/sw/logalizer/plotprofile # /sw/simulator/ /sw/simulator/gaia diff --git a/Makefile b/Makefile index 1d98d73191..51425b4589 100644 --- a/Makefile +++ b/Makefile @@ -52,12 +52,14 @@ STATICINCLUDE =$(PAPARAZZI_HOME)/var/include MESSAGES_H=$(STATICINCLUDE)/messages.h MESSAGES2_H=$(STATICINCLUDE)/messages2.h UBX_PROTOCOL_H=$(STATICINCLUDE)/ubx_protocol.h +MTK_PROTOCOL_H=$(STATICINCLUDE)/mtk_protocol.h XSENS_PROTOCOL_H=$(STATICINCLUDE)/xsens_protocol.h DL_PROTOCOL_H=$(STATICINCLUDE)/dl_protocol.h DL_PROTOCOL2_H=$(STATICINCLUDE)/dl_protocol2.h ABI_MESSAGES_H=$(STATICINCLUDE)/abi_messages.h MESSAGES_XML = $(CONF)/messages.xml UBX_XML = $(CONF)/ubx.xml +MTK_XML = $(CONF)/mtk.xml XSENS_XML = $(CONF)/xsens_MTi-G.xml TOOLS=$(PAPARAZZI_SRC)/sw/tools HAVE_ARM_NONE_EABI_GCC := $(shell which arm-none-eabi-gcc) @@ -69,27 +71,29 @@ endif OCAML=$(shell which ocaml) OCAMLRUN=$(shell which ocamlrun) -all: commands static conf +all: conf commands static static : lib center tools cockpit multimon tmtc misc logalizer lpc21iap sim_static static_h usb_lib -conf: conf/conf.xml conf/control_panel.xml conf/maps_data/maps.conf +conf: conf/conf.xml conf/control_panel.xml conf/maps.xml FORCE conf/%.xml :conf/%.xml.example [ -L $@ ] || [ -f $@ ] || cp $< $@ -conf/maps_data/maps.conf: - cd data/maps; $(MAKE) +conf/maps.xml: conf/maps.xml.example FORCE + -cd data/maps; $(MAKE) + if test ! -e $@; then cp $< $@; fi +FORCE: lib: cd $(LIB)/ocaml; $(MAKE) center: lib - cd sw/supervision; make + cd sw/supervision; $(MAKE) tools: lib - cd $(TOOLS); make + cd $(TOOLS); $(MAKE) logalizer: lib cd $(LOGALIZER); $(MAKE) @@ -109,7 +113,7 @@ misc: multimon: cd $(MULTIMON); $(MAKE) -static_h: $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(XSENS_PROTOCOL_H) $(DL_PROTOCOL_H) $(DL_PROTOCOL2_H) $(ABI_MESSAGES_H) +static_h: $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(XSENS_PROTOCOL_H) $(DL_PROTOCOL_H) $(DL_PROTOCOL2_H) $(ABI_MESSAGES_H) usb_lib: @[ -d sw/airborne/arch/lpc21/lpcusb ] && ((test -x "$(ARMGCC)" && (cd sw/airborne/arch/lpc21/lpcusb; $(MAKE))) || echo "Not building usb_lib: ARMGCC=$(ARMGCC) not found") || echo "Not building usb_lib: sw/airborne/arch/lpc21/lpcusb directory missing" @@ -117,35 +121,40 @@ usb_lib: $(MESSAGES_H) : $(MESSAGES_XML) $(CONF_XML) tools $(Q)test -d $(STATICINCLUDE) || mkdir -p $(STATICINCLUDE) @echo BUILD $@ - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(TOOLS)/gen_messages.out $< telemetry > /tmp/msg.h + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages.out $< telemetry > /tmp/msg.h $(Q)mv /tmp/msg.h $@ $(Q)chmod a+r $@ $(MESSAGES2_H) : $(MESSAGES_XML) $(CONF_XML) tools $(Q)test -d $(STATICINCLUDE) || mkdir -p $(STATICINCLUDE) @echo BUILD $@ - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(TOOLS)/gen_messages2.out $< telemetry > /tmp/msg2.h + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages2.out $< telemetry > /tmp/msg2.h $(Q)mv /tmp/msg2.h $@ $(Q)chmod a+r $@ $(UBX_PROTOCOL_H) : $(UBX_XML) tools @echo BUILD $@ - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(TOOLS)/gen_ubx.out $< > /tmp/ubx.h + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_ubx.out $< > /tmp/ubx.h $(Q)mv /tmp/ubx.h $@ +$(MTK_PROTOCOL_H) : $(MTK_XML) tools + @echo BUILD $@ + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_mtk.out $< > /tmp/mtk.h + $(Q)mv /tmp/mtk.h $@ + $(XSENS_PROTOCOL_H) : $(XSENS_XML) tools @echo BUILD $@ - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(TOOLS)/gen_xsens.out $< > /tmp/xsens.h + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_xsens.out $< > /tmp/xsens.h $(Q)mv /tmp/xsens.h $@ $(DL_PROTOCOL_H) : $(MESSAGES_XML) tools @echo BUILD $@ - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(TOOLS)/gen_messages.out $< datalink > /tmp/dl.h + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages.out $< datalink > /tmp/dl.h $(Q)mv /tmp/dl.h $@ $(DL_PROTOCOL2_H) : $(MESSAGES_XML) tools @echo BUILD $@ - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(TOOLS)/gen_messages2.out $< datalink > /tmp/dl2.h + $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(TOOLS)/gen_messages2.out $< datalink > /tmp/dl2.h $(Q)mv /tmp/dl2.h $@ $(ABI_MESSAGES_H) : $(MESSAGES_XML) tools @@ -165,7 +174,7 @@ ac_h ac1 ac2 ac3 ac fbw ap: static conf # # call with : make bl PROC=[TINY|FBW|AP|GENERIC] bl: - cd $(AIRBORNE)/arch/lpc21/test/bootloader; make clean; make + cd $(AIRBORNE)/arch/lpc21/test/bootloader; $(MAKE) clean; $(MAKE) BOOTLOADER_DEV=/dev/ttyUSB0 upload_bl bl.upload: bl @@ -180,15 +189,15 @@ upload_jtag: bl lpc21iap: - cd sw/ground_segment/lpc21iap; make + cd sw/ground_segment/lpc21iap; $(MAKE) upgrade_bl bl.upgrade: bl lpc21iap $(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap $(AIRBORNE)/arch/lpc21/test/bootloader/bl_ram.elf $(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap $(AIRBORNE)/arch/lpc21/test/bootloader/bl.elf ms: - cd $(AIRBORNE)/arch/lpc21/lpcusb; make - cd $(AIRBORNE)/arch/lpc21/lpcusb/examples; make + cd $(AIRBORNE)/arch/lpc21/lpcusb; $(MAKE) + cd $(AIRBORNE)/arch/lpc21/lpcusb/examples; $(MAKE) upload_ms ms.upload: ms $(PAPARAZZI_SRC)/sw/ground_segment/lpc21iap/lpc21iap $(AIRBORNE)/arch/lpc21/lpcusb/examples/msc.elf @@ -204,10 +213,10 @@ run_sitl : $(PAPARAZZI_HOME)/var/$(AIRCRAFT)/sim/simsitl install : - make -f Makefile.install PREFIX=$(PREFIX) + $(MAKE) -f Makefile.install PREFIX=$(PREFIX) uninstall : - make -f Makefile.install PREFIX=$(PREFIX) uninstall + $(MAKE) -f Makefile.install PREFIX=$(PREFIX) uninstall DISTRO=lenny deb : @@ -217,11 +226,11 @@ deb : dpkg-buildpackage $(DEBFLAGS) -Ivar -rfakeroot fast_deb: - make deb OCAMLC=ocamlc.opt DEBFLAGS=-b + $(MAKE) deb OCAMLC=ocamlc.opt DEBFLAGS=-b clean: rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-arm7 debian/paparazzi-avr debian/paparazzi-base debian/paparazzi-bin debian/paparazzi-dev - rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(DL_PROTOCOL_H) + rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_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 @@ -236,7 +245,7 @@ cleanspaces: distclean : dist_clean dist_clean : clean rm -r conf/srtm_data - rm -r conf/maps_data + rm -r conf/maps_data conf/maps.xml ab_clean: find sw/airborne -name '*~' -exec rm -f {} \; diff --git a/Makefile.install b/Makefile.install index 1acf59704f..fd2aa46350 100644 --- a/Makefile.install +++ b/Makefile.install @@ -134,6 +134,7 @@ 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_mtk.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/ diff --git a/conf/Makefile.lpc21 b/conf/Makefile.lpc21 index 7415bf1da3..4f1b034859 100644 --- a/conf/Makefile.lpc21 +++ b/conf/Makefile.lpc21 @@ -34,7 +34,6 @@ SRC_ARCH = arch/lpc21 # Define programs and commands. HAVE_ARM_NONE_EABI_GCC := $(shell which arm-none-eabi-gcc) ifeq ($(strip $(HAVE_ARM_NONE_EABI_GCC)),) -$(info Using gcc-arm 3.4.4 packaged by paparazzi.) CC = arm-elf-gcc LD = $(CC) SHELL = sh @@ -43,7 +42,6 @@ OBJDUMP = arm-elf-objdump SIZE = arm-elf-size NM = arm-elf-nm else -$(info Using arm-none-eabi-gcc.) CC = arm-none-eabi-gcc LD = $(CC) SHELL = sh @@ -55,6 +53,8 @@ endif REMOVE = rm -f COPY = cp +MULTILIB = $(shell if $(CC) --print-multi-lib | grep thumb2 > /dev/null ; then echo "yes"; else echo "no"; fi) + # Launch with "make Q=''" to get full command display Q=@ @@ -179,7 +179,28 @@ ALL_ASFLAGS = -mcpu=$(MCU) $(THUMB_IW) -I. -x assembler-with-cpp $(ASFLAGS) # Default target. -all: sizebefore build sizeafter +all: printcommands printmultilib sizebefore build sizeafter + +printcommands: + @echo "Using CC = $(CC)" + @echo "Using LD = $(LD)" + @echo "Using CP = $(OBJCOPY)" + @echo "Using DMP = $(OBJDUMP)" + @echo "Using NM = $(NM)" + @echo "Using SIZE = $(SIZE)" + @echo "Using OOCD = $(OOCD)" + @echo "GCC version:" + @$(CC) --version | head -1 + +ifeq ("$(MULTILIB)","yes") +printmultilib: + @echo "*** Using multilib ***" + @echo "--------------------------" +else +printmultilib: + @echo "*** NOT using multilib ***" + @echo "--------------------------" +endif build: elf hex lss sym diff --git a/conf/airframes/CDW/ChimuLisaFw.xml b/conf/airframes/CDW/ChimuLisaFw.xml index 0e2fef40aa..812d8ed402 100644 --- a/conf/airframes/CDW/ChimuLisaFw.xml +++ b/conf/airframes/CDW/ChimuLisaFw.xml @@ -196,7 +196,7 @@ - + diff --git a/conf/airframes/CDW/ChimuTinyFw.xml b/conf/airframes/CDW/ChimuTinyFw.xml index 239d3ecace..d1d6271509 100644 --- a/conf/airframes/CDW/ChimuTinyFw.xml +++ b/conf/airframes/CDW/ChimuTinyFw.xml @@ -176,7 +176,7 @@ - + @@ -189,7 +189,7 @@ - + diff --git a/conf/airframes/CDW/ChimuTinyFwSpi.xml b/conf/airframes/CDW/ChimuTinyFwSpi.xml index f144a138e5..6d10394322 100644 --- a/conf/airframes/CDW/ChimuTinyFwSpi.xml +++ b/conf/airframes/CDW/ChimuTinyFwSpi.xml @@ -175,7 +175,7 @@ - + @@ -186,7 +186,7 @@ - + diff --git a/conf/airframes/CDW/LisaFw.xml b/conf/airframes/CDW/LisaFw.xml index 15baa30976..37cb8df3ea 100644 --- a/conf/airframes/CDW/LisaFw.xml +++ b/conf/airframes/CDW/LisaFw.xml @@ -200,7 +200,7 @@ --> - + diff --git a/conf/airframes/CDW/TinyFw.xml b/conf/airframes/CDW/TinyFw.xml index 160460fe9a..31523ce721 100644 --- a/conf/airframes/CDW/TinyFw.xml +++ b/conf/airframes/CDW/TinyFw.xml @@ -187,7 +187,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/funjet2.xml b/conf/airframes/ENAC/fixed-wing/funjet2.xml index a10debf64c..b1b5b3861d 100644 --- a/conf/airframes/ENAC/fixed-wing/funjet2.xml +++ b/conf/airframes/ENAC/fixed-wing/funjet2.xml @@ -49,7 +49,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/funjet2_nc.xml b/conf/airframes/ENAC/fixed-wing/funjet2_nc.xml index b02cd6ec66..c7e177da46 100644 --- a/conf/airframes/ENAC/fixed-wing/funjet2_nc.xml +++ b/conf/airframes/ENAC/fixed-wing/funjet2_nc.xml @@ -47,7 +47,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/funjet2_new.xml b/conf/airframes/ENAC/fixed-wing/funjet2_new.xml index 83436e97ef..f1edbb278c 100644 --- a/conf/airframes/ENAC/fixed-wing/funjet2_new.xml +++ b/conf/airframes/ENAC/fixed-wing/funjet2_new.xml @@ -47,7 +47,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/funjet3.xml b/conf/airframes/ENAC/fixed-wing/funjet3.xml index 764d6e69d7..da2e705780 100644 --- a/conf/airframes/ENAC/fixed-wing/funjet3.xml +++ b/conf/airframes/ENAC/fixed-wing/funjet3.xml @@ -49,7 +49,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/merlin.xml b/conf/airframes/ENAC/fixed-wing/merlin.xml index 2ab3b975ac..17d65550e7 100644 --- a/conf/airframes/ENAC/fixed-wing/merlin.xml +++ b/conf/airframes/ENAC/fixed-wing/merlin.xml @@ -20,7 +20,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/minimag1.xml b/conf/airframes/ENAC/fixed-wing/minimag1.xml index 714f48dc14..4235bd68c9 100644 --- a/conf/airframes/ENAC/fixed-wing/minimag1.xml +++ b/conf/airframes/ENAC/fixed-wing/minimag1.xml @@ -26,7 +26,7 @@ - + diff --git a/conf/airframes/ENAC/fixed-wing/overview.xml b/conf/airframes/ENAC/fixed-wing/overview.xml new file mode 100644 index 0000000000..da39395fe1 --- /dev/null +++ b/conf/airframes/ENAC/fixed-wing/overview.xml @@ -0,0 +1,188 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + + + +
+ +
+ + + + + + + + + + +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + + + + + +
+ +
+ + +
+ +
+ + + + + + + + +
+ +
+ + + + + +
+ +
diff --git a/conf/airframes/ENAC/fixed-wing/spocIII-1.xml b/conf/airframes/ENAC/fixed-wing/spocIII-1.xml index 1ed5c98946..f1ed87e6be 100644 --- a/conf/airframes/ENAC/fixed-wing/spocIII-1.xml +++ b/conf/airframes/ENAC/fixed-wing/spocIII-1.xml @@ -34,7 +34,7 @@ - + - + - + diff --git a/conf/airframes/ENAC/fixed-wing/twinjet2.xml b/conf/airframes/ENAC/fixed-wing/twinjet2.xml index c118819f03..c4881fe2b3 100644 --- a/conf/airframes/ENAC/fixed-wing/twinjet2.xml +++ b/conf/airframes/ENAC/fixed-wing/twinjet2.xml @@ -34,7 +34,7 @@ - +
diff --git a/conf/airframes/LAAS/mmlaas_N1.xml b/conf/airframes/LAAS/mmlaas_N1.xml index 59cacc5ea6..80e16b86ce 100644 --- a/conf/airframes/LAAS/mmlaas_N1.xml +++ b/conf/airframes/LAAS/mmlaas_N1.xml @@ -28,7 +28,7 @@
- + diff --git a/conf/airframes/LAAS/mmlaas_N2.xml b/conf/airframes/LAAS/mmlaas_N2.xml index 018c4551cf..134dfba4ed 100644 --- a/conf/airframes/LAAS/mmlaas_N2.xml +++ b/conf/airframes/LAAS/mmlaas_N2.xml @@ -28,7 +28,7 @@ - + diff --git a/conf/airframes/LAAS/mmlaas_N3.xml b/conf/airframes/LAAS/mmlaas_N3.xml index 5f75acae18..515b5179ad 100644 --- a/conf/airframes/LAAS/mmlaas_N3.xml +++ b/conf/airframes/LAAS/mmlaas_N3.xml @@ -28,7 +28,7 @@ - + diff --git a/conf/airframes/PPZUAV/fixed-wing/ppzimu_tiny.xml b/conf/airframes/PPZUAV/fixed-wing/ppzimu_tiny.xml index e27ed4dde5..c61e31f6b4 100644 --- a/conf/airframes/PPZUAV/fixed-wing/ppzimu_tiny.xml +++ b/conf/airframes/PPZUAV/fixed-wing/ppzimu_tiny.xml @@ -260,7 +260,7 @@ - + diff --git a/conf/airframes/Poine/funjet42.xml b/conf/airframes/Poine/funjet42.xml index 875701c703..f207399ce6 100644 --- a/conf/airframes/Poine/funjet42.xml +++ b/conf/airframes/Poine/funjet42.xml @@ -16,7 +16,7 @@ - + diff --git a/conf/airframes/Poine/swift_1.xml b/conf/airframes/Poine/swift_1.xml index 0f9e70f29f..7b9a62075f 100644 --- a/conf/airframes/Poine/swift_1.xml +++ b/conf/airframes/Poine/swift_1.xml @@ -16,7 +16,7 @@ - + diff --git a/conf/airframes/TU_Delft/MicrojetBR.xml b/conf/airframes/TU_Delft/MicrojetBR.xml index 3ef28141cd..3c61ec196b 100644 --- a/conf/airframes/TU_Delft/MicrojetBR.xml +++ b/conf/airframes/TU_Delft/MicrojetBR.xml @@ -261,7 +261,7 @@ --> - + diff --git a/conf/airframes/TU_Delft/MicrojetBRimu.xml b/conf/airframes/TU_Delft/MicrojetBRimu.xml index c9bacfa7ed..f43c11d34e 100644 --- a/conf/airframes/TU_Delft/MicrojetBRimu.xml +++ b/conf/airframes/TU_Delft/MicrojetBRimu.xml @@ -298,7 +298,7 @@ - + diff --git a/conf/airframes/TU_Delft/MicrojetCDW.xml b/conf/airframes/TU_Delft/MicrojetCDW.xml index fadfc8e760..e2886febb2 100644 --- a/conf/airframes/TU_Delft/MicrojetCDW.xml +++ b/conf/airframes/TU_Delft/MicrojetCDW.xml @@ -215,7 +215,7 @@ - + diff --git a/conf/airframes/delta_wing_minimal_example.xml b/conf/airframes/delta_wing_minimal_example.xml index ff34074880..63256bbf06 100644 --- a/conf/airframes/delta_wing_minimal_example.xml +++ b/conf/airframes/delta_wing_minimal_example.xml @@ -18,7 +18,7 @@ - + diff --git a/conf/airframes/easy_glider_example.xml b/conf/airframes/easy_glider_example.xml index 313e793a84..34404f643d 100644 --- a/conf/airframes/easy_glider_example.xml +++ b/conf/airframes/easy_glider_example.xml @@ -169,7 +169,7 @@ - + diff --git a/conf/airframes/easystar_ets_example.xml b/conf/airframes/easystar_ets_example.xml index 763be2683d..7e4ca831bc 100644 --- a/conf/airframes/easystar_ets_example.xml +++ b/conf/airframes/easystar_ets_example.xml @@ -25,7 +25,7 @@ - + diff --git a/conf/airframes/easystar_example.xml b/conf/airframes/easystar_example.xml index edf296f575..f1241e5274 100644 --- a/conf/airframes/easystar_example.xml +++ b/conf/airframes/easystar_example.xml @@ -24,7 +24,7 @@ - + diff --git a/conf/airframes/example_twog_analogimu.xml b/conf/airframes/example_twog_analogimu.xml index cfe4def763..d212c9586d 100644 --- a/conf/airframes/example_twog_analogimu.xml +++ b/conf/airframes/example_twog_analogimu.xml @@ -213,7 +213,7 @@ - + diff --git a/conf/airframes/flixr_discovery.xml b/conf/airframes/flixr_discovery.xml index c11a5d7754..95dd5eae07 100644 --- a/conf/airframes/flixr_discovery.xml +++ b/conf/airframes/flixr_discovery.xml @@ -42,7 +42,7 @@ http://paparazzi.enac.fr/w/index.php?title=Theory_of_Operation - + diff --git a/conf/airframes/funjet_cam_example.xml b/conf/airframes/funjet_cam_example.xml index 839a8f761d..21578763b8 100644 --- a/conf/airframes/funjet_cam_example.xml +++ b/conf/airframes/funjet_cam_example.xml @@ -28,9 +28,9 @@ - + - + @@ -44,6 +44,9 @@ + + + diff --git a/conf/airframes/funjet_example.xml b/conf/airframes/funjet_example.xml index 9257855ec5..967e9cb736 100644 --- a/conf/airframes/funjet_example.xml +++ b/conf/airframes/funjet_example.xml @@ -28,7 +28,7 @@ - + diff --git a/conf/airframes/jsbsim.xml b/conf/airframes/jsbsim.xml index 18dc8cc3ca..9c70b45f8e 100644 --- a/conf/airframes/jsbsim.xml +++ b/conf/airframes/jsbsim.xml @@ -217,7 +217,7 @@ - + diff --git a/conf/airframes/mentor_tum.xml b/conf/airframes/mentor_tum.xml index 4d00f9c4fa..54be2a848c 100644 --- a/conf/airframes/mentor_tum.xml +++ b/conf/airframes/mentor_tum.xml @@ -24,7 +24,7 @@ - + diff --git a/conf/airframes/microjet_example.xml b/conf/airframes/microjet_example.xml index 405a1356c0..e00b450467 100644 --- a/conf/airframes/microjet_example.xml +++ b/conf/airframes/microjet_example.xml @@ -8,6 +8,7 @@ + @@ -187,7 +188,7 @@ - + diff --git a/conf/airframes/mm/extra/probe_t.xml b/conf/airframes/mm/extra/probe_t.xml index 217b5f9bbd..c35b765f3c 100644 --- a/conf/airframes/mm/extra/probe_t.xml +++ b/conf/airframes/mm/extra/probe_t.xml @@ -17,7 +17,7 @@ - + diff --git a/conf/airframes/mm/extra/turbine_trigger.xml b/conf/airframes/mm/extra/turbine_trigger.xml index 91c6cad9a1..59b3a1db34 100644 --- a/conf/airframes/mm/extra/turbine_trigger.xml +++ b/conf/airframes/mm/extra/turbine_trigger.xml @@ -10,7 +10,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/drops.xml b/conf/airframes/mm/fixed-wing/drops.xml index d725fffcde..9fcb3e4fd8 100644 --- a/conf/airframes/mm/fixed-wing/drops.xml +++ b/conf/airframes/mm/fixed-wing/drops.xml @@ -23,7 +23,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjet43.xml b/conf/airframes/mm/fixed-wing/funjet43.xml index 8da7f898a5..0126c730bf 100644 --- a/conf/airframes/mm/fixed-wing/funjet43.xml +++ b/conf/airframes/mm/fixed-wing/funjet43.xml @@ -21,7 +21,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetdca.xml b/conf/airframes/mm/fixed-wing/funjetdca.xml index 43cad0aa91..f7f7c92b6d 100644 --- a/conf/airframes/mm/fixed-wing/funjetdca.xml +++ b/conf/airframes/mm/fixed-wing/funjetdca.xml @@ -34,7 +34,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetdcb.xml b/conf/airframes/mm/fixed-wing/funjetdcb.xml index a22e56f15f..90c5701c00 100644 --- a/conf/airframes/mm/fixed-wing/funjetdcb.xml +++ b/conf/airframes/mm/fixed-wing/funjetdcb.xml @@ -34,7 +34,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetdcc.xml b/conf/airframes/mm/fixed-wing/funjetdcc.xml index f97b1f2fea..ea06dceedb 100644 --- a/conf/airframes/mm/fixed-wing/funjetdcc.xml +++ b/conf/airframes/mm/fixed-wing/funjetdcc.xml @@ -34,7 +34,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetgfi8.xml b/conf/airframes/mm/fixed-wing/funjetgfi8.xml index 2f28f49668..3c3955a099 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi8.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi8.xml @@ -29,7 +29,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetlisa.xml b/conf/airframes/mm/fixed-wing/funjetlisa.xml index a92f5d8271..2831f87b3c 100644 --- a/conf/airframes/mm/fixed-wing/funjetlisa.xml +++ b/conf/airframes/mm/fixed-wing/funjetlisa.xml @@ -17,7 +17,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetlisam.xml b/conf/airframes/mm/fixed-wing/funjetlisam.xml index 33e68d8522..ba9395fce4 100644 --- a/conf/airframes/mm/fixed-wing/funjetlisam.xml +++ b/conf/airframes/mm/fixed-wing/funjetlisam.xml @@ -17,7 +17,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/funjetmm.xml b/conf/airframes/mm/fixed-wing/funjetmm.xml index 7249478bc8..17fd3c558a 100644 --- a/conf/airframes/mm/fixed-wing/funjetmm.xml +++ b/conf/airframes/mm/fixed-wing/funjetmm.xml @@ -37,7 +37,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/fw_ins_arduimu.xml b/conf/airframes/mm/fixed-wing/fw_ins_arduimu.xml index 144fa3b68f..bd593ded79 100644 --- a/conf/airframes/mm/fixed-wing/fw_ins_arduimu.xml +++ b/conf/airframes/mm/fixed-wing/fw_ins_arduimu.xml @@ -35,7 +35,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/merlin.xml b/conf/airframes/mm/fixed-wing/merlin.xml index cd9c69901e..c901aafb24 100644 --- a/conf/airframes/mm/fixed-wing/merlin.xml +++ b/conf/airframes/mm/fixed-wing/merlin.xml @@ -182,7 +182,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/slowfast.xml b/conf/airframes/mm/fixed-wing/slowfast.xml index 13fca656e9..e2490384cf 100644 --- a/conf/airframes/mm/fixed-wing/slowfast.xml +++ b/conf/airframes/mm/fixed-wing/slowfast.xml @@ -23,7 +23,7 @@ - + diff --git a/conf/airframes/mm/fixed-wing/slowfast2.xml b/conf/airframes/mm/fixed-wing/slowfast2.xml index 13db40d0c9..622adedb12 100644 --- a/conf/airframes/mm/fixed-wing/slowfast2.xml +++ b/conf/airframes/mm/fixed-wing/slowfast2.xml @@ -24,7 +24,7 @@ - + diff --git a/conf/airframes/test_hb.xml b/conf/airframes/test_hb.xml index 30cfa01a09..fc87901459 100644 --- a/conf/airframes/test_hb.xml +++ b/conf/airframes/test_hb.xml @@ -17,7 +17,7 @@ - + diff --git a/conf/airframes/twinjet_example.xml b/conf/airframes/twinjet_example.xml index b5974575d7..58a8205193 100644 --- a/conf/airframes/twinjet_example.xml +++ b/conf/airframes/twinjet_example.xml @@ -23,7 +23,7 @@ - + diff --git a/conf/airframes/twinjet_overo.xml b/conf/airframes/twinjet_overo.xml index 5ed5655242..52b4e0f3d9 100644 --- a/conf/airframes/twinjet_overo.xml +++ b/conf/airframes/twinjet_overo.xml @@ -26,7 +26,7 @@ - + diff --git a/conf/airframes/twinstar_example.xml b/conf/airframes/twinstar_example.xml index 264b8af0ec..c5187f7674 100644 --- a/conf/airframes/twinstar_example.xml +++ b/conf/airframes/twinstar_example.xml @@ -23,7 +23,7 @@ - + diff --git a/conf/airframes/usb_test.xml b/conf/airframes/usb_test.xml index 51592e9f3f..197e442754 100644 --- a/conf/airframes/usb_test.xml +++ b/conf/airframes/usb_test.xml @@ -15,7 +15,7 @@ - + diff --git a/conf/autopilot/booz2_test_progs.makefile b/conf/autopilot/booz2_test_progs.makefile index ff3604c885..05fddfbcc9 100644 --- a/conf/autopilot/booz2_test_progs.makefile +++ b/conf/autopilot/booz2_test_progs.makefile @@ -49,6 +49,7 @@ test_downlink.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./10.))' -DTIM test_downlink.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_downlink.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_downlink.srcs += mcu_periph/uart.c test_downlink.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_downlink.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -68,6 +69,7 @@ test_max1168.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' -DTIM test_max1168.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_max1168.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_max1168.srcs += mcu_periph/uart.c test_max1168.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_max1168.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -89,6 +91,7 @@ test_micromag.CFLAGS += -DUSE_LED test_micromag.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_micromag.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_micromag.srcs += mcu_periph/uart.c test_micromag.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_micromag.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -116,6 +119,7 @@ tunnel.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c tunnel.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400 tunnel.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +tunnel.srcs += mcu_periph/uart.c tunnel.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c @@ -138,7 +142,7 @@ usb_tunnel_0.ARCHDIR = $(ARCH) usb_tunnel_0.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) usb_tunnel_0.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400 -DPERIPHERALS_AUTO_INIT usb_tunnel_0.CFLAGS += -DUSE_USB_LINE_CODING -DUSE_USB_SERIAL -DUSE_LED -usb_tunnel_0.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c $(SRC_ARCH)/mcu_periph/uart_arch.c +usb_tunnel_0.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c usb_tunnel_0.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c usb_tunnel_0.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c usb_tunnel_0.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c @@ -148,7 +152,7 @@ usb_tunnel_1.ARCHDIR = $(ARCH) usb_tunnel_1.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) usb_tunnel_1.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B38400 -DPERIPHERALS_AUTO_INIT usb_tunnel_1.CFLAGS += -DUSE_USB_LINE_CODING -DUSE_USB_SERIAL -DUSE_LED -usb_tunnel_1.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c $(SRC_ARCH)/mcu_periph/uart_arch.c +usb_tunnel_1.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c usb_tunnel_1.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c usb_tunnel_1.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c usb_tunnel_1.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c @@ -167,6 +171,7 @@ test_gps.CFLAGS += -DUSE_LED test_gps.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_gps.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_gps.srcs += mcu_periph/uart.c test_gps.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_gps.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -192,6 +197,7 @@ test_modem.CFLAGS += -DUSE_LED test_modem.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_modem.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_modem.srcs += mcu_periph/uart.c test_modem.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_modem.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -215,13 +221,14 @@ test_usb.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_usb.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c #test_usb.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +#test_usb.srcs += mcu_periph/uart.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)/mcu_periph/uart_arch.c $(SRC_ARCH)/usb_ser_hw.c pprz_transport.c +test_usb.srcs += downlink.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c $(SRC_ARCH)/usb_ser_hw.c pprz_transport.c # $(SRC_FIRMWARE)/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 @@ -243,6 +250,7 @@ test_ami.CFLAGS += -DUSE_LED test_ami.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_ami.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_ami.srcs += mcu_periph/uart.c test_ami.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_ami.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -266,6 +274,7 @@ test_crista.CFLAGS += -DUSE_LED test_crista.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_crista.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B57600 +test_crista.srcs += mcu_periph/uart.c test_crista.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_crista.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0 @@ -292,6 +301,7 @@ test_micromag2.CFLAGS += -DUSE_LED test_micromag2.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_micromag2.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_micromag2.srcs += mcu_periph/uart.c test_micromag2.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_micromag2.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -314,6 +324,7 @@ test_imu_b2.CFLAGS += -DUSE_LED test_imu_b2.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_imu_b2.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_imu_b2.srcs += mcu_periph/uart.c test_imu_b2.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_imu_b2.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -344,6 +355,7 @@ test_rc_spektrum.CFLAGS += -DUSE_LED test_rc_spektrum.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c #test_rc_spektrum.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +#test_rc_spektrum.srcs += mcu_periph/uart.c #test_rc_spektrum.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c #test_rc_spektrum.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 #test_rc_spektrum.srcs += downlink.c pprz_transport.c @@ -360,6 +372,7 @@ test_rc_spektrum.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200 test_rc_spektrum.CFLAGS += -DRADIO_CONTROL_LINK=Uart0 test_rc_spektrum.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ $(SRC_SUBSYSTEMS)/radio_control_spektrum.c \ + mcu_periph/uart.c \ $(SRC_ARCH)/mcu_periph/uart_arch.c # @@ -405,6 +418,7 @@ test_mc.CFLAGS += -DUSE_LED test_mc.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_mc.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_mc.srcs += mcu_periph/uart.c test_mc.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_mc.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -430,6 +444,7 @@ test_buss_bldc.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' -DT test_buss_bldc.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_buss_bldc.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_buss_bldc.srcs += mcu_periph/uart.c test_buss_bldc.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_buss_bldc.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -452,6 +467,7 @@ test_amc.CFLAGS += -DUSE_LED test_amc.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_amc.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_amc.srcs += mcu_periph/uart.c test_amc.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_amc.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 @@ -497,6 +513,7 @@ test_baro_24.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_baro_24.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 +test_baro_24.srcs += mcu_periph/uart.c test_baro_24.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_baro_24.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart1 diff --git a/conf/autopilot/fixedwing.xml b/conf/autopilot/fixedwing.xml index f65f6282b1..ad2527f967 100644 --- a/conf/autopilot/fixedwing.xml +++ b/conf/autopilot/fixedwing.xml @@ -34,7 +34,7 @@ - + diff --git a/conf/autopilot/lisa_l_test_progs.makefile b/conf/autopilot/lisa_l_test_progs.makefile index 22f35e0081..a2292f254f 100644 --- a/conf/autopilot/lisa_l_test_progs.makefile +++ b/conf/autopilot/lisa_l_test_progs.makefile @@ -95,6 +95,7 @@ test_uart.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_uart.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 test_uart.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 test_uart.CFLAGS += -DUSE_UART3 -DUART3_BAUD=B57600 +test_uart.srcs += mcu_periph/uart.c test_uart.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c @@ -176,6 +177,7 @@ test_baro.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_baro.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) test_baro.srcs += downlink.c pprz_transport.c test_baro.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_baro.srcs += mcu_periph/uart.c test_baro.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_baro.srcs += $(SRC_BOARD)/baro_board.c test_baro.CFLAGS += -DUSE_I2C2 @@ -209,6 +211,7 @@ test_rc_spektrum.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' test_rc_spektrum.CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED) test_rc_spektrum.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_rc_spektrum.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_rc_spektrum.srcs += mcu_periph/uart.c test_rc_spektrum.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_rc_spektrum.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) test_rc_spektrum.srcs += downlink.c pprz_transport.c @@ -252,6 +255,7 @@ test_rc_ppm.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' test_rc_ppm.CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED) test_rc_ppm.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_rc_ppm.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_rc_ppm.srcs += mcu_periph/uart.c test_rc_ppm.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_rc_ppm.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) test_rc_ppm.srcs += downlink.c pprz_transport.c @@ -291,6 +295,7 @@ test_adc.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' test_adc.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_adc.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_adc.srcs += mcu_periph/uart.c test_adc.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_adc.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=$(MODEM_PORT) @@ -327,6 +332,7 @@ COMMON_TEST_CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./$(PERIODIC_FRE COMMON_TEST_CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY) COMMON_TEST_SRCS += sys_time.c $(SRC_ARCH)/sys_time_hw.c COMMON_TEST_CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +COMMON_TEST_SRCS += mcu_periph/uart.c COMMON_TEST_SRCS += $(SRC_ARCH)/mcu_periph/uart_arch.c COMMON_TEST_CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) COMMON_TEST_SRCS += downlink.c pprz_transport.c @@ -494,6 +500,7 @@ test_hmc5843.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' test_hmc5843.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_hmc5843.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_hmc5843.srcs += mcu_periph/uart.c test_hmc5843.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_hmc5843.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) @@ -525,6 +532,7 @@ test_itg3200.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' test_itg3200.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_itg3200.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_itg3200.srcs += mcu_periph/uart.c test_itg3200.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_itg3200.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) @@ -555,6 +563,7 @@ test_adxl345.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' test_adxl345.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_adxl345.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +test_adxl345.srcs += mcu_periph/uart.c test_adxl345.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_adxl345.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -626,6 +635,7 @@ test_actuators_mkk.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' test_actuators_mkk.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_actuators_mkk.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +test_actuators_mkk.srcs += mcu_periph/uart.c test_actuators_mkk.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_actuators_mkk.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -658,6 +668,7 @@ test_actuators_asctecv1.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512 test_actuators_asctecv1.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_actuators_asctecv1.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +test_actuators_asctecv1.srcs += mcu_periph/uart.c test_actuators_asctecv1.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_actuators_asctecv1.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -688,6 +699,7 @@ test_bmp085.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' test_bmp085.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_bmp085.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_bmp085.srcs += mcu_periph/uart.c test_bmp085.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_bmp085.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) @@ -783,6 +795,7 @@ tunnel_hw.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' tunnel_hw.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c tunnel_hw.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 tunnel_hw.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +tunnel_hw.srcs += mcu_periph/uart.c tunnel_hw.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c @@ -812,6 +825,7 @@ test_settings.CFLAGS += -DUSE_$(MODEM_PORT) test_settings.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) test_settings.srcs += downlink.c pprz_transport.c test_settings.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) +test_settings.srcs += mcu_periph/uart.c test_settings.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_settings.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=$(MODEM_PORT) test_settings.srcs += subsystems/settings.c diff --git a/conf/autopilot/lisa_m_test_progs.makefile b/conf/autopilot/lisa_m_test_progs.makefile index 9fa3bd820f..2922f9aeec 100644 --- a/conf/autopilot/lisa_m_test_progs.makefile +++ b/conf/autopilot/lisa_m_test_progs.makefile @@ -93,6 +93,7 @@ test_uart_lisam.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 test_uart_lisam.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 test_uart_lisam.CFLAGS += -DUSE_UART3 -DUART3_BAUD=B57600 test_uart_lisam.CFLAGS += -DUSE_UART5 -DUART5_BAUD=B57600 +test_uart_lisam.srcs += mcu_periph/uart.c test_uart_lisam.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c @@ -145,6 +146,7 @@ test_telemetry.CFLAGS += -DUSE_$(MODEM_PORT) test_telemetry.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) test_telemetry.srcs += downlink.c pprz_transport.c test_telemetry.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) +test_telemetry.srcs += mcu_periph/uart.c test_telemetry.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # # @@ -173,6 +175,7 @@ test_baro.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_baro.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) test_baro.srcs += downlink.c pprz_transport.c test_baro.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_baro.srcs += mcu_periph/uart.c test_baro.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_baro.srcs += $(SRC_BOARD)/baro_board.c test_baro.CFLAGS += -DUSE_I2C2 @@ -206,6 +209,7 @@ test_rc_spektrum.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' test_rc_spektrum.CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED) test_rc_spektrum.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c test_rc_spektrum.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +test_rc_spektrum.srcs += mcu_periph/uart.c test_rc_spektrum.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_rc_spektrum.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) test_rc_spektrum.srcs += downlink.c pprz_transport.c @@ -251,6 +255,7 @@ test_rc_spektrum.srcs += $(SRC_SUBSYSTEMS)/radio_control.c #test_rc_ppm.CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED) #test_rc_ppm.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c #test_rc_ppm.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_rc_ppm.srcs += mcu_periph/uart.c #test_rc_ppm.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c #test_rc_ppm.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) #test_rc_ppm.srcs += downlink.c pprz_transport.c @@ -290,6 +295,7 @@ test_rc_spektrum.srcs += $(SRC_SUBSYSTEMS)/radio_control.c #test_adc.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_adc.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_adc.srcs += mcu_periph/uart.c #test_adc.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c #test_adc.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=$(MODEM_PORT) # @@ -326,6 +332,7 @@ test_rc_spektrum.srcs += $(SRC_SUBSYSTEMS)/radio_control.c #test_imu_b2.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_imu_b2.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_imu_b2.srcs += mcu_periph/uart.c #test_imu_b2.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_imu_b2.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -369,6 +376,7 @@ test_rc_spektrum.srcs += $(SRC_SUBSYSTEMS)/radio_control.c #test_imu_b2_2.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_imu_b2_2.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_imu_b2_2.srcs += mcu_periph/uart.c #test_imu_b2_2.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_imu_b2_2.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -416,6 +424,7 @@ test_imu_aspirin.CFLAGS += -DUSE_$(MODEM_PORT) test_imu_aspirin.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) test_imu_aspirin.srcs += downlink.c pprz_transport.c test_imu_aspirin.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) +test_imu_aspirin.srcs += mcu_periph/uart.c test_imu_aspirin.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c test_imu_aspirin.srcs += math/pprz_trig_int.c test_imu_aspirin.CFLAGS += -DIMU_TYPE_H=\"imu/imu_aspirin.h\" -DIMU_OVERRIDE_CHANNELS @@ -449,6 +458,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_hmc5843.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_hmc5843.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_hmc5843.srcs += mcu_periph/uart.c #test_hmc5843.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_hmc5843.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) @@ -480,6 +490,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_itg3200.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_itg3200.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_itg3200.srcs += mcu_periph/uart.c #test_itg3200.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_itg3200.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) @@ -510,6 +521,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_adxl345.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_adxl345.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +#test_adxl345.srcs += mcu_periph/uart.c #test_adxl345.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_adxl345.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -581,6 +593,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_actuators_mkk.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_actuators_mkk.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +#test_actuators_mkk.srcs += mcu_periph/uart.c #test_actuators_mkk.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_actuators_mkk.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -613,6 +626,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_actuators_asctecv1.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_actuators_asctecv1.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +#test_actuators_asctecv1.srcs += mcu_periph/uart.c #test_actuators_asctecv1.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_actuators_asctecv1.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 @@ -643,6 +657,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_bmp085.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_bmp085.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_bmp085.srcs += mcu_periph/uart.c #test_bmp085.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_bmp085.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) @@ -673,6 +688,7 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_manual.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c # #test_manual.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) +#test_manual.srcs += mcu_periph/uart.c #test_manual.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # #test_manual.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT) diff --git a/conf/autopilot/lisa_passthrough.makefile b/conf/autopilot/lisa_passthrough.makefile index 05526f258a..74dea03fdf 100644 --- a/conf/autopilot/lisa_passthrough.makefile +++ b/conf/autopilot/lisa_passthrough.makefile @@ -42,6 +42,7 @@ stm_passthrough.CFLAGS += -DDOWNLINK stm_passthrough.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2 stm_passthrough.srcs += downlink.c pprz_transport.c stm_passthrough.CFLAGS += -DUSE_UART2 -DUART2_BAUD=B57600 +stm_passthrough.srcs += mcu_periph/uart.c stm_passthrough.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # Link Overo diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile index c2e3c421c2..a6585b42fe 100644 --- a/conf/autopilot/rotorcraft.makefile +++ b/conf/autopilot/rotorcraft.makefile @@ -98,6 +98,8 @@ endif # ap.srcs += subsystems/settings.c ap.srcs += $(SRC_ARCH)/subsystems/settings_arch.c + +ap.srcs += mcu_periph/uart.c ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # I2C is needed for speed controllers and barometers on lisa diff --git a/conf/autopilot/setup.makefile b/conf/autopilot/setup.makefile index f633384d9a..246c8c7277 100644 --- a/conf/autopilot/setup.makefile +++ b/conf/autopilot/setup.makefile @@ -26,7 +26,7 @@ tunnel.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c ifeq ($(ARCH), lpc21) usb_tunnel_0.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200 -DPERIPHERALS_AUTO_INIT usb_tunnel_0.CFLAGS += -DUSE_USB_LINE_CODING -DUSE_USB_SERIAL -DUSE_LED -DUSE_USB_HIGH_PCLK -usb_tunnel_0.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c $(SRC_ARCH)/mcu_periph/uart_arch.c +usb_tunnel_0.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c usb_tunnel_0.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c usb_tunnel_0.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c usb_tunnel_0.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c @@ -34,7 +34,7 @@ usb_tunnel_0.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c usb_tunnel_1.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B115200 -DPERIPHERALS_AUTO_INIT usb_tunnel_1.CFLAGS += -DUSE_USB_LINE_CODING -DUSE_USB_SERIAL -DUSE_LED -DUSE_USB_HIGH_PCLK -usb_tunnel_1.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c $(SRC_ARCH)/mcu_periph/uart_arch.c +usb_tunnel_1.srcs += $(SRC_ARCH)/usb_tunnel.c $(SRC_ARCH)/usb_ser_hw.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c usb_tunnel_1.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c usb_tunnel_1.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c usb_tunnel_1.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c @@ -78,7 +78,7 @@ setup_actuators.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 -DDOWNLINK_DEVICE=Uart setup_actuators.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=PPRZ setup_actuators.CFLAGS += -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 setup_actuators.CFLAGS += $(SETUP_INC) -Ifirmwares/fixedwing -setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c downlink.c $(SRC_FIRMWARE)/setup_actuators.c $(SRC_ARCH)/mcu_periph/uart_arch.c firmwares/fixedwing/main.c mcu.c $(SRC_ARCH)/mcu_arch.c +setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c downlink.c $(SRC_FIRMWARE)/setup_actuators.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c firmwares/fixedwing/main.c mcu.c $(SRC_ARCH)/mcu_arch.c # a test program for ABI test_abi.CFLAGS += -DUSE_LED -DPERIPHERALS_AUTO_INIT diff --git a/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile b/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile index 7395522edb..6f51989bd1 100644 --- a/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile +++ b/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile @@ -36,4 +36,6 @@ $(TARGET).srcs += subsystems/sensors/infrared.c $(TARGET).srcs += subsystems/sensors/infrared_adc.c sim.srcs += $(SRC_ARCH)/sim_ir.c -jsbsim.srcs += $(SRC_ARCH)/jsbsim_ir.c + +# is already added to sources in autopilot.makefile +#jsbsim.srcs += $(SRC_ARCH)/jsbsim_ir.c diff --git a/conf/autopilot/subsystems/fixedwing/autopilot.makefile b/conf/autopilot/subsystems/fixedwing/autopilot.makefile index 1df9a246cc..2bcd6f2984 100644 --- a/conf/autopilot/subsystems/fixedwing/autopilot.makefile +++ b/conf/autopilot/subsystems/fixedwing/autopilot.makefile @@ -137,6 +137,7 @@ ns_srcs += $(SRC_ARCH)/sys_time_hw.c # UARTS # +ns_srcs += mcu_periph/uart.c ns_srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c ns_srcs += subsystems/settings.c ns_srcs += $(SRC_ARCH)/subsystems/settings_arch.c diff --git a/conf/autopilot/subsystems/fixedwing/gps_mediatek_diy.makefile b/conf/autopilot/subsystems/fixedwing/gps_mediatek_diy.makefile new file mode 100644 index 0000000000..5b11c32b8d --- /dev/null +++ b/conf/autopilot/subsystems/fixedwing/gps_mediatek_diy.makefile @@ -0,0 +1,23 @@ +# Mediatek MT3329, DIYDrones V1.4/1.6 protocol + + +ap.CFLAGS += -DUSE_GPS -DGPS_CONFIGURE -DGPS_USE_LATLONG +ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) +ap.CFLAGS += -DUSE_$(GPS_PORT) +ap.CFLAGS += -D$(GPS_PORT)_BAUD=$(GPS_BAUD) + +ifneq ($(GPS_LED),none) + ap.CFLAGS += -DGPS_LED=$(GPS_LED) +endif + +ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_mtk.h\" +ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_mtk.c + +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c + +sim.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG +sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c + +jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c diff --git a/conf/autopilot/subsystems/fixedwing/gps_ublox.makefile b/conf/autopilot/subsystems/fixedwing/gps_ublox.makefile new file mode 100644 index 0000000000..d8d5723be0 --- /dev/null +++ b/conf/autopilot/subsystems/fixedwing/gps_ublox.makefile @@ -0,0 +1,23 @@ +# UBlox LEA 5H + + +ap.CFLAGS += -DUSE_GPS -DUBX -DGPS_USE_LATLONG +ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) +ap.CFLAGS += -DUSE_$(GPS_PORT) +ap.CFLAGS += -D$(GPS_PORT)_BAUD=$(GPS_BAUD) + +ifneq ($(GPS_LED),none) + ap.CFLAGS += -DGPS_LED=$(GPS_LED) +endif + +ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\" +ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c + +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c + +sim.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG +sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c + +jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c diff --git a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h_hitl.makefile b/conf/autopilot/subsystems/fixedwing/gps_ublox_hitl.makefile similarity index 85% rename from conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h_hitl.makefile rename to conf/autopilot/subsystems/fixedwing/gps_ublox_hitl.makefile index 40338ab345..43d6130d6b 100644 --- a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h_hitl.makefile +++ b/conf/autopilot/subsystems/fixedwing/gps_ublox_hitl.makefile @@ -1,4 +1,4 @@ -# UBlox LEA 5H +# UBlox Hardware In The Loop ap.CFLAGS += -DUSE_GPS -DUBX -DGPS_USE_LATLONG diff --git a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea4p.makefile b/conf/autopilot/subsystems/fixedwing/gps_ublox_lea4p.makefile index 368d4e76a8..da4d84a19d 100644 --- a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea4p.makefile +++ b/conf/autopilot/subsystems/fixedwing/gps_ublox_lea4p.makefile @@ -1,22 +1,3 @@ # UBlox LEA 4P - -ap.CFLAGS += -DUSE_GPS -DUBX -ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) -ap.CFLAGS += -DUSE_$(GPS_PORT) -ap.CFLAGS += -D$(GPS_PORT)_BAUD=$(GPS_BAUD) - -ifneq ($(GPS_LED),none) - ap.CFLAGS += -DGPS_LED=$(GPS_LED) -endif - -ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\" -ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c - -$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c - -sim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" -sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c - -jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" -jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c +$(error The gps_ublox_lea4p subsystem has been renamed, please replace with in your airframe file.) diff --git a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h.makefile b/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h.makefile index d8d5723be0..59e9799be5 100644 --- a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h.makefile +++ b/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h.makefile @@ -1,23 +1,4 @@ # UBlox LEA 5H +$(error The gps_ublox_lea5h subsystem has been renamed, please replace with in your airframe file.) -ap.CFLAGS += -DUSE_GPS -DUBX -DGPS_USE_LATLONG -ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) -ap.CFLAGS += -DUSE_$(GPS_PORT) -ap.CFLAGS += -D$(GPS_PORT)_BAUD=$(GPS_BAUD) - -ifneq ($(GPS_LED),none) - ap.CFLAGS += -DGPS_LED=$(GPS_LED) -endif - -ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\" -ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c - -$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c - -sim.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG -sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" -sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c - -jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" -jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c diff --git a/conf/autopilot/subsystems/fixedwing/gps_ublox_utm.makefile b/conf/autopilot/subsystems/fixedwing/gps_ublox_utm.makefile new file mode 100644 index 0000000000..368d4e76a8 --- /dev/null +++ b/conf/autopilot/subsystems/fixedwing/gps_ublox_utm.makefile @@ -0,0 +1,22 @@ +# UBlox LEA 4P + + +ap.CFLAGS += -DUSE_GPS -DUBX +ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) +ap.CFLAGS += -DUSE_$(GPS_PORT) +ap.CFLAGS += -D$(GPS_PORT)_BAUD=$(GPS_BAUD) + +ifneq ($(GPS_LED),none) + ap.CFLAGS += -DGPS_LED=$(GPS_LED) +endif + +ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\" +ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c + +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c + +sim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c + +jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c diff --git a/conf/autopilot/subsystems/fixedwing/imu_ppzuav.makefile b/conf/autopilot/subsystems/fixedwing/imu_ppzuav.makefile index dee6b9aaf9..c7a4b3910a 100644 --- a/conf/autopilot/subsystems/fixedwing/imu_ppzuav.makefile +++ b/conf/autopilot/subsystems/fixedwing/imu_ppzuav.makefile @@ -1,22 +1,22 @@ -IMU_PPZUAVIMU_CFLAGS = -DUSE_IMU -IMU_PPZUAVIMU_CFLAGS += -DIMU_TYPE_H=\"modules/ins/ins_ppzuavimu.h\" +IMU_PPZUAV_CFLAGS = -DUSE_IMU +IMU_PPZUAV_CFLAGS += -DIMU_TYPE_H=\"modules/sensors/imu_ppzuav.h\" -IMU_PPZUAVIMU_SRCS = $(SRC_SUBSYSTEMS)/imu.c \ - $(SRC_MODULES)/ins/ins_ppzuavimu.c +IMU_PPZUAV_SRCS = $(SRC_SUBSYSTEMS)/imu.c \ + $(SRC_MODULES)/sensors/imu_ppzuav.c -IMU_PPZUAVIMU_CFLAGS += -DUSE_I2C +IMU_PPZUAV_CFLAGS += -DUSE_I2C ifeq ($(ARCH), stm32) - IMU_PPZUAVIMU_CFLAGS += -DUSE_I2C2 - IMU_PPZUAVIMU_CFLAGS += -DPPZUAVIMU_I2C_DEVICE=i2c2 + IMU_PPZUAV_CFLAGS += -DUSE_I2C2 + IMU_PPZUAV_CFLAGS += -DPPZUAVIMU_I2C_DEVICE=i2c2 else ifeq ($(ARCH), lpc21) - IMU_PPZUAVIMU_CFLAGS += -DUSE_I2C0 - IMU_PPZUAVIMU_CFLAGS += -DPPZUAVIMU_I2C_DEVICE=i2c0 + IMU_PPZUAV_CFLAGS += -DUSE_I2C0 + IMU_PPZUAV_CFLAGS += -DPPZUAVIMU_I2C_DEVICE=i2c0 endif -ap.CFLAGS += $(IMU_PPZUAVIMU_CFLAGS) -ap.srcs += $(IMU_PPZUAVIMU_SRCS) +ap.CFLAGS += $(IMU_PPZUAV_CFLAGS) +ap.srcs += $(IMU_PPZUAV_SRCS) ap.CFLAGS += -DAHRS_MAG_UPDATE_YAW_ONLY diff --git a/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile b/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile index 51e0e4c1ce..70bc35ceaa 100644 --- a/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile +++ b/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile @@ -18,7 +18,7 @@ NPSDIR = $(SIMDIR)/nps sim.ARCHDIR = $(ARCH) sim.CFLAGS += -DSITL -DNPS -sim.CFLAGS += `pkg-config glib-2.0 --cflags` -I /usr/include/meschach +sim.CFLAGS += `pkg-config glib-2.0 --cflags` sim.LDFLAGS += `pkg-config glib-2.0 --libs` -lm -lpcre -lglibivy -lgsl -lgslcblas sim.CFLAGS += -I$(NPSDIR) -I$(SRC_FIRMWARE) -I$(SRC_BOARD) -I../simulator -I$(PAPARAZZI_HOME)/conf/simulator/nps diff --git a/conf/conf.xml.example b/conf/conf.xml.example index 86c4d30d5d..de5832bada 100644 --- a/conf/conf.xml.example +++ b/conf/conf.xml.example @@ -29,9 +29,9 @@ diff --git a/conf/control_panel.xml.example b/conf/control_panel.xml.example index b54fddac02..88bb2185d3 100644 --- a/conf/control_panel.xml.example +++ b/conf/control_panel.xml.example @@ -68,6 +68,8 @@ + + diff --git a/conf/flight_plans/standard.xml b/conf/flight_plans/standard.xml deleted file mode 100644 index ffa5e8dbda..0000000000 --- a/conf/flight_plans/standard.xml +++ /dev/null @@ -1,84 +0,0 @@ - - - -
-#include "subsystems/navigation/nav_line.h" -#include "datalink.h" -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/conf/maps.dtd b/conf/maps.dtd new file mode 100644 index 0000000000..74f1070fd8 --- /dev/null +++ b/conf/maps.dtd @@ -0,0 +1,6 @@ + + + + + diff --git a/conf/maps.xml.example b/conf/maps.xml.example new file mode 100644 index 0000000000..0103dd0ef4 --- /dev/null +++ b/conf/maps.xml.example @@ -0,0 +1,3 @@ + + + diff --git a/conf/messages.xml b/conf/messages.xml index 850381a788..2f4bf78a64 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -130,8 +130,8 @@ - - + + @@ -489,13 +489,63 @@ - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + + + + + + @@ -550,6 +600,8 @@ + + @@ -652,7 +704,7 @@ - + @@ -731,16 +783,16 @@ - - - + + + - - - - - - + + + + + + @@ -800,7 +852,28 @@ - + + + + + + + + + + + + + + + + + + + + + + @@ -838,8 +911,31 @@ - - + + + + + + + + + + + + + + + + + + + + + + + + + @@ -1137,8 +1233,18 @@ - - + + + + + + + + + + + + diff --git a/conf/modules/AOA_adc.xml b/conf/modules/AOA_adc.xml new file mode 100644 index 0000000000..553ace5c0f --- /dev/null +++ b/conf/modules/AOA_adc.xml @@ -0,0 +1,24 @@ + + + + + + +
+ +
+ + + + + + + + + + + +
+ diff --git a/conf/modules/airspeed_amsys.xml b/conf/modules/airspeed_amsys.xml new file mode 100755 index 0000000000..87e6d92d61 --- /dev/null +++ b/conf/modules/airspeed_amsys.xml @@ -0,0 +1,25 @@ + + + + + + +
+ +
+ + + + + + + + +
diff --git a/conf/modules/baro_amsys.xml b/conf/modules/baro_amsys.xml new file mode 100755 index 0000000000..e7364b4a16 --- /dev/null +++ b/conf/modules/baro_amsys.xml @@ -0,0 +1,21 @@ + + + + + + +
+ +
+ + + + + + + + +
diff --git a/conf/modules/cam_segment.xml b/conf/modules/cam_segment.xml new file mode 100644 index 0000000000..0bbb23e0a1 --- /dev/null +++ b/conf/modules/cam_segment.xml @@ -0,0 +1,13 @@ + + + + +
+ +
+ + + + + +
diff --git a/conf/modules/digital_cam.xml b/conf/modules/digital_cam.xml index e190c57f90..627061410c 100644 --- a/conf/modules/digital_cam.xml +++ b/conf/modules/digital_cam.xml @@ -1,8 +1,8 @@ - @@ -33,10 +33,9 @@ - + - diff --git a/conf/modules/flight_benchmark.xml b/conf/modules/flight_benchmark.xml new file mode 100644 index 0000000000..bbd59403bb --- /dev/null +++ b/conf/modules/flight_benchmark.xml @@ -0,0 +1,14 @@ + + + +
+ +
+ + + + + + +
+ diff --git a/conf/modules/geiger_counter.xml b/conf/modules/geiger_counter.xml new file mode 100644 index 0000000000..a09ec1c90a --- /dev/null +++ b/conf/modules/geiger_counter.xml @@ -0,0 +1,14 @@ + + + +
+ +
+ + + + + + +
+ diff --git a/conf/modules/humid_pcap01.xml b/conf/modules/humid_pcap01.xml new file mode 100644 index 0000000000..2e792e2c2c --- /dev/null +++ b/conf/modules/humid_pcap01.xml @@ -0,0 +1,13 @@ + + + +
+ +
+ + + + + + +
\ No newline at end of file diff --git a/conf/modules/humid_sht_i2c.xml b/conf/modules/humid_sht_i2c.xml index a9587748e3..82eb88d942 100644 --- a/conf/modules/humid_sht_i2c.xml +++ b/conf/modules/humid_sht_i2c.xml @@ -9,11 +9,11 @@
- - + + - + diff --git a/conf/modules/imu_aspirin_i2c.xml b/conf/modules/imu_aspirin_i2c.xml new file mode 100644 index 0000000000..140fdf5fb7 --- /dev/null +++ b/conf/modules/imu_aspirin_i2c.xml @@ -0,0 +1,25 @@ + + + + +
+ +
+ + + + + + + + + + + + + + + + + +
diff --git a/conf/modules/imu_ppzuav.xml b/conf/modules/imu_ppzuav.xml new file mode 100644 index 0000000000..5b32512991 --- /dev/null +++ b/conf/modules/imu_ppzuav.xml @@ -0,0 +1,24 @@ + + + + +
+ +
+ + + + + + + + + + + + + + + + +
diff --git a/conf/modules/ins_aspirin_via_i2c.xml b/conf/modules/ins_aspirin_via_i2c.xml index d5f93cd327..4a73004f2c 100644 --- a/conf/modules/ins_aspirin_via_i2c.xml +++ b/conf/modules/ins_aspirin_via_i2c.xml @@ -6,20 +6,9 @@ - - - - - - - - - - - - - - + +$(error The ins_aspirin_via_i2c module has been renamed, please replace the name="ins_aspirin_via_i2c.xml" with name="imu_aspirin_i2c.xml" in the load tag of your airframe file modules section.) + diff --git a/conf/modules/ins_chimu_spi.xml b/conf/modules/ins_chimu_spi.xml index c4da2f470a..ea57d2ff2e 100644 --- a/conf/modules/ins_chimu_spi.xml +++ b/conf/modules/ins_chimu_spi.xml @@ -11,10 +11,10 @@ - + - + diff --git a/conf/modules/ins_chimu_uart.xml b/conf/modules/ins_chimu_uart.xml index 94dc63594a..f6c69cecbc 100644 --- a/conf/modules/ins_chimu_uart.xml +++ b/conf/modules/ins_chimu_uart.xml @@ -17,7 +17,7 @@ For older CHIMU v1.0 you should define CHIMU_BIG_ENDIAN - + diff --git a/conf/modules/ins_ppzuavimu.xml b/conf/modules/ins_ppzuavimu.xml index a2544c204d..ddc1962102 100644 --- a/conf/modules/ins_ppzuavimu.xml +++ b/conf/modules/ins_ppzuavimu.xml @@ -1,24 +1,13 @@ -
- +
- - - - - - - - - - - - - - + + +$(error The ins_ppzuavimu module has been renamed, please replace the name="ins_ppzuavimu.xml" with name="imu_ppzuav.xml" in the load tag of your airframe file modules section.) +
diff --git a/conf/modules/light_solar.xml b/conf/modules/light_solar.xml new file mode 100644 index 0000000000..7cf08e80b9 --- /dev/null +++ b/conf/modules/light_solar.xml @@ -0,0 +1,17 @@ + + + +
+ +
+ + + + + + + + + +
+ diff --git a/conf/modules/temp_tcouple_adc.xml b/conf/modules/temp_tcouple_adc.xml new file mode 100644 index 0000000000..0b44301318 --- /dev/null +++ b/conf/modules/temp_tcouple_adc.xml @@ -0,0 +1,17 @@ + + + +
+ +
+ + + + + + + + + +
+ diff --git a/conf/mtk.dtd b/conf/mtk.dtd new file mode 100644 index 0000000000..60aeb6c8b7 --- /dev/null +++ b/conf/mtk.dtd @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/conf/mtk.xml b/conf/mtk.xml new file mode 100644 index 0000000000..201ba3b60a --- /dev/null +++ b/conf/mtk.xml @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/conf/settings/AOA_adc.xml b/conf/settings/AOA_adc.xml new file mode 100644 index 0000000000..72fa08af3a --- /dev/null +++ b/conf/settings/AOA_adc.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/conf/settings/airspeed_amsys.xml b/conf/settings/airspeed_amsys.xml new file mode 100755 index 0000000000..875cc5a9b7 --- /dev/null +++ b/conf/settings/airspeed_amsys.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/conf/settings/baro_amsys.xml b/conf/settings/baro_amsys.xml new file mode 100755 index 0000000000..162b81c06b --- /dev/null +++ b/conf/settings/baro_amsys.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/conf/settings/basic.xml b/conf/settings/basic.xml index 767f0659f7..252f4aeec6 100644 --- a/conf/settings/basic.xml +++ b/conf/settings/basic.xml @@ -10,10 +10,10 @@ - + - - + + @@ -21,13 +21,9 @@ - + - - - - diff --git a/conf/settings/basic_infrared.xml b/conf/settings/basic_infrared.xml new file mode 100644 index 0000000000..2933dca3be --- /dev/null +++ b/conf/settings/basic_infrared.xml @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/conf/settings/basic_ins.xml b/conf/settings/basic_ins.xml new file mode 100644 index 0000000000..f11281ab82 --- /dev/null +++ b/conf/settings/basic_ins.xml @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/conf/settings/benchmark.xml b/conf/settings/benchmark.xml new file mode 100755 index 0000000000..31d3b08c1e --- /dev/null +++ b/conf/settings/benchmark.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/conf/settings/cam.xml b/conf/settings/cam.xml index 2511de50b1..e581080f24 100644 --- a/conf/settings/cam.xml +++ b/conf/settings/cam.xml @@ -3,7 +3,7 @@ - + diff --git a/conf/settings/dc.xml b/conf/settings/dc.xml index b2e44f1e56..c859849583 100644 --- a/conf/settings/dc.xml +++ b/conf/settings/dc.xml @@ -19,6 +19,9 @@ + + + diff --git a/conf/settings/flight_params.xml b/conf/settings/flight_params.xml index 19bb8d51df..00b68d0496 100644 --- a/conf/settings/flight_params.xml +++ b/conf/settings/flight_params.xml @@ -26,12 +26,11 @@ - - + + + - - diff --git a/conf/settings/ins_basic.xml b/conf/settings/ins_neutrals.xml similarity index 100% rename from conf/settings/ins_basic.xml rename to conf/settings/ins_neutrals.xml diff --git a/conf/settings/tuning.xml b/conf/settings/tuning.xml index 22ac1e1d7c..8e9538720e 100644 --- a/conf/settings/tuning.xml +++ b/conf/settings/tuning.xml @@ -17,8 +17,8 @@ - - + + @@ -30,21 +30,6 @@ - - - - - - - - - - - - - - - @@ -54,10 +39,8 @@ - - diff --git a/conf/settings/tuning_infrared.xml b/conf/settings/tuning_infrared.xml new file mode 100644 index 0000000000..aa9a9c18b0 --- /dev/null +++ b/conf/settings/tuning_infrared.xml @@ -0,0 +1,109 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/conf/settings/tuning_ins.xml b/conf/settings/tuning_ins.xml index 2cf8fe880b..1f092a4a56 100644 --- a/conf/settings/tuning_ins.xml +++ b/conf/settings/tuning_ins.xml @@ -17,8 +17,8 @@ - - + + @@ -32,9 +32,6 @@ - - - diff --git a/conf/settings/tuning_basic_ins.xml b/conf/settings/tuning_ins_dcm.xml similarity index 91% rename from conf/settings/tuning_basic_ins.xml rename to conf/settings/tuning_ins_dcm.xml index 0d84278f26..4ba4f43d96 100644 --- a/conf/settings/tuning_basic_ins.xml +++ b/conf/settings/tuning_ins_dcm.xml @@ -17,8 +17,8 @@ - - + + @@ -32,6 +32,9 @@ + + + diff --git a/conf/telemetry/default_fixedwing_imu.xml b/conf/telemetry/default_fixedwing_imu.xml index 256cb30917..28e3f604b0 100644 --- a/conf/telemetry/default_fixedwing_imu.xml +++ b/conf/telemetry/default_fixedwing_imu.xml @@ -53,6 +53,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + @@ -71,17 +96,6 @@ - - - - - - - - - - - diff --git a/conf/wavecard.xml b/conf/wavecard.xml deleted file mode 100644 index 431efd5638..0000000000 --- a/conf/wavecard.xml +++ /dev/null @@ -1,54 +0,0 @@ - - - - - - - - - - - - - - - - - - - - 0x40, "REQ_WRITE_RADIO_PARAM"; - 0x41, "RES_WRITE_RADIO_PARAM"; - 0x50, "REQ_READ_RADIO_PARAM"; - 0x51, "RES_READ_RADIO_PARAM"; - 0x60, "REQ_SELECT_CHANNEL"; - 0x61, "RES_SELECT_CHANNEL"; - 0x62, "REQ_READ_CHANNEL"; - 0x63, "RES_READ_CHANNEL"; - 0x64, "REQ_SELECT_PHYCONFIG"; - 0x65, "RES_SELECT_PHYCONFIG"; - 0x66, "REQ_READ_PHYCONFIG"; - 0x67, "RES_READ_PHYCONFIG"; - 0x68, "REQ_READ_REMOTE_RSSI"; - 0x69, "RES_READ_REMOTE_RSSI"; - 0x6A, "REQ_READ_LOCAL_RSSI"; - 0x6B, "RES_READ_LOCAL_RSSI"; - 0xA0, "REQ_FIRMWARE_VERSION"; - 0xA1, "RES_ FIRMWARE_VERSION"; - - - - - - - - - - - - - - - - - diff --git a/conf/waypoints.xml b/conf/waypoints.xml deleted file mode 100644 index 011b9a8a9c..0000000000 --- a/conf/waypoints.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/data/maps/Makefile b/data/maps/Makefile index 784efe1bf5..6ceb046a40 100644 --- a/data/maps/Makefile +++ b/data/maps/Makefile @@ -1,16 +1,17 @@ DATADIR = $(PAPARAZZI_HOME)/conf/maps_data Q=@ -all: $(DATADIR)/maps.google.com $(DATADIR)/maps.conf +all: $(DATADIR)/maps.google.com $(PAPARAZZI_HOME)/conf/maps.xml $(DATADIR): mkdir $(DATADIR) -$(DATADIR)/maps.google.com: $(DATADIR) +$(DATADIR)/maps.google.com: $(DATADIR) FORCE wget -O $(@) http://maps.google.com/ -$(DATADIR)/maps.conf: $(DATADIR)/maps.google.com - $(Q)echo "[GOOGLE]" > $(@) - $(Q)echo "google_version:" `grep -P "http://khm[0-9]+.google.com/kh/v=[0-9]+.x26" $(DATADIR)/maps.google.com | sed -E s#.*http://khm[0-9]+.google.com/kh/v=## | sed -E s#.x26.*##` >> $(@) +$(PAPARAZZI_HOME)/conf/maps.xml: $(DATADIR)/maps.google.com + $(Q)echo "\n" > $(@) + $(Q)echo "" >> $(@) $(Q)echo "" >> $(@) +FORCE: diff --git a/sw/airborne/ap_downlink.h b/sw/airborne/ap_downlink.h index 36bb4705d2..d50310508f 100644 --- a/sw/airborne/ap_downlink.h +++ b/sw/airborne/ap_downlink.h @@ -189,10 +189,13 @@ #define PERIODIC_SEND_NAVIGATION(_chan) SEND_NAVIGATION(_chan) + #if defined CAM || defined MOBILE_CAM -#define SEND_CAM(_chan) Downlink({ int16_t x = cam_target_x; int16_t y = cam_target_y; int8_t phi = DegOfRad(cam_phi_c); int8_t theta = DegOfRad(cam_theta_c); DOWNLINK_SEND_CAM(_chan, &phi, &theta, &x, &y);}) +#define SEND_CAM(_chan) Downlink({ int16_t x = cam_target_x; int16_t y = cam_target_y; int16_t phi = DegOfRad(cam_phi_c); int16_t theta = DegOfRad(cam_theta_c); DOWNLINK_SEND_CAM(_chan, &phi, &theta, &x, &y);}) +#define PERIODIC_SEND_CAM_POINT(_chan) DOWNLINK_SEND_CAM_POINT(_chan, &cam_point_distance_from_home, &cam_point_lat, &cam_point_lon) #else #define SEND_CAM(_chan) {} +#define PERIODIC_SEND_CAM_POINT(_chan) {} #endif #define PERIODIC_SEND_DL_VALUE(_chan) PeriodicSendDlValue(_chan) /** generated from the xml settings config in conf/settings */ diff --git a/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h b/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h new file mode 100644 index 0000000000..b25efbcd9a --- /dev/null +++ b/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h @@ -0,0 +1,10 @@ +#ifndef MY_GPIO_ARCH_H +#define MY_GPIO_ARCH_H + + +#define GPIO_ARCH_SET_SPI_CS_HIGH() \ +{ \ +} + + +#endif /* MY_GPIO_ARCH_H */ diff --git a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c index 55d8df8c52..f6017400fc 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c @@ -29,27 +29,151 @@ #include "mcu_periph/uart.h" #include "armVIC.h" +static inline void uart_disable_interrupts(struct uart_periph* p) { + // disable interrups + ((uartRegs_t *)(p->reg_addr))->ier = 0x00; // disable all interrupts + ((uartRegs_t *)(p->reg_addr))->iir; // clear interrupt ID + ((uartRegs_t *)(p->reg_addr))->rbr; // clear receive register + ((uartRegs_t *)(p->reg_addr))->lsr; // clear line status register +} + +static inline void uart_enable_interrupts(struct uart_periph* p) { + // enable receiver interrupts + ((uartRegs_t *)(p->reg_addr))->ier = UIER_ERBFI; +} + +static inline void uart_set_baudrate(struct uart_periph* p, uint32_t baud) { + // set the baudrate + ((uartRegs_t *)(p->reg_addr))->lcr = ULCR_DLAB_ENABLE; // select divisor latches + ((uartRegs_t *)(p->reg_addr))->dll = (uint8_t)baud; // set for baud low byte + ((uartRegs_t *)(p->reg_addr))->dlm = (uint8_t)(baud >> 8); // set for baud high byte + + // set the number of characters and other + // user specified operating parameters + // For now: hard wired configuration 8 bits 1 stop no parity + // fifo triger -> 8 bytes + ((uartRegs_t *)(p->reg_addr))->lcr = (UART_8N1 & ~ULCR_DLAB_ENABLE); + ((uartRegs_t *)(p->reg_addr))->fcr = UART_FIFO_8; +} + +void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { + uart_disable_interrupts(p); + uart_set_baudrate(p, baud); + uart_enable_interrupts(p); +} + +void uart_transmit(struct uart_periph* p, uint8_t data ) { + uint16_t temp; + unsigned cpsr; + + temp = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE; + + if (temp == p->tx_extract_idx) + return; // no room + + cpsr = disableIRQ(); // disable global interrupts + ((uartRegs_t *)(p->reg_addr))->ier &= ~UIER_ETBEI; // disable TX interrupts + restoreIRQ(cpsr); // restore global interrupts + + // check if in process of sending data + if (p->tx_running) { + // add to queue + p->tx_buf[p->tx_insert_idx] = data; + p->tx_insert_idx = temp; + } else { + // set running flag and write to output register + p->tx_running = 1; + ((uartRegs_t *)(p->reg_addr))->thr = data; + } + + cpsr = disableIRQ(); // disable global interrupts + ((uartRegs_t *)(p->reg_addr))->ier |= UIER_ETBEI; // enable TX interrupts + restoreIRQ(cpsr); // restore global interrupts +} + +static inline void uart_ISR(struct uart_periph* p) +{ + uint8_t iid; + + // loop until not more interrupt sources + while (((iid = ((uartRegs_t *)(p->reg_addr))->iir) & UIIR_NO_INT) == 0) + { + // identify & process the highest priority interrupt + switch (iid & UIIR_ID_MASK) + { + case UIIR_RLS_INT: // Receive Line Status + ((uartRegs_t *)(p->reg_addr))->lsr; // read LSR to clear + break; + + case UIIR_CTI_INT: // Character Timeout Indicator + case UIIR_RDA_INT: // Receive Data Available + do + { + uint16_t temp; + + // calc next insert index & store character + temp = (p->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE; + p->rx_buf[p->rx_insert_idx] = ((uartRegs_t *)(p->reg_addr))->rbr; + + // check for more room in queue + if (temp != p->rx_extract_idx) + p->rx_insert_idx = temp; // update insert index + } + while (((uartRegs_t *)(p->reg_addr))->lsr & ULSR_RDR); + + break; + + case UIIR_THRE_INT: // Transmit Holding Register Empty + while (((uartRegs_t *)(p->reg_addr))->lsr & ULSR_THRE) + { + // check if more data to send + if (p->tx_insert_idx != p->tx_extract_idx) + { + ((uartRegs_t *)(p->reg_addr))->thr = p->tx_buf[p->tx_extract_idx]; + p->tx_extract_idx++; + p->tx_extract_idx %= UART_TX_BUFFER_SIZE; + } + else + { + // no + p->tx_running = 0; // clear running flag + break; + } + } + + break; + + default: // Unknown + ((uartRegs_t *)(p->reg_addr))->lsr; + ((uartRegs_t *)(p->reg_addr))->rbr; + break; + } + } +} + #ifdef USE_UART0 #ifndef UART0_VIC_SLOT #define UART0_VIC_SLOT 5 #endif - void uart0_ISR(void) __attribute__((naked)); -uint8_t uart0_rx_buffer[UART0_RX_BUFFER_SIZE]; -uint16_t uart0_rx_insert_idx, uart0_rx_extract_idx; +void uart0_ISR(void) { + // perform proper ISR entry so thumb-interwork works properly + ISR_ENTRY(); -uint8_t uart0_tx_buffer[UART0_TX_BUFFER_SIZE]; -uint16_t uart0_tx_insert_idx, uart0_tx_extract_idx; -uint8_t uart0_tx_running; + uart_ISR(&uart0); -void uart0_init( void ) { - uart0_init_param(UART0_BAUD, UART_8N1, UART_FIFO_8); + VICVectAddr = 0x00000000; // clear this interrupt from the VIC + ISR_EXIT(); // recover registers and return } -void uart0_init_param( uint16_t baud, uint8_t mode, uint8_t fmode) { +void uart0_init( void ) { + + uart_periph_init(&uart0); + uart0.reg_addr = UART0_BASE; + #ifdef USE_UART0_RX_ONLY // only use the RX0 P0.1 pin, no TX PINSEL0 = (PINSEL0 & ~U0_PINMASK_RX) | U0_PINSEL_RX; @@ -58,20 +182,9 @@ void uart0_init_param( uint16_t baud, uint8_t mode, uint8_t fmode) { PINSEL0 = (PINSEL0 & ~U0_PINMASK) | U0_PINSEL; #endif - U0IER = 0x00; // disable all interrupts - U0IIR; // clear interrupt ID - U0RBR; // clear receive register - U0LSR; // clear line status register - - // set the baudrate - U0LCR = ULCR_DLAB_ENABLE; // select divisor latches - U0DLL = (uint8_t)baud; // set for baud low byte - U0DLM = (uint8_t)(baud >> 8); // set for baud high byte - - // set the number of characters and other - // user specified operating parameters - U0LCR = (mode & ~ULCR_DLAB_ENABLE); - U0FCR = fmode; + // initialize uart parameters + uart_disable_interrupts(&uart0); + uart_set_baudrate(&uart0, UART0_BAUD); // initialize the interrupt vector VICIntSelect &= ~VIC_BIT(VIC_UART0); // UART0 selected as IRQ @@ -79,138 +192,11 @@ void uart0_init_param( uint16_t baud, uint8_t mode, uint8_t fmode) { _VIC_CNTL(UART0_VIC_SLOT) = VIC_ENABLE | VIC_UART0; _VIC_ADDR(UART0_VIC_SLOT) = (uint32_t)uart0_ISR; // address of the ISR - // initialize the transmit data queue - uart0_tx_extract_idx = 0; - uart0_tx_insert_idx = 0; - uart0_tx_running = 0; - - // initialize the receive data queue - uart0_rx_extract_idx = 0; - uart0_rx_insert_idx = 0; - - // enable receiver interrupts - U0IER = UIER_ERBFI; -} - -bool_t uart0_check_free_space( uint8_t len) { - int16_t space = uart0_tx_extract_idx - uart0_tx_insert_idx; - if (space <= 0) - space += UART0_TX_BUFFER_SIZE; - - return (uint16_t)(space - 1) >= len; -} - -void uart0_transmit( unsigned char data ) { - uint16_t temp; - unsigned cpsr; - - temp = (uart0_tx_insert_idx + 1) % UART0_TX_BUFFER_SIZE; - - if (temp == uart0_tx_extract_idx) - // return -1; // no room - return; // no room - - cpsr = disableIRQ(); // disable global interrupts - U0IER &= ~UIER_ETBEI; // disable TX interrupts - restoreIRQ(cpsr); // restore global interrupts - - // check if in process of sending data - if (uart0_tx_running) - { - // add to queue - uart0_tx_buffer[uart0_tx_insert_idx] = (uint8_t)data; - uart0_tx_insert_idx = temp; - } - else - { - // set running flag and write to output register - uart0_tx_running = 1; - U0THR = (uint8_t)data; - } - - cpsr = disableIRQ(); // disable global interrupts - U0IER |= UIER_ETBEI; // enable TX interrupts - restoreIRQ(cpsr); // restore global interrupts - // return (uint8_t)ch; -} - - -void uart0_ISR(void) -{ - uint8_t iid; - - // perform proper ISR entry so thumb-interwork works properly - ISR_ENTRY(); - - // loop until not more interrupt sources - while (((iid = U0IIR) & UIIR_NO_INT) == 0) - { - // identify & process the highest priority interrupt - switch (iid & UIIR_ID_MASK) - { - case UIIR_RLS_INT: // Receive Line Status - U0LSR; // read LSR to clear - break; - - case UIIR_CTI_INT: // Character Timeout Indicator - case UIIR_RDA_INT: // Receive Data Available - do - { - uint16_t temp; - - // calc next insert index & store character - temp = (uart0_rx_insert_idx + 1) % UART0_RX_BUFFER_SIZE; - uart0_rx_buffer[uart0_rx_insert_idx] = U0RBR; - - // check for more room in queue - if (temp != uart0_rx_extract_idx) - uart0_rx_insert_idx = temp; // update insert index - } - while (U0LSR & ULSR_RDR); - - break; - - case UIIR_THRE_INT: // Transmit Holding Register Empty - while (U0LSR & ULSR_THRE) - { - // check if more data to send - if (uart0_tx_insert_idx != uart0_tx_extract_idx) - { - U0THR = uart0_tx_buffer[uart0_tx_extract_idx]; - uart0_tx_extract_idx++; - uart0_tx_extract_idx %= UART0_TX_BUFFER_SIZE; - } - else - { - // no - uart0_tx_running = 0; // clear running flag - break; - } - } - - break; - - default: // Unknown - U0LSR; - U0RBR; - break; - } - } - - VICVectAddr = 0x00000000; // clear this interrupt from the VIC - ISR_EXIT(); // recover registers and return + uart_enable_interrupts(&uart0); } #endif /* USE_UART0 */ -/* - * - * UART1 handling functions - those are pale copies of UART0 ones - * We should probably find a better way to make the code configurable - * for both uarts - * - */ - #ifdef USE_UART1 #ifndef UART1_VIC_SLOT @@ -219,27 +205,21 @@ void uart0_ISR(void) void uart1_ISR(void) __attribute__((naked)); -uint8_t uart1_rx_buffer[UART1_RX_BUFFER_SIZE]; -uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx; +void uart1_ISR(void) { + // perform proper ISR entry so thumb-interwork works properly + ISR_ENTRY(); -uint8_t uart1_tx_buffer[UART1_TX_BUFFER_SIZE]; -uint16_t uart1_tx_insert_idx, uart1_tx_extract_idx; -uint8_t uart1_tx_running; + uart_ISR(&uart1); + + VICVectAddr = 0x00000000; // clear this interrupt from the VIC + ISR_EXIT(); // recover registers and return +} void uart1_init( void ) { - uart1_init_param(UART1_BAUD, UART_8N1, UART_FIFO_8); -} -bool_t uart1_check_free_space( uint8_t len) { - int16_t space = uart1_tx_extract_idx - uart1_tx_insert_idx; - if (space <= 0) - space += UART1_TX_BUFFER_SIZE; + uart_periph_init(&uart1); + uart1.reg_addr = UART1_BASE; - return (uint16_t)(space - 1) >= len; -} - - -void uart1_init_param( uint16_t baud, uint8_t mode, uint8_t fmode) { #ifdef USE_UART1_RX_ONLY // only use the RX1 P0.9 pin, no TX PINSEL0 = (PINSEL0 & ~U1_PINMASK_RX) | U1_PINSEL_RX; @@ -248,20 +228,8 @@ void uart1_init_param( uint16_t baud, uint8_t mode, uint8_t fmode) { PINSEL0 = (PINSEL0 & ~U1_PINMASK) | U1_PINSEL; #endif - U1IER = 0x00; // disable all interrupts - U1IIR; // clear interrupt ID - U1RBR; // clear receive register - U1LSR; // clear line status register - - // set the baudrate - U1LCR = ULCR_DLAB_ENABLE; // select divisor latches - U1DLL = (uint8_t)baud; // set for baud low byte - U1DLM = (uint8_t)(baud >> 8); // set for baud high byte - - // set the number of characters and other - // user specified operating parameters - U1LCR = (mode & ~ULCR_DLAB_ENABLE); - U1FCR = fmode; + uart_disable_interrupts(&uart1); + uart_set_baudrate(&uart1, UART1_BAUD); // initialize the interrupt vector VICIntSelect &= ~VIC_BIT(VIC_UART1); // UART1 selected as IRQ @@ -269,122 +237,9 @@ void uart1_init_param( uint16_t baud, uint8_t mode, uint8_t fmode) { _VIC_CNTL(UART1_VIC_SLOT) = VIC_ENABLE | VIC_UART1; _VIC_ADDR(UART1_VIC_SLOT) = (uint32_t)uart1_ISR; // address of the ISR - // initialize the transmit data queue - uart1_tx_extract_idx = 0; - uart1_tx_insert_idx = 0; - uart1_tx_running = 0; - - // initialize the receive data queue - uart1_rx_extract_idx = 0; - uart1_rx_insert_idx = 0; - // enable receiver interrupts - U1IER = UIER_ERBFI; + uart_enable_interrupts(&uart1); } +#endif -void uart1_transmit( unsigned char data ) { - uint16_t temp; - unsigned cpsr; - - temp = (uart1_tx_insert_idx + 1) % UART1_TX_BUFFER_SIZE; - - if (temp == uart1_tx_extract_idx) - // return -1; // no room - return; // no room - - cpsr = disableIRQ(); // disable global interrupts - U1IER &= ~UIER_ETBEI; // disable TX interrupts - restoreIRQ(cpsr); // restore global interrupts - - // check if in process of sending data - if (uart1_tx_running) - { - // add to queue - uart1_tx_buffer[uart1_tx_insert_idx] = (uint8_t)data; - uart1_tx_insert_idx = temp; - } - else - { - // set running flag and write to output register - uart1_tx_running = 1; - U1THR = (uint8_t)data; - } - - cpsr = disableIRQ(); // disable global interrupts - U1IER |= UIER_ETBEI; // enable TX interrupts - restoreIRQ(cpsr); // restore global interrupts -} - - -void uart1_ISR(void) -{ - uint8_t iid; - - // perform proper ISR entry so thumb-interwork works properly - ISR_ENTRY(); - - // loop until not more interrupt sources - while (((iid = U1IIR) & UIIR_NO_INT) == 0) - { - // identify & process the highest priority interrupt - switch (iid & UIIR_ID_MASK) - { - case UIIR_RLS_INT: // Receive Line Status - U1LSR; // read LSR to clear - break; - - case UIIR_CTI_INT: // Character Timeout Indicator - case UIIR_RDA_INT: // Receive Data Available - do - { - uint16_t temp; - // calc next insert index & store character - temp = (uart1_rx_insert_idx + 1) % UART1_RX_BUFFER_SIZE; - uart1_rx_buffer[uart1_rx_insert_idx] = U1RBR; - - // check for more room in queue - if (temp != uart1_rx_extract_idx) - uart1_rx_insert_idx = temp; // update insert index - } - while (U1LSR & ULSR_RDR); - - break; - - case UIIR_THRE_INT: // Transmit Holding Register Empty - while (U1LSR & ULSR_THRE) - { - // check if more data to send - if (uart1_tx_insert_idx != uart1_tx_extract_idx) - { - U1THR = uart1_tx_buffer[uart1_tx_extract_idx]; - uart1_tx_extract_idx++; - uart1_tx_extract_idx %= UART1_TX_BUFFER_SIZE; - } - else - { - // no - uart1_tx_running = 0; // clear running flag - break; - } - } - - break; - - case UIIR_MS_INT: // MODEM Status - U1MSR; // read MSR to clear - break; - - default: // Unknown - U1LSR; - U1RBR; - U1MSR; - break; - } - } - - VICVectAddr = 0x00000000; // clear this interrupt from the VIC - ISR_EXIT(); // recover registers and return -} - -#endif /* USE_UART1 */ diff --git a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h index fbc1c6c991..40cd39250b 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h +++ b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h @@ -29,11 +29,6 @@ #include "LPC21xx.h" #include BOARD_CONFIG -#define UART0_RX_BUFFER_SIZE 128 // UART0 receive buffer size -#define UART0_TX_BUFFER_SIZE 128 // UART0 transmit buffer size -#define UART1_RX_BUFFER_SIZE 128 // UART1 receive buffer size -#define UART1_TX_BUFFER_SIZE 128 // UART1 transmit buffer size - #define UART_BAUD(baud) (uint16_t)((PCLK / ((baud) * 16.0)) + 0.5) #define B1200 UART_BAUD(1200) @@ -64,33 +59,4 @@ #define UART_FIFO_8 (uint8_t)(UFCR_FIFO_ENABLE + UFCR_FIFO_TRIG8) #define UART_FIFO_14 (uint8_t)(UFCR_FIFO_ENABLE + UFCR_FIFO_TRIG14) - -extern uint16_t uart0_rx_insert_idx, uart0_rx_extract_idx; -extern uint8_t uart0_rx_buffer[UART0_RX_BUFFER_SIZE]; - -#define Uart0ChAvailable() (uart0_rx_insert_idx != uart0_rx_extract_idx) - -#define Uart0Getch() ({\ - uint8_t ret = uart0_rx_buffer[uart0_rx_extract_idx]; \ - uart0_rx_extract_idx = (uart0_rx_extract_idx + 1)%UART0_RX_BUFFER_SIZE; \ - ret; \ -}) - - -extern uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx; -extern uint8_t uart1_rx_buffer[UART1_RX_BUFFER_SIZE]; -extern void uart1_init_param( uint16_t baud, uint8_t mode, uint8_t fmode); -extern void uart0_init_param( uint16_t baud, uint8_t mode, uint8_t fmode); - -#define Uart1ChAvailable() (uart1_rx_insert_idx != uart1_rx_extract_idx) - -#define Uart1Getch() ({\ - uint8_t ret = uart1_rx_buffer[uart1_rx_extract_idx]; \ - uart1_rx_extract_idx = (uart1_rx_extract_idx + 1)%UART1_RX_BUFFER_SIZE; \ - ret; \ -}) - -extern uint8_t uart0_tx_running; -extern uint8_t uart1_tx_running; - #endif /* LPC21_UART_ARCH_H */ diff --git a/sw/airborne/arch/lpc21/subsystems/settings_arch.c b/sw/airborne/arch/lpc21/subsystems/settings_arch.c index f8763b3147..ea6b285355 100644 --- a/sw/airborne/arch/lpc21/subsystems/settings_arch.c +++ b/sw/airborne/arch/lpc21/subsystems/settings_arch.c @@ -146,7 +146,7 @@ static int32_t pflash_erase_page(FlashInfo* flash) { iap_entry(command, result); enableIRQ(); if (result[0] != 0) return result[0]; - + /* erase page/sector */ command[0] = IAP_ERASE_SECTORS; command[1] = flash->page_nr; @@ -162,7 +162,7 @@ static int32_t pflash_erase_page(FlashInfo* flash) { command[2] = flash->page_nr; iap_entry(command, result); if (result[0] != 0) return result[0]; - + return 0; } @@ -173,7 +173,7 @@ static int32_t pflash_program_array(FlashInfo* flash, IAP iap_entry; iap_entry = (IAP) IAP_LOCATION; - + /* prepare page/sector */ command[0] = IAP_PREPARE_SECTORS; command[1] = flash->page_nr; @@ -182,7 +182,7 @@ static int32_t pflash_program_array(FlashInfo* flash, iap_entry(command, result); enableIRQ(); if (result[0] != 0) return result[0]; - + /* flash from ram */ command[0] = IAP_COPY_RAM_TO_FLASH; command[1] = dest; @@ -193,7 +193,7 @@ static int32_t pflash_program_array(FlashInfo* flash, iap_entry(command, result); enableIRQ(); if (result[0] != 0) return result[0]; - + return 0; } @@ -273,4 +273,3 @@ int32_t persistent_read(uint32_t ptr, uint32_t size) { return 0; } - diff --git a/sw/airborne/arch/lpc21/usb_tunnel.c b/sw/airborne/arch/lpc21/usb_tunnel.c index aeef32b1dc..c2acef1e61 100644 --- a/sw/airborne/arch/lpc21/usb_tunnel.c +++ b/sw/airborne/arch/lpc21/usb_tunnel.c @@ -71,7 +71,7 @@ int main( void ) { LED_ON(2); tx_time = T0TC; inc = VCOM_getchar(); - uart0_transmit(inc); + Uart0Transmit(inc); } } #else @@ -88,7 +88,7 @@ int main( void ) { LED_ON(2); tx_time = T0TC; inc = VCOM_getchar(); - uart1_transmit(inc); + Uart1Transmit(inc); } } #endif diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.c b/sw/airborne/arch/omap/mcu_periph/uart_arch.c new file mode 100644 index 0000000000..ff5f49445e --- /dev/null +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.c @@ -0,0 +1,130 @@ +/* + * Paparazzi $Id$ + * + * Copyright (C) 2009 Antoine Drouin + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "mcu_periph/uart.h" + +#include +#include +#include +#include +#include + +#include "fms/fms_serial_port.h" + + +void uart_periph_set_baudrate(struct uart_periph* p, uint16_t baud) { + struct FmsSerialPort* fmssp; + // close serial port if already open + if (p->reg_addr != NULL) { + fmssp = (struct FmsSerialPort*)(p->reg_addr); + serial_port_close(fmssp); + serial_port_free(fmssp); + } + // open serial port + fmssp = serial_port_new(); + // use register address to store SerialPort structure pointer... + p->reg_addr = (void*)fmssp; + + //TODO: set device name in application and pass as argument + printf("opening %s on uart0 at %d\n",p->dev,baud); + serial_port_open_raw(fmssp,p->dev,baud); +} + +void uart_transmit(struct uart_periph* p, uint8_t data ) { + uint16_t temp = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE; + + if (temp == p->tx_extract_idx) + return; // no room + + // check if in process of sending data + if (p->tx_running) { // yes, add to queue + p->tx_buf[p->tx_insert_idx] = data; + p->tx_insert_idx = temp; + } + else { // no, set running flag and write to output register + p->tx_running = TRUE; + struct FmsSerialPort* fmssp = (struct FmsSerialPort*)(p->reg_addr); + write((int)(fmssp->fd),&data,1); + //printf("w %x\n",data); + } +} + +static inline void uart_handler(struct uart_periph* p) { + unsigned char c='D'; + + if (p->reg_addr == NULL) return; // device not initialized ? + + struct FmsSerialPort* fmssp = (struct FmsSerialPort*)(p->reg_addr); + int fd = fmssp->fd; + + // check if more data to send + if (p->tx_insert_idx != p->tx_extract_idx) { + write(fd,&(p->tx_buf[p->tx_extract_idx]),1); + //printf("w %x\n",p->tx_buf[p->tx_extract_idx]); + p->tx_extract_idx++; + p->tx_extract_idx %= UART_TX_BUFFER_SIZE; + } + else { + p->tx_running = FALSE; // clear running flag + } + + if(read(fd,&c,1) > 0){ + //printf("r %x %c\n",c,c); + uint16_t temp = (p->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE; + p->rx_buf[p->rx_insert_idx] = c; + // check for more room in queue + if (temp != p->rx_extract_idx) + p->rx_insert_idx = temp; // update insert index + } + +} + +#ifdef USE_UART0 + +void uart0_init( void ) { + uart_periph_init(&uart0); + uart.dev = UART0_DEV; + uart_periph_set_baudrate(&uart0,UART0_BAUD); +} + + +void uart0_handler(void) { + uart_handler(&uart0); +} + +#endif /* USE_UART0 */ + +#ifdef USE_UART1 + +void uart1_init( void ) { + uart_periph_init(&uart1); + uart.dev = UART1_DEV; + uart_periph_init_param(&uart1,UART1_BAUD); +} + +void uart1_handler(void) { + uart_handler(&uart1); +} + +#endif /* USE_UART1 */ + diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.h b/sw/airborne/arch/omap/mcu_periph/uart_arch.h new file mode 100644 index 0000000000..b3845bf8d0 --- /dev/null +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.h @@ -0,0 +1,70 @@ +/* + * $Id$ + * + * Copyright (C) 2009 Antoine Drouin + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef UART_ARCH_H +#define UART_ARCH_H + +#include "std.h" +//coment to avoid redefinition +/*#define B9600 9600 +#define B38400 38400 + #define B57600 57600 +#define B115200 115200 +*/ + +//junk for gps_configure_uart in gps_ubx.c to compile +#define UART_BAUD(baud) (baud) + + +#define Uart1_init uart1_init() +#define Uart2_init uart2_init() +#define Uart3_init uart3_init() +#define Uart5_init uart5_init() + +#define UART1_irq_handler usart1_irq_handler +#define UART2_irq_handler usart2_irq_handler +#define UART3_irq_handler usart3_irq_handler +#define UART5_irq_handler usart5_irq_handler + +#if defined USE_UART0 || OVERRIDE_UART0_IRQ_HANDLER +extern void uart0_handler(void); +#endif + +#ifdef USE_UART0 + +void uart0_init( void ); + +#endif /* USE_UART0 */ + + +#if defined USE_UART1 || OVERRIDE_UART1_IRQ_HANDLER +extern void uart1_handler(void); +#endif + +#ifdef USE_UART1 + +void uart1_init( void ); + +#endif /* USE_UART1 */ + +#endif /* UART_ARCH_H */ diff --git a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c index e486ebbc38..e680ebc675 100644 --- a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c +++ b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c @@ -35,6 +35,7 @@ void imu_periodic(void) { } +#ifdef USE_NPS #include "nps_sensors.h" void imu_feed_gyro_accel(void) { @@ -61,3 +62,4 @@ void imu_feed_mag(void) { ami601_status = AMI601_DATA_AVAILABLE; #endif } +#endif //USE_NPS diff --git a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h index 8ef38139af..025acd33bf 100644 --- a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h +++ b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h @@ -31,8 +31,9 @@ extern int imu_overrun; +#ifdef USE_NPS extern void imu_feed_gyro_accel(void); extern void imu_feed_mag(void); - +#endif #endif /* IMU_B2_HW_H */ diff --git a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c index de1a37d3d7..be462fc82b 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c +++ b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c @@ -28,7 +28,7 @@ #include #include -#ifdef NPS +#ifdef USE_NPS #include "nps_radio_control.h" #endif @@ -55,7 +55,7 @@ value send_ppm(value unit) { return unit; } -#ifdef NPS +#ifdef USE_NPS #define PPM_OF_NPS(_nps, _neutral, _min, _max) \ ((_nps) >= 0 ? (_neutral) + (_nps) * ((_max)-(_neutral)) : (_neutral) + (_nps) * ((_neutral)- (_min))) @@ -94,7 +94,7 @@ value send_ppm(value unit) { return unit; } -#ifdef NPS +#ifdef USE_NPS void radio_control_feed(void) {} #endif diff --git a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h index 5f9bfd681d..c0f27a3b5e 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h +++ b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h @@ -36,7 +36,7 @@ #define PPM_NB_CHANNEL RADIO_CONTROL_NB_CHANNEL -#ifdef NPS +#ifdef USE_NPS extern void radio_control_feed(void); #endif diff --git a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h new file mode 100644 index 0000000000..8fb35263c6 --- /dev/null +++ b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h @@ -0,0 +1,21 @@ +#ifndef MY_GPIO_ARCH_H +#define MY_GPIO_ARCH_H + +#include +#include + +#define GPIO_ARCH_SET_SPI_CS_HIGH() \ +{ \ + GPIO_InitTypeDef GPIO_InitStructure; \ + /* initialise peripheral clock for port B */ \ + RCC_APB2PeriphClockCmd( RCC_APB2Periph_GPIOB, ENABLE); \ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; \ + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; \ + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; \ + GPIO_Init(GPIOB, &GPIO_InitStructure); \ + /* set port B pin 12 to be high */ \ + GPIO_WriteBit(GPIOB, GPIO_Pin_12 , Bit_SET ); \ +} + + +#endif /* MY_GPIO_ARCH_H */ diff --git a/sw/airborne/arch/stm32/mcu_periph/uart_arch.c b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c index e0406d9c85..f9fd7a430b 100644 --- a/sw/airborne/arch/stm32/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c @@ -30,28 +30,99 @@ #include "std.h" #include "pprz_baudrate.h" +void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { + + /* Configure USART */ + USART_InitTypeDef usart; + usart.USART_BaudRate = baud; + usart.USART_WordLength = USART_WordLength_8b; + usart.USART_StopBits = USART_StopBits_1; + usart.USART_Parity = USART_Parity_No; + usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + usart.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_Init(p->reg_addr, &usart); + /* Enable USART1 Receive interrupts */ + USART_ITConfig(p->reg_addr, USART_IT_RXNE, ENABLE); + + pprz_usart_set_baudrate(p->reg_addr, baud); + + /* Enable the USART */ + USART_Cmd(p->reg_addr, ENABLE); + +} +// TODO set_mode function + +void uart_transmit(struct uart_periph* p, uint8_t data ) { + + uint16_t temp = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE; + + if (temp == p->tx_extract_idx) + return; // no room + + USART_ITConfig(p->reg_addr, USART_IT_TXE, DISABLE); + + // check if in process of sending data + if (p->tx_running) { // yes, add to queue + p->tx_buf[p->tx_insert_idx] = data; + p->tx_insert_idx = temp; + } + else { // no, set running flag and write to output register + p->tx_running = TRUE; + USART_SendData(p->reg_addr, data); + } + + USART_ITConfig(p->reg_addr, USART_IT_TXE, ENABLE); + +} + +static inline void usart_irq_handler(struct uart_periph* p) { + + if(USART_GetITStatus(p->reg_addr, USART_IT_TXE) != RESET){ + // check if more data to send + if (p->tx_insert_idx != p->tx_extract_idx) { + USART_SendData(p->reg_addr,p->tx_buf[p->tx_extract_idx]); + p->tx_extract_idx++; + p->tx_extract_idx %= UART_TX_BUFFER_SIZE; + } + else { + p->tx_running = FALSE; // clear running flag + USART_ITConfig(p->reg_addr, USART_IT_TXE, DISABLE); + } + } + + if(USART_GetITStatus(p->reg_addr, USART_IT_RXNE) != RESET){ + uint16_t temp = (p->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE;; + p->rx_buf[p->rx_insert_idx] = USART_ReceiveData(p->reg_addr); + // check for more room in queue + if (temp != p->rx_extract_idx) + p->rx_insert_idx = temp; // update insert index + } + +} + +static inline void usart_enable_irq(IRQn_Type IRQn) { + /* Enable USART interrupts */ + NVIC_InitTypeDef nvic; + nvic.NVIC_IRQChannel = IRQn; + nvic.NVIC_IRQChannelPreemptionPriority = 2; + nvic.NVIC_IRQChannelSubPriority = 1; + nvic.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&nvic); +} + #ifdef USE_UART1 -volatile uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx; -uint8_t uart1_rx_buffer[UART1_RX_BUFFER_SIZE]; - -volatile uint16_t uart1_tx_insert_idx, uart1_tx_extract_idx; -volatile bool_t uart1_tx_running; -uint8_t uart1_tx_buffer[UART1_TX_BUFFER_SIZE]; - - void uart1_init( void ) { + + uart_periph_init(&uart1); + uart1.reg_addr = USART1; + /* init RCC */ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); RCC_APB2PeriphClockCmd(UART1_Periph, ENABLE); /* Enable USART1 interrupts */ - NVIC_InitTypeDef nvic; - nvic.NVIC_IRQChannel = USART1_IRQn; - nvic.NVIC_IRQChannelPreemptionPriority = 2; - nvic.NVIC_IRQChannelSubPriority = 1; - nvic.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&nvic); + usart_enable_irq(USART1_IRQn); /* Init GPIOS */ GPIO_InitTypeDef gpio; @@ -66,119 +137,26 @@ void uart1_init( void ) { GPIO_Init(UART1_RxPort, &gpio); /* Configure USART1 */ - USART_InitTypeDef usart; - usart.USART_BaudRate = UART1_BAUD; - usart.USART_WordLength = USART_WordLength_8b; - usart.USART_StopBits = USART_StopBits_1; - usart.USART_Parity = USART_Parity_No; - usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None; - usart.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - USART_Init(USART1, &usart); - /* Enable USART1 Receive interrupts */ - USART_ITConfig(USART1, USART_IT_RXNE, ENABLE); - - pprz_usart_set_baudrate(USART1, UART1_BAUD); - - /* Enable the USART1 */ - USART_Cmd(USART1, ENABLE); - - // initialize the transmit data queue - uart1_tx_extract_idx = 0; - uart1_tx_insert_idx = 0; - uart1_tx_running = FALSE; - - // initialize the receive data queue - uart1_rx_extract_idx = 0; - uart1_rx_insert_idx = 0; - -} - -void uart1_transmit( uint8_t data ) { - - uint16_t temp = (uart1_tx_insert_idx + 1) % UART1_TX_BUFFER_SIZE; - - if (temp == uart1_tx_extract_idx) - return; // no room - - USART_ITConfig(USART1, USART_IT_TXE, DISABLE); - - // check if in process of sending data - if (uart1_tx_running) { // yes, add to queue - uart1_tx_buffer[uart1_tx_insert_idx] = data; - uart1_tx_insert_idx = temp; - } - else { // no, set running flag and write to output register - uart1_tx_running = TRUE; - USART_SendData(USART1, data); - } - - USART_ITConfig(USART1, USART_IT_TXE, ENABLE); - -} - -bool_t uart1_check_free_space( uint8_t len) { - int16_t space = uart1_tx_extract_idx - uart1_tx_insert_idx; - if (space <= 0) - space += UART1_TX_BUFFER_SIZE; - return (uint16_t)(space - 1) >= len; -} - -void usart1_irq_handler(void) { - - if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET){ - // check if more data to send - if (uart1_tx_insert_idx != uart1_tx_extract_idx) { - USART_SendData(USART1,uart1_tx_buffer[uart1_tx_extract_idx]); - uart1_tx_extract_idx++; - uart1_tx_extract_idx %= UART1_TX_BUFFER_SIZE; - } - else { - uart1_tx_running = FALSE; // clear running flag - USART_ITConfig(USART1, USART_IT_TXE, DISABLE); - } - } - - if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET){ - uint16_t temp = (uart1_rx_insert_idx + 1) % UART1_RX_BUFFER_SIZE;; - uart1_rx_buffer[uart1_rx_insert_idx] = USART_ReceiveData(USART1); - // check for more room in queue - if (temp != uart1_rx_extract_idx) - uart1_rx_insert_idx = temp; // update insert index - } - + uart_periph_set_baudrate(&uart1, UART1_BAUD); } +void usart1_irq_handler(void) { usart_irq_handler(&uart1); } #endif /* USE_UART1 */ - - - - - - #ifdef USE_UART2 -volatile uint16_t uart2_rx_insert_idx, uart2_rx_extract_idx; -uint8_t uart2_rx_buffer[UART2_RX_BUFFER_SIZE]; - -volatile uint16_t uart2_tx_insert_idx, uart2_tx_extract_idx; -volatile bool_t uart2_tx_running; -uint8_t uart2_tx_buffer[UART2_TX_BUFFER_SIZE]; - - void uart2_init( void ) { + + uart_periph_init(&uart2); + uart2.reg_addr = USART2; + /* init RCC */ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); RCC_APB2PeriphClockCmd(UART2_Periph, ENABLE); /* Enable USART2 interrupts */ - NVIC_InitTypeDef nvic; - nvic.NVIC_IRQChannel = USART2_IRQn; - nvic.NVIC_IRQChannelPreemptionPriority = 2; - nvic.NVIC_IRQChannelSubPriority = 1; - nvic.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&nvic); + usart_enable_irq(USART2_IRQn); /* Init GPIOS */ GPIO_InitTypeDef gpio; @@ -193,118 +171,27 @@ void uart2_init( void ) { GPIO_Init(UART2_RxPort, &gpio); /* Configure USART2 */ - USART_InitTypeDef usart; - usart.USART_BaudRate = UART2_BAUD; - usart.USART_WordLength = USART_WordLength_8b; - usart.USART_StopBits = USART_StopBits_1; - usart.USART_Parity = USART_Parity_No; - usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None; - usart.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - USART_Init(USART2, &usart); - /* Enable USART2 Receive interrupts */ - USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); - - pprz_usart_set_baudrate(USART2, UART2_BAUD); - - /* Enable the USART2 */ - USART_Cmd(USART2, ENABLE); - - // initialize the transmit data queue - uart2_tx_extract_idx = 0; - uart2_tx_insert_idx = 0; - uart2_tx_running = FALSE; - - // initialize the receive data queue - uart2_rx_extract_idx = 0; - uart2_rx_insert_idx = 0; - -} - -void uart2_transmit( uint8_t data ) { - - uint16_t temp = (uart2_tx_insert_idx + 1) % UART2_TX_BUFFER_SIZE; - - if (temp == uart2_tx_extract_idx) - return; // no room - - USART_ITConfig(USART2, USART_IT_TXE, DISABLE); - - // check if in process of sending data - if (uart2_tx_running) { // yes, add to queue - uart2_tx_buffer[uart2_tx_insert_idx] = data; - uart2_tx_insert_idx = temp; - } - else { // no, set running flag and write to output register - uart2_tx_running = TRUE; - USART_SendData(USART2, data); - } - - USART_ITConfig(USART2, USART_IT_TXE, ENABLE); - -} - -bool_t uart2_check_free_space( uint8_t len) { - int16_t space = uart2_tx_extract_idx - uart2_tx_insert_idx; - if (space <= 0) - space += UART2_TX_BUFFER_SIZE; - return (uint16_t)(space - 1) >= len; -} - -void usart2_irq_handler(void) { - if(USART_GetITStatus(USART2, USART_IT_TXE) != RESET){ - // check if more data to send - if (uart2_tx_insert_idx != uart2_tx_extract_idx) { - USART_SendData(USART2,uart2_tx_buffer[uart2_tx_extract_idx]); - uart2_tx_extract_idx++; - uart2_tx_extract_idx %= UART2_TX_BUFFER_SIZE; - } - else { - uart2_tx_running = FALSE; // clear running flag - USART_ITConfig(USART2, USART_IT_TXE, DISABLE); - } - } - - if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET){ - uint16_t temp = (uart2_rx_insert_idx + 1) % UART2_RX_BUFFER_SIZE;; - uart2_rx_buffer[uart2_rx_insert_idx] = USART_ReceiveData(USART2); - // check for more room in queue - if (temp != uart2_rx_extract_idx) - uart2_rx_insert_idx = temp; // update insert index - } - + uart_periph_set_baudrate(&uart2, UART2_BAUD); } +void usart2_irq_handler(void) { usart_irq_handler(&uart2); } #endif /* USE_UART2 */ - - - - - #ifdef USE_UART3 -volatile uint16_t uart3_rx_insert_idx, uart3_rx_extract_idx; -uint8_t uart3_rx_buffer[UART3_RX_BUFFER_SIZE]; - -volatile uint16_t uart3_tx_insert_idx, uart3_tx_extract_idx; -volatile bool_t uart3_tx_running; -uint8_t uart3_tx_buffer[UART3_TX_BUFFER_SIZE]; - void uart3_init( void ) { + uart_periph_init(&uart3); + uart3.reg_addr = USART3; + /* init RCC */ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); RCC_APB2PeriphClockCmd(UART3_Periph, ENABLE); /* Enable USART3 interrupts */ - NVIC_InitTypeDef nvic; - nvic.NVIC_IRQChannel = USART3_IRQn; - nvic.NVIC_IRQChannelPreemptionPriority = 2; - nvic.NVIC_IRQChannelSubPriority = 1; - nvic.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&nvic); + usart_enable_irq(USART3_IRQn); /* Init GPIOS */ GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE); @@ -320,114 +207,27 @@ void uart3_init( void ) { GPIO_Init(UART3_RxPort, &gpio); /* Configure USART3 */ - USART_InitTypeDef usart; - usart.USART_BaudRate = UART3_BAUD; - usart.USART_WordLength = USART_WordLength_8b; - usart.USART_StopBits = USART_StopBits_1; - usart.USART_Parity = USART_Parity_No; - usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None; - usart.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - USART_Init(USART3, &usart); - /* Enable USART3 Receive interrupts */ - USART_ITConfig(USART3, USART_IT_RXNE, ENABLE); - - pprz_usart_set_baudrate(USART3, UART3_BAUD); - - /* Enable the USART3 */ - USART_Cmd(USART3, ENABLE); - - // initialize the transmit data queue - uart3_tx_extract_idx = 0; - uart3_tx_insert_idx = 0; - uart3_tx_running = FALSE; - - // initialize the receive data queuenn - uart3_rx_extract_idx = 0; - uart3_rx_insert_idx = 0; - -} - -void uart3_transmit( uint8_t data ) { - - uint16_t temp = (uart3_tx_insert_idx + 1) % UART3_TX_BUFFER_SIZE; - - if (temp == uart3_tx_extract_idx) - return; // no room - - USART_ITConfig(USART3, USART_IT_TXE, DISABLE); - - // check if in process of sending data - if (uart3_tx_running) { // yes, add to queue - uart3_tx_buffer[uart3_tx_insert_idx] = data; - uart3_tx_insert_idx = temp; - } - else { // no, set running flag and write to output register - uart3_tx_running = TRUE; - USART_SendData(USART3, data); - } - USART_ITConfig(USART3, USART_IT_TXE, ENABLE); - -} - -bool_t uart3_check_free_space( uint8_t len) { - int16_t space = uart3_tx_extract_idx - uart3_tx_insert_idx; - if (space <= 0) - space += UART3_TX_BUFFER_SIZE; - return (uint16_t)(space - 1) >= len; -} - - -void usart3_irq_handler(void) { - - if(USART_GetITStatus(USART3, USART_IT_TXE) != RESET){ - // check if more data to send - if (uart3_tx_insert_idx != uart3_tx_extract_idx) { - USART_SendData(USART3,uart3_tx_buffer[uart3_tx_extract_idx]); - uart3_tx_extract_idx++; - uart3_tx_extract_idx %= UART3_TX_BUFFER_SIZE; - } - else { - uart3_tx_running = FALSE; // clear running flag - USART_ITConfig(USART3, USART_IT_TXE, DISABLE); - } - } - - if(USART_GetITStatus(USART3, USART_IT_RXNE) != RESET){ - uint16_t temp = (uart3_rx_insert_idx + 1) % UART3_RX_BUFFER_SIZE;; - uart3_rx_buffer[uart3_rx_insert_idx] = USART_ReceiveData(USART3); - // check for more room in queue - if (temp != uart3_rx_extract_idx) - uart3_rx_insert_idx = temp; // update insert index - } - + uart_periph_set_baudrate(&uart3, UART3_BAUD); } +void usart3_irq_handler(void) { usart_irq_handler(&uart3); } #endif /* USE_UART3 */ #ifdef USE_UART5 -volatile uint16_t uart5_rx_insert_idx, uart5_rx_extract_idx; -uint8_t uart5_rx_buffer[UART5_RX_BUFFER_SIZE]; - -volatile uint16_t uart5_tx_insert_idx, uart5_tx_extract_idx; -volatile bool_t uart5_tx_running; -uint8_t uart5_tx_buffer[UART5_TX_BUFFER_SIZE]; - void uart5_init( void ) { + uart_periph_init(&uart5); + uart5.reg_addr = USART5; + /* init RCC */ RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE); RCC_APB2PeriphClockCmd(UART5_PeriphTx, ENABLE); RCC_APB2PeriphClockCmd(UART5_PeriphRx, ENABLE); /* Enable UART5 interrupts */ - NVIC_InitTypeDef nvic; - nvic.NVIC_IRQChannel = UART5_IRQn; - nvic.NVIC_IRQChannelPreemptionPriority = 2; - nvic.NVIC_IRQChannelSubPriority = 1; - nvic.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&nvic); + usart_enable_irq(USART5_IRQn); /* Init GPIOS */ GPIO_InitTypeDef gpio; @@ -442,105 +242,10 @@ void uart5_init( void ) { GPIO_Init(UART5_RxPort, &gpio); /* Configure UART5 */ - USART_InitTypeDef usart; - usart.USART_BaudRate = UART5_BAUD; - usart.USART_WordLength = USART_WordLength_8b; - usart.USART_StopBits = USART_StopBits_1; - usart.USART_Parity = USART_Parity_No; - usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None; - usart.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - USART_Init(USART5, &usart); - /* Enable UART5 Receive interrupts */ - USART_ITConfig(UART5, USART_IT_RXNE, ENABLE); - - pprz_usart_set_baudrate(UART5, UART5_BAUD); - - /* Enable the UART5 */ - USART_Cmd(UART5, ENABLE); - - // initialize the transmit data queue - uart5_tx_extract_idx = 0; - uart5_tx_insert_idx = 0; - uart5_tx_running = FALSE; - - // initialize the receive data queuenn - uart5_rx_extract_idx = 0; - uart5_rx_insert_idx = 0; - -} - -void uart5_transmit( uint8_t data ) { - - uint16_t temp = (uart5_tx_insert_idx + 1) % UART5_TX_BUFFER_SIZE; - - if (temp == uart5_tx_extract_idx) - return; // no room - - USART_ITConfig(USART5, USART_IT_TXE, DISABLE); - - // check if in process of sending data - if (uart5_tx_running) { // yes, add to queue - uart5_tx_buffer[uart5_tx_insert_idx] = data; - uart5_tx_insert_idx = temp; - } - else { // no, set running flag and write to output register - uart5_tx_running = TRUE; - USART_SendData(USART5, data); - } - USART_ITConfig(USART5, USART_IT_TXE, ENABLE); - -} - -bool_t uart5_check_free_space( uint8_t len) { - int16_t space = uart5_tx_extract_idx - uart5_tx_insert_idx; - if (space <= 0) - space += UART5_TX_BUFFER_SIZE; - return (uint16_t)(space - 1) >= len; -} - - -void usart5_irq_handler(void) { - - if(USART_GetITStatus(USART5, USART_IT_TXE) != RESET){ - // check if more data to send - if (uart5_tx_insert_idx != uart5_tx_extract_idx) { - USART_SendData(USART5,uart5_tx_buffer[uart5_tx_extract_idx]); - uart5_tx_extract_idx++; - uart5_tx_extract_idx %= UART5_TX_BUFFER_SIZE; - } - else { - uart5_tx_running = FALSE; // clear running flag - USART_ITConfig(USART5, USART_IT_TXE, DISABLE); - } - } - - if(USART_GetITStatus(USART5, USART_IT_RXNE) != RESET){ - uint16_t temp = (uart5_rx_insert_idx + 1) % UART5_RX_BUFFER_SIZE;; - uart5_rx_buffer[uart5_rx_insert_idx] = USART_ReceiveData(USART5); - // check for more room in queue - if (temp != uart5_rx_extract_idx) - uart5_rx_insert_idx = temp; // update insert index - } - + uart_periph_set_baudrate(&uart5, UART5_BAUD); } +void usart5_irq_handler(void) { usart_irq_handler(&uart5); } #endif /* USE_UART5 */ -void uart_init( void ) -{ -#ifdef USE_UART1 - uart1_init(); -#endif -#ifdef USE_UART2 - uart2_init(); -#endif -#ifdef USE_UART3 - uart3_init(); -#endif -#ifdef USE_UART5 - uart5_init(); -#endif -} - - diff --git a/sw/airborne/arch/stm32/mcu_periph/uart_arch.h b/sw/airborne/arch/stm32/mcu_periph/uart_arch.h index 3d7113ef42..6160e8cbb0 100644 --- a/sw/airborne/arch/stm32/mcu_periph/uart_arch.h +++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.h @@ -36,6 +36,9 @@ #define B57600 57600 #define B115200 115200 +/* junk for gps_configure_uart in gps_ubx.c to compile */ +#define UART_8N1 1 +#define UART_FIFO_8 1 /* sort out the problem of UART5 already defined in stm32.h */ #define USART5 ((USART_TypeDef *) UART5_BASE) @@ -125,92 +128,6 @@ extern void usart3_irq_handler(void); extern void usart5_irq_handler(void); #endif -#ifdef USE_UART1 -#define UART1_RX_BUFFER_SIZE 128 -#define UART1_TX_BUFFER_SIZE 128 - -extern volatile uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx; -extern uint8_t uart1_rx_buffer[UART1_RX_BUFFER_SIZE]; - -extern volatile uint16_t uart1_tx_insert_idx, uart1_tx_extract_idx; -extern volatile bool_t uart1_tx_running; -extern uint8_t uart1_tx_buffer[UART1_TX_BUFFER_SIZE]; - -#define Uart1ChAvailable() (uart1_rx_insert_idx != uart1_rx_extract_idx) -#define Uart1Getch() ({ \ - uint8_t ret = uart1_rx_buffer[uart1_rx_extract_idx]; \ - uart1_rx_extract_idx = (uart1_rx_extract_idx + 1)%UART1_RX_BUFFER_SIZE; \ - ret; \ - }) - -#endif /* USE_UART1 */ - - -#ifdef USE_UART2 - -#define UART2_RX_BUFFER_SIZE 128 -#define UART2_TX_BUFFER_SIZE 128 - -extern volatile uint16_t uart2_rx_insert_idx, uart2_rx_extract_idx; -extern uint8_t uart2_rx_buffer[UART2_RX_BUFFER_SIZE]; - -extern volatile uint16_t uart2_tx_insert_idx, uart2_tx_extract_idx; -extern volatile bool_t uart2_tx_running; -extern uint8_t uart2_tx_buffer[UART2_TX_BUFFER_SIZE]; - -#define Uart2ChAvailable() (uart2_rx_insert_idx != uart2_rx_extract_idx) -#define Uart2Getch() ({ \ - uint8_t ret = uart2_rx_buffer[uart2_rx_extract_idx]; \ - uart2_rx_extract_idx = (uart2_rx_extract_idx + 1)%UART2_RX_BUFFER_SIZE; \ - ret; \ - }) - -#endif /* USE_UART2 */ - - -#ifdef USE_UART3 - -#define UART3_RX_BUFFER_SIZE 128 -#define UART3_TX_BUFFER_SIZE 128 - -extern volatile uint16_t uart3_rx_insert_idx, uart3_rx_extract_idx; -extern uint8_t uart3_rx_buffer[UART3_RX_BUFFER_SIZE]; - -extern volatile uint16_t uart3_tx_insert_idx, uart3_tx_extract_idx; -extern volatile bool_t uart3_tx_running; -extern uint8_t uart3_tx_buffer[UART3_TX_BUFFER_SIZE]; - -#define Uart3ChAvailable() (uart3_rx_insert_idx != uart3_rx_extract_idx) -#define Uart3Getch() ({ \ - uint8_t ret = uart3_rx_buffer[uart3_rx_extract_idx]; \ - uart3_rx_extract_idx = (uart3_rx_extract_idx + 1)%UART3_RX_BUFFER_SIZE; \ - ret; \ - }) - -#endif /* USE_UART3 */ - -#ifdef USE_UART5 - -#define UART5_RX_BUFFER_SIZE 128 -#define UART5_TX_BUFFER_SIZE 128 - -extern volatile uint16_t uart5_rx_insert_idx, uart5_rx_extract_idx; -extern uint8_t uart5_rx_buffer[UART5_RX_BUFFER_SIZE]; - -extern volatile uint16_t uart5_tx_insert_idx, uart5_tx_extract_idx; -extern volatile bool_t uart5_tx_running; -extern uint8_t uart5_tx_buffer[UART5_TX_BUFFER_SIZE]; - -#define Uart5ChAvailable() (uart5_rx_insert_idx != uart5_rx_extract_idx) -#define Uart5Getch() ({ \ - uint8_t ret = uart5_rx_buffer[uart5_rx_extract_idx]; \ - uart5_rx_extract_idx = (uart5_rx_extract_idx + 1)%UART5_RX_BUFFER_SIZE; \ - ret; \ - }) - -#endif /* USE_UART5 */ - - -void uart_init( void ); +//void uart_init( void ); #endif /* STM32_UART_ARCH_H */ diff --git a/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.h b/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.h index 5891d37df5..c8b77fab84 100644 --- a/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.h +++ b/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.h @@ -4,7 +4,6 @@ #include "subsystems/imu.h" #include -extern void imu_aspirin_arch_init(void); extern void imu_aspirin_arch_int_enable(void); extern void imu_aspirin_arch_int_disable(void); extern void adxl345_write_to_reg(uint8_t addr, uint8_t val); diff --git a/sw/airborne/arch/stm32/subsystems/settings_arch.c b/sw/airborne/arch/stm32/subsystems/settings_arch.c index 6ded02cc6e..e232d29471 100644 --- a/sw/airborne/arch/stm32/subsystems/settings_arch.c +++ b/sw/airborne/arch/stm32/subsystems/settings_arch.c @@ -24,7 +24,7 @@ /* flash data is located in the last page/sector of flash - + data flash_addr data_size flash_end - FSIZ checksum flash_end - FCHK @@ -50,9 +50,9 @@ struct FlashInfo { static uint32_t pflash_checksum(uint32_t ptr, uint32_t size); static int32_t flash_detect(struct FlashInfo* flash); static int32_t pflash_program_bytes(struct FlashInfo* flash, - uint32_t src, - uint32_t size, - uint32_t chksum); + uint32_t src, + uint32_t size, + uint32_t chksum); #define FLASH_SIZE_ MMIO16(0x1FFFF7E0) @@ -188,9 +188,9 @@ static int32_t flash_detect(struct FlashInfo* flash) { // 0x807F800 0x80000 static int32_t pflash_program_bytes(struct FlashInfo* flash, - uint32_t src, - uint32_t size, - uint32_t chksum) { + uint32_t src, + uint32_t size, + uint32_t chksum) { uint32_t i; /* erase */ @@ -250,13 +250,13 @@ int32_t persistent_read(uint32_t ptr, uint32_t size) { struct FlashInfo flash; uint32_t i; - /* check parameters */ + /* check parameters */ if (flash_detect(&flash)) return -1; if ((size > flash.page_size-FSIZ) || (size == 0)) return -2; /* check consistency */ if (size != *(uint32_t*)(flash.addr+flash.page_size-FSIZ)) return -3; - if (pflash_checksum(flash.addr, size) != + if (pflash_checksum(flash.addr, size) != *(uint32_t*)(flash.addr+flash.page_size-FCHK)) return -4; @@ -267,4 +267,3 @@ int32_t persistent_read(uint32_t ptr, uint32_t size) { return 0; } - diff --git a/sw/airborne/booz/test/booz2_tunnel.c b/sw/airborne/booz/test/booz2_tunnel.c index 9f8a4689ea..6bf2379e9d 100644 --- a/sw/airborne/booz/test/booz2_tunnel.c +++ b/sw/airborne/booz/test/booz2_tunnel.c @@ -62,10 +62,10 @@ static inline void main_periodic_task( void ) { static inline void main_event_task( void ) { while (Uart1ChAvailable()) - uart0_transmit(Uart1Getch()); + Uart0Transmit(Uart1Getch()); while (Uart0ChAvailable()) - uart1_transmit(Uart0Getch()); + Uart1Transmit(Uart0Getch()); } diff --git a/sw/airborne/csc/ppm_bridge_main.c b/sw/airborne/csc/ppm_bridge_main.c index e2915321b7..95961e9ef8 100644 --- a/sw/airborne/csc/ppm_bridge_main.c +++ b/sw/airborne/csc/ppm_bridge_main.c @@ -81,8 +81,8 @@ static void csc_main_periodic( void ) static void send_short( int16_t s ) { - uart1_transmit(s >> 8); - uart1_transmit(s & 0xFF); + Uart1Transmit(s >> 8); + Uart1Transmit(s & 0xFF); } static void send_channel ( int16_t c ) diff --git a/sw/airborne/estimator.c b/sw/airborne/estimator.c index 72b1ea4c8a..7753689238 100644 --- a/sw/airborne/estimator.c +++ b/sw/airborne/estimator.c @@ -66,6 +66,7 @@ float estimator_hspeed_dir; /* wind */ float wind_east, wind_north; float estimator_airspeed; +float estimator_AOA; #define NORM_RAD_ANGLE2(x) { \ while (x > 2 * M_PI) x -= 2 * M_PI; \ @@ -100,7 +101,11 @@ void estimator_init( void ) { #ifdef USE_AIRSPEED EstimatorSetAirspeed( 0. ); #endif - + +#ifdef USE_AOA + EstimatorSetAOA( 0. ); +#endif + estimator_flight_time = 0; estimator_airspeed = NOMINAL_AIRSPEED; diff --git a/sw/airborne/estimator.h b/sw/airborne/estimator.h index 54d25d9a4d..9924f7f7e3 100644 --- a/sw/airborne/estimator.h +++ b/sw/airborne/estimator.h @@ -69,6 +69,8 @@ extern float estimator_hspeed_dir; extern float wind_east, wind_north; /* m/s */ extern float estimator_airspeed; /* m/s */ +/* Angle of Attack estimation */ +extern float estimator_AOA; /* radians */ void estimator_init( void ); void estimator_propagate_state( void ); @@ -121,6 +123,7 @@ extern void alt_kalman( float ); #endif #define EstimatorSetAirspeed(airspeed) { estimator_airspeed = airspeed; } +#define EstimatorSetAOA(AOA) { estimator_AOA = AOA; } #define EstimatorSetAtt(phi, psi, theta) { estimator_phi = phi; estimator_psi = psi; estimator_theta = theta; } #define EstimatorSetPhiPsi(phi, psi) { estimator_phi = phi; estimator_psi = psi; } diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 248e74abab..36b6d9f51a 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -691,6 +691,10 @@ static inline void on_gyro_event( void ) { ahrs_update_accel(); ahrs_update_fw_estimator(); +#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP + new_ins_attitude = 1; +#endif + #else //PERIODIC_FREQUENCY static uint8_t _reduced_propagation_rate = 0; static uint8_t _reduced_correction_rate = 0; @@ -723,8 +727,13 @@ static inline void on_gyro_event( void ) { INT_VECT3_ZERO(acc_avg); ImuScaleAccel(imu); ahrs_update_accel(); - ahrs_update_fw_estimator(); } + + ahrs_update_fw_estimator(); + +#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP + new_ins_attitude = 1; +#endif } #endif //PERIODIC_FREQUENCY @@ -732,10 +741,6 @@ static inline void on_gyro_event( void ) { LED_OFF(AHRS_CPU_LED); #endif -#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP - new_ins_attitude = 1; -#endif - } static inline void on_mag_event(void) diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c index d779ed7cf5..cff5f79434 100644 --- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c +++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c @@ -65,6 +65,7 @@ float h_ctl_pitch_loop_setpoint; float h_ctl_pitch_pgain; float h_ctl_pitch_dgain; pprz_t h_ctl_elevator_setpoint; +uint8_t h_ctl_pitch_mode; /* inner loop pre-command */ float h_ctl_aileron_of_throttle; @@ -417,7 +418,18 @@ inline static void h_ctl_pitch_loop( void ) { h_ctl_pitch_setpoint - h_ctl_elevator_of_roll / h_ctl_pitch_pgain * fabs(estimator_phi); - float err = estimator_theta - h_ctl_pitch_loop_setpoint; + float err = 0; + switch (h_ctl_pitch_mode){ + case H_CTL_PITCH_MODE_THETA: + err = estimator_theta - h_ctl_pitch_loop_setpoint; + break; + case H_CTL_PITCH_MODE_AOA: + err = estimator_AOA - h_ctl_pitch_loop_setpoint; + break; + default: + err = estimator_theta - h_ctl_pitch_loop_setpoint; + break; + } float d_err = err - last_err; last_err = err; float cmd = h_ctl_pitch_pgain * (err + h_ctl_pitch_dgain * d_err); diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h index 0c68e7bd64..4ba21c5a11 100644 --- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h +++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h @@ -56,6 +56,11 @@ extern float h_ctl_roll_pgain; extern pprz_t h_ctl_aileron_setpoint; extern float h_ctl_roll_slew; +/* Pitch mode */ +#define H_CTL_PITCH_MODE_THETA 0 +#define H_CTL_PITCH_MODE_AOA 1 +extern uint8_t h_ctl_pitch_mode; + /* inner pitch loop parameters */ extern float h_ctl_pitch_setpoint; extern float h_ctl_pitch_loop_setpoint; diff --git a/sw/airborne/firmwares/non_ap/geiger_counter/geiger_counter.c b/sw/airborne/firmwares/non_ap/geiger_counter/geiger_counter.c new file mode 100644 index 0000000000..76c22094b4 --- /dev/null +++ b/sw/airborne/firmwares/non_ap/geiger_counter/geiger_counter.c @@ -0,0 +1,171 @@ +/* + * $Id$ + * + * Copyright (C) 2011 Martin Mueller + * + * This file is part of Paparazzi. + * + * Paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * Paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/* I2C interface for University of Reading Geiger-Mueller counter */ + +#include + +#define END_MSG 0x13 + +/* green LED pin PB5 (on arduino pro mini) */ +#define LED_GR_PIN 13 + +#define GEIGER_CNT_I2C_ADDR 0x76 + +enum stats { + INIT, + FOUND_SYNC, + FOUND_1, + FOUND_2, + FOUND_3, + FOUND_4, + FOUND_5 }; + +int received data = 0; +int stat = 0, received data = 0; +unsigned long count_geiger_1 = 0; +unsigned long count_geiger_2 = 0; +unsigned short volt_geiger = 0; + +void read_i2c() { + unsigned char dat[10]; + digitalWrite(LED_GR_PIN, LOW); + received_data = 0; + memcpy(dat, count_geiger_1, 4); + memcpy(dat+4, count_geiger_2, 4); + memcpy(dat+8, volt_geiger, 2); + Wire.send(dat, 2); +} + +void setup() { + /* serial port */ + Serial.begin(2400); + pinMode(2,OUTPUT); + digitalWrite(2,HIGH); +#ifdef DEBUG + Serial.println("geiger counter init"); +#endif + + /* I2C init */ + Wire.begin(GEIGER_CNT_I2C_ADDR >> 1); + Wire.onRequest(read_i2c); + + /* green LED init */ + digitalWrite(LED_GR_PIN, LOW); + pinMode(LED_GR_PIN, OUTPUT); + + stat = INIT; +} + +void loop() { + unsigned char ser; + int i; + + /* wait for data */ + if (Serial.available() > 0) { + ser = Serial.read(); + switch (stat) { + case INIT: + /* sync on the last byte of the prev message */ + if (b == END_MSG) { + count_geiger_1 = 0; + count_geiger_2 = 0; + volt_geiger = 0; + i = 0; + stat = FOUND_SYNC; + } + break; + case FOUND_SYNC: + if ((b <= '9') && (b >= '0')) { + count_geiger_1 = count_geiger_1 * 10 + (b-'0'); + if (++i > 7) state = IDLE; + } else if (b == ',')) { + i = 0; + stat = FOUND_1; + } else stat = INIT; + break; + case FOUND_1: + /* read counter 1 */ + if ((b <= '9') && (b >= '0')) { + count_geiger_2 = count_geiger_2 * 10 + (b-'0'); + if (++i > 7) state = IDLE; + } else if (b == ',')) { +#ifdef DEBUG + Serial.println(count_geiger_1, DEC); +#endif + i = 0; + stat = FOUND_2; + } else stat = INIT; + break; + case FOUND_2: + /* read counter 2 */ + if ((b <= '9') && (b >= '0')) { + count_geiger_2 = count_geiger_2 * 10 + (b-'0'); + if (++i > 7) state = IDLE; + } else if (b == ',')) { +#ifdef DEBUG + Serial.println(count_geiger_2, DEC); +#endif + i = 0; + stat = FOUND_3; + } else stat = INIT; + break; + case FOUND_3: + /* ignore 3 */ + if ((b <= '9') && (b >= '0')) { + if (++i > 7) state = IDLE; + } else if (b == ',')) { + i = 0; + stat = FOUND_4; + } else stat = INIT; + break; + case FOUND_4: + /* ignore 4 */ + if ((b <= '9') && (b >= '0')) { + if (++i > 7) state = IDLE; + } else if (b == ',')) { + i = 0; + stat = FOUND_5; + } else stat = INIT; + break; + case FOUND_5: + /* read voltage */ + if ((b <= '9') && (b >= '0')) { + volt_geiger = volt_geiger * 10 + (b-'0'); + if (++i > 7) state = IDLE; + } else if (b == 'V')) { + digitalWrite(LED_GR_PIN, HIGH); +#ifdef DEBUG + Serial.println(volt_geiger, DEC); +#endif + received_data = 0; + stat = INIT; + } else stat = INIT; + break; + default: + stat = INIT; + } + } +} + diff --git a/sw/airborne/firmwares/vor/lpc_vor_main.c b/sw/airborne/firmwares/vor/lpc_vor_main.c index bb6ee1e1b4..818f23e394 100644 --- a/sw/airborne/firmwares/vor/lpc_vor_main.c +++ b/sw/airborne/firmwares/vor/lpc_vor_main.c @@ -50,31 +50,31 @@ static inline void main_report( void ) { my_qdr = vid_qdr * 360 / 4980; if (my_qdr < 0) my_qdr+=3600; if (my_qdr > 3600) my_qdr-=3600; - uart0_transmit('\r'); + Uart0Transmit('\r'); break; case 1: tmp = my_qdr / 1000; my_qdr = my_qdr - 1000*tmp; - uart0_transmit('0'+tmp); + Uart0Transmit('0'+tmp); break; case 2: tmp = my_qdr / 100; my_qdr = my_qdr - 100*tmp; - uart0_transmit('0'+tmp); + Uart0Transmit('0'+tmp); break; case 3: tmp = my_qdr / 10; my_qdr = my_qdr - 10*tmp; - uart0_transmit('0'+tmp); + Uart0Transmit('0'+tmp); break; case 4: - uart0_transmit('.'); + Uart0Transmit('.'); break; case 5: - uart0_transmit('0'+my_qdr); + Uart0Transmit('0'+my_qdr); break; case 6: - uart0_transmit('\r'); + Uart0Transmit('\r'); break; } diff --git a/sw/airborne/lisa/test/lisa_tunnel.c b/sw/airborne/lisa/test/lisa_tunnel.c index 48c5072eca..d50839ffa0 100644 --- a/sw/airborne/lisa/test/lisa_tunnel.c +++ b/sw/airborne/lisa/test/lisa_tunnel.c @@ -59,10 +59,10 @@ static inline void main_periodic_task( void ) { static inline void main_event_task( void ) { if (Uart2ChAvailable()) - uart1_transmit(Uart2Getch()); + Uart1Transmit(Uart2Getch()); if (Uart1ChAvailable()) - uart2_transmit(Uart1Getch()); + Uart2Transmit(Uart1Getch()); } diff --git a/sw/airborne/lisa/test/test_board.c b/sw/airborne/lisa/test/test_board.c index 603f6ec155..d1fab3a701 100644 --- a/sw/airborne/lisa/test/test_board.c +++ b/sw/airborne/lisa/test/test_board.c @@ -246,8 +246,8 @@ static void test_uart_periodic(void) { if (idx_txrx_insert_idx = 0; + p->rx_extract_idx = 0; + p->tx_insert_idx = 0; + p->tx_extract_idx = 0; + p->tx_running = FALSE; +} + +bool_t uart_check_free_space(struct uart_periph* p, uint8_t len) { + int16_t space = p->tx_extract_idx - p->tx_insert_idx; + if (space <= 0) + space += UART_TX_BUFFER_SIZE; + return (uint16_t)(space - 1) >= len; +} + diff --git a/sw/airborne/mcu_periph/uart.h b/sw/airborne/mcu_periph/uart.h index 554fc6b9aa..f7c6e4f788 100644 --- a/sw/airborne/mcu_periph/uart.h +++ b/sw/airborne/mcu_periph/uart.h @@ -33,48 +33,82 @@ #include "mcu_periph/uart_arch.h" #include "std.h" +#define UART_RX_BUFFER_SIZE 128 +#define UART_TX_BUFFER_SIZE 128 +#define UART_DEV_NAME_SIZE 16 + +/** + * UART peripheral + */ +struct uart_periph { + /* Receive buffer */ + uint8_t rx_buf[UART_RX_BUFFER_SIZE]; + uint16_t rx_insert_idx; + uint16_t rx_extract_idx; + /* Transmit buffer */ + uint8_t tx_buf[UART_RX_BUFFER_SIZE]; + uint16_t tx_insert_idx; + uint16_t tx_extract_idx; + uint8_t tx_running; + /* UART Register */ + void* reg_addr; + /* UART Dev (linux) */ + char dev[UART_DEV_NAME_SIZE]; +}; + +extern void uart_periph_init(struct uart_periph* p); +extern void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud); +//extern void uart_periph_init_param(struct uart_periph* p, uint32_t baud, uint8_t mode, uint8_t fmode, char * dev); +extern void uart_transmit(struct uart_periph* p, uint8_t data); +extern bool_t uart_check_free_space(struct uart_periph* p, uint8_t len); + +#define UartChAvailable(_p) (_p.rx_insert_idx != _p.rx_extract_idx) + +#define UartGetch(_p) ({ \ + uint8_t ret = _p.rx_buf[_p.rx_extract_idx]; \ + _p.rx_extract_idx = (_p.rx_extract_idx + 1)%UART_RX_BUFFER_SIZE; \ + ret; \ +}) + #ifdef USE_UART0 +extern struct uart_periph uart0; +extern void uart0_init(void); -extern void uart0_init( void ); -extern void uart0_transmit( uint8_t data ); -extern bool_t uart0_check_free_space( uint8_t len); - -#define Uart0Init uart0_init -#define Uart0CheckFreeSpace(_x) uart0_check_free_space(_x) -#define Uart0Transmit(_x) uart0_transmit(_x) +#define Uart0Init() uart_periph_init(&uart0) +#define Uart0CheckFreeSpace(_x) uart_check_free_space(&uart0, _x) +#define Uart0Transmit(_x) uart_transmit(&uart0, _x) #define Uart0SendMessage() {} +#define Uart0ChAvailable() UartChAvailable(uart0) +#define Uart0Getch() UartGetch(uart0) +#define Uart0TxRunning uart0.tx_running +#define Uart0SetBaudrate(_b) uart_periph_set_baudrate(&uart0, _b) +//#define Uart0InitParam(_b, _m, _fm) uart_periph_init_param(&uart0, _b, _m, _fm, "") -#define Uart0TxRunning uart0_tx_running -#define Uart0InitParam uart0_init_param -#define UART0TxRunning uart0_tx_running -#define UART0InitParam uart0_init_param - -/* I want to trigger USE_UART and generate macros with the makefile same variable */ #define UART0Init Uart0Init #define UART0CheckFreeSpace Uart0CheckFreeSpace #define UART0Transmit Uart0Transmit #define UART0SendMessage Uart0SendMessage #define UART0ChAvailable Uart0ChAvailable #define UART0Getch Uart0Getch +#define UART0TxRunning Uart0TxRunning +#define UART0InitParam Uart0InitParam -#endif /* USE_UART0 */ +#endif // USE_UART0 #ifdef USE_UART1 +extern struct uart_periph uart1; +extern void uart1_init(void); -extern void uart1_init( void ); -extern void uart1_transmit( uint8_t data ); -extern bool_t uart1_check_free_space( uint8_t len); - -#define Uart1Init uart1_init -#define Uart1CheckFreeSpace(_x) uart1_check_free_space(_x) -#define Uart1Transmit(_x) uart1_transmit(_x) +#define Uart1Init() uart_periph_init(&uart1) +#define Uart1CheckFreeSpace(_x) uart_check_free_space(&uart1, _x) +#define Uart1Transmit(_x) uart_transmit(&uart1, _x) #define Uart1SendMessage() {} - -#define Uart1TxRunning uart1_tx_running -#define Uart1InitParam uart1_init_param -#define UART1TxRunning uart1_tx_running -#define UART1InitParam uart1_init_param +#define Uart1ChAvailable() UartChAvailable(uart1) +#define Uart1Getch() UartGetch(uart1) +#define Uart1TxRunning uart1.tx_running +#define Uart1SetBaudrate(_b) uart_periph_set_baudrate(&uart1, _b) +//#define Uart1InitParam(_b, _m, _fm) uart_periph_init_param(&uart1, _b, _m, _fm, "") #define UART1Init Uart1Init #define UART1CheckFreeSpace Uart1CheckFreeSpace @@ -82,19 +116,24 @@ extern bool_t uart1_check_free_space( uint8_t len); #define UART1SendMessage Uart1SendMessage #define UART1ChAvailable Uart1ChAvailable #define UART1Getch Uart1Getch +#define UART1TxRunning Uart1TxRunning +#define UART1InitParam Uart1InitParam -#endif /* USE_UART1 */ +#endif // USE_UART1 #ifdef USE_UART2 +extern struct uart_periph uart2; +extern void uart2_init(void); -extern void uart2_init( void ); -extern void uart2_transmit( uint8_t data ); -extern bool_t uart2_check_free_space( uint8_t len); - -#define Uart2Init uart2_init -#define Uart2CheckFreeSpace(_x) uart2_check_free_space(_x) -#define Uart2Transmit(_x) uart2_transmit(_x) +#define Uart2Init() uart_periph_init(&uart2) +#define Uart2CheckFreeSpace(_x) uart_check_free_space(&uart2, _x) +#define Uart2Transmit(_x) uart_transmit(&uart2, _x) #define Uart2SendMessage() {} +#define Uart2ChAvailable() UartChAvailable(uart2) +#define Uart2Getch() UartGetch(uart2) +#define Uart2TxRunning uart2.tx_running +#define Uart2SetBaudrate(_b) uart_periph_set_baudrate(&uart2, _b) +//#define Uart2InitParam(_b, _m, _fm) uart_periph_init_param(&uart2, _b, _m, _fm, "") #define UART2Init Uart2Init #define UART2CheckFreeSpace Uart2CheckFreeSpace @@ -102,19 +141,24 @@ extern bool_t uart2_check_free_space( uint8_t len); #define UART2SendMessage Uart2SendMessage #define UART2ChAvailable Uart2ChAvailable #define UART2Getch Uart2Getch +#define UART2TxRunning Uart2TxRunning +#define UART2InitParam Uart2InitParam -#endif /* USE_UART2 */ +#endif // USE_UART2 #ifdef USE_UART3 +extern struct uart_periph uart3; +extern void uart3_init(void); -extern void uart3_init( void ); -extern void uart3_transmit( uint8_t data ); -extern bool_t uart3_check_free_space( uint8_t len); - -#define Uart3Init uart3_init -#define Uart3CheckFreeSpace(_x) uart3_check_free_space(_x) -#define Uart3Transmit(_x) uart3_transmit(_x) +#define Uart3Init() uart_periph_init(&uart3) +#define Uart3CheckFreeSpace(_x) uart_check_free_space(&uart3, _x) +#define Uart3Transmit(_x) uart_transmit(&uart3, _x) #define Uart3SendMessage() {} +#define Uart3ChAvailable() UartChAvailable(uart3) +#define Uart3Getch() UartGetch(uart3) +#define Uart3TxRunning uart3.tx_running +#define Uart3SetBaudrate(_b) uart_periph_set_baudrate(&uart3, _b) +//#define Uart3InitParam(_b, _m, _fm) uart_periph_init_param(&uart3, _b, _m, _fm, "") #define UART3Init Uart3Init #define UART3CheckFreeSpace Uart3CheckFreeSpace @@ -122,19 +166,24 @@ extern bool_t uart3_check_free_space( uint8_t len); #define UART3SendMessage Uart3SendMessage #define UART3ChAvailable Uart3ChAvailable #define UART3Getch Uart3Getch +#define UART3TxRunning Uart3TxRunning +#define UART3InitParam Uart3InitParam -#endif /* USE_UART3 */ +#endif // USE_UART3 #ifdef USE_UART5 +extern struct uart_periph uart5; +extern void uart5_init(void); -extern void uart5_init( void ); -extern void uart5_transmit( uint8_t data ); -extern bool_t uart5_check_free_space( uint8_t len); - -#define Uart5Init uart5_init -#define Uart5CheckFreeSpace(_x) uart5_check_free_space(_x) -#define Uart5Transmit(_x) uart5_transmit(_x) +#define Uart5Init() uart_periph_init(&uart5) +#define Uart5CheckFreeSpace(_x) uart_check_free_space(&uart5, _x) +#define Uart5Transmit(_x) uart_transmit(&uart5, _x) #define Uart5SendMessage() {} +#define Uart5ChAvailable() UartChAvailable(uart5) +#define Uart5Getch() UartGetch(uart5) +#define Uart5TxRunning uart5.tx_running +#define Uart5SetBaudrate(_b) uart_periph_set_baudrate(&uart5, _b) +//#define Uart5InitParam(_b, _m, _fm) uart_periph_init_param(&uart5, _b, _m, _fm, "") #define UART5Init Uart5Init #define UART5CheckFreeSpace Uart5CheckFreeSpace @@ -142,7 +191,9 @@ extern bool_t uart5_check_free_space( uint8_t len); #define UART5SendMessage Uart5SendMessage #define UART5ChAvailable Uart5ChAvailable #define UART5Getch Uart5Getch +#define UART5TxRunning Uart5TxRunning +#define UART5InitParam Uart5InitParam -#endif /* USE_UART5 */ +#endif // USE_UART5 #endif /* MCU_PERIPH_UART_H */ diff --git a/sw/airborne/modules/benchmark/flight_benchmark.c b/sw/airborne/modules/benchmark/flight_benchmark.c new file mode 100644 index 0000000000..a965c21b86 --- /dev/null +++ b/sw/airborne/modules/benchmark/flight_benchmark.c @@ -0,0 +1,138 @@ +//Author: Bruzzlee + +//This module allows a quantitative assessment of the flight. +//It calculates the sum of squared error of the two-dimensional course (x / y), the altitude and true airspeed. +//The sum of squared error of the course and altitude were separated, because they are regulated separately, and so they dependent on various parameters. +//The module was written to optimize the control parameters and has already been used successfully. + + +#include "firmwares/fixedwing/guidance/guidance_v.h" +#include "estimator.h" +#include "messages.h" +#include "downlink.h" +#include "mcu_periph/uart.h" +#include "generated/airframe.h" +#include "subsystems/nav.h" +// #include "math/pprz_algebra_int.h" +// #include "math/pprz_algebra_float.h" + +// For Downlink +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + + + +float SquareSumErr_airspeed; +float SquareSumErr_altitude; +float SquareSumErr_position; +float ToleranceAispeed; +float ToleranceAltitude; +float TolerancePosition; +bool_t benchm_reset; +bool_t benchm_go; + + +//uint8_t numOfCount; + + + +void flight_benchmark_init( void ) { + SquareSumErr_airspeed = 0; + SquareSumErr_altitude = 0; + SquareSumErr_position = 0; + ToleranceAispeed = BENCHMARK_TOLERANCE_AIRSPEED; + ToleranceAltitude = BENCHMARK_TOLERANCE_ALTITUDE; + TolerancePosition = BENCHMARK_TOLERANCE_POSITION; + benchm_reset = 0; + benchm_go = 0; +} + +void flight_benchmark_periodic( void ) { + float Err_airspeed = 0; + float Err_altitude = 0; + float Err_position = 0; + + if (benchm_reset){ + flight_benchmark_reset(); + benchm_reset = 0; + } + + if (benchm_go){ + #if defined(USE_AIRSPEED) && defined(BENCHMARK_AIRSPEED) + Err_airspeed = fabs(estimator_airspeed - v_ctl_auto_airspeed_setpoint); + if (Err_airspeed>ToleranceAispeed){ + Err_airspeed = Err_airspeed-ToleranceAispeed; + SquareSumErr_airspeed += (Err_airspeed * Err_airspeed); + } + #endif + + #ifdef BENCHMARK_ALTITUDE + Err_altitude = fabs(estimator_z - v_ctl_altitude_setpoint); + if (Err_altitude>ToleranceAltitude){ + Err_altitude = Err_altitude-ToleranceAltitude; + SquareSumErr_altitude += (Err_altitude * Err_altitude); + } + #endif + + #ifdef BENCHMARK_POSITION + + //---------------This part is a waste of memory and calculation power - but it works - feel free to optimize it ;-) ----------------- + + // err_temp = waypoints[target].x - estimator_x; + float deltaPlaneX = 0; + float deltaPlaneY = 0; + float Err_position_segment = 0; + float Err_position_circle = 0; + +// if (nav_in_segment){ + float deltaX = nav_segment_x_2 - nav_segment_x_1; + float deltaY = nav_segment_y_2 - nav_segment_y_1; + float anglePath = atan2(deltaX,deltaY); + deltaPlaneX = nav_segment_x_2 - estimator_x; + deltaPlaneY = nav_segment_y_2 - estimator_y; + float anglePlane = atan2(deltaPlaneX,deltaPlaneY); + float angleDiff = fabs(anglePlane - anglePath); + Err_position_segment = fabs(sin(angleDiff)*sqrt(deltaPlaneX*deltaPlaneX+deltaPlaneY*deltaPlaneY)); +// } + +// if (nav_in_circle){ + deltaPlaneX = nav_circle_x - estimator_x; + deltaPlaneY = nav_circle_y - estimator_y; + Err_position_circle = fabs(sqrt(deltaPlaneX*deltaPlaneX+deltaPlaneY*deltaPlaneY)-nav_circle_radius); +// } + if (Err_position_circle < Err_position_segment){ + Err_position = Err_position_circle; + } + else + Err_position = Err_position_segment; + + if (Err_position>TolerancePosition){ + SquareSumErr_position += (Err_position * Err_position); + } + #endif + } + + DOWNLINK_SEND_FLIGHT_BENCHMARK(DefaultChannel, &SquareSumErr_airspeed, &SquareSumErr_altitude, &SquareSumErr_position, &Err_airspeed, &Err_altitude, &Err_position) + +} + +void flight_benchmark_reset( void ) { + SquareSumErr_airspeed = 0; + SquareSumErr_altitude = 0; + SquareSumErr_position = 0; +} + + + + + + + + + + + + + + diff --git a/sw/airborne/modules/benchmark/flight_benchmark.h b/sw/airborne/modules/benchmark/flight_benchmark.h new file mode 100644 index 0000000000..8bef0d3976 --- /dev/null +++ b/sw/airborne/modules/benchmark/flight_benchmark.h @@ -0,0 +1,16 @@ +#ifndef FLIGHTBENCHMARK_H +#define FLIGHTBENCHMARK_H + +#include + +void flight_benchmark_init( void ); +void flight_benchmark_periodic( void ); +void flight_benchmark_reset( void ); + +extern float ToleranceAispeed; +extern float ToleranceAltitude; +extern float TolerancePosition; +extern bool_t benchm_reset; +extern bool_t benchm_go; + +#endif /* FLIGHTBENCHMARK_H */ diff --git a/sw/airborne/modules/cam_control/cam.c b/sw/airborne/modules/cam_control/cam.c index b4619aacdd..0290a4d471 100644 --- a/sw/airborne/modules/cam_control/cam.c +++ b/sw/airborne/modules/cam_control/cam.c @@ -87,6 +87,7 @@ uint8_t cam_target_wp; uint8_t cam_target_ac; uint8_t cam_mode; +bool_t cam_lock; int16_t cam_pan_command; int16_t cam_tilt_command; @@ -106,31 +107,100 @@ void cam_init( void ) { } void cam_periodic( void ) { - switch (cam_mode) { - case CAM_MODE_OFF: - break; - case CAM_MODE_ANGLES: +#if defined(CAM_FIXED_FOR_FPV_IN_AUTO1) && CAM_FIXED_FOR_FPV_IN_AUTO1 == 1 + //Position the camera for straight view. + if (pprz_mode == PPRZ_MODE_AUTO2){ +#endif + switch (cam_mode) { + case CAM_MODE_OFF: +#if defined(CAM_PAN0) + cam_pan_c = RadOfDeg(CAM_PAN0); +#else + cam_pan_c = RadOfDeg(0); +#endif +#if defined(CAM_TILT0) + cam_tilt_c = RadOfDeg(CAM_TILT0); +#else + cam_tilt_c = RadOfDeg(90); +#endif + cam_angles(); + break; + case CAM_MODE_ANGLES: + cam_angles(); + break; + case CAM_MODE_NADIR: + cam_nadir(); + break; + case CAM_MODE_XY_TARGET: + cam_target(); + break; + case CAM_MODE_WP_TARGET: + cam_waypoint_target(); + break; + case CAM_MODE_AC_TARGET: + cam_ac_target(); + break; + // In this mode the target coordinates are calculated continuously from the pan and tilt radio channels. + // The "TARGET" waypoint coordinates are not used. + // If the "-DSHOW_CAM_COORDINATES" is defined then the coordinates of where the camera is looking are calculated. + case CAM_MODE_STABILIZED: + cam_waypoint_target(); + break; + // In this mode the angles come from the pan and tilt radio channels. + // The "TARGET" waypoint coordinates are not used but i need to call the "cam_waypoint_target()" function + // in order to calculate the coordinates of where the camera is looking. + case CAM_MODE_RC: + cam_waypoint_target(); + break; + } +#if defined(CAM_FIXED_FOR_FPV_IN_AUTO1) && CAM_FIXED_FOR_FPV_IN_AUTO1 == 1 + }else if (pprz_mode == PPRZ_MODE_AUTO1){ + //Position the camera for straight view. + +#if defined(CAM_TILT_POSITION_FOR_FPV) + cam_tilt_c = RadOfDeg(CAM_TILT_POSITION_FOR_FPV); +#else + cam_tilt_c = RadOfDeg(90); +#endif +#if defined(CAM_PAN_POSITION_FOR_FPV) + cam_pan_c = RadOfDeg(CAM_PAN_POSITION_FOR_FPV); +#else + cam_pan_c = RadOfDeg(0); +#endif cam_angles(); - break; - case CAM_MODE_NADIR: - cam_nadir(); - break; - case CAM_MODE_XY_TARGET: - cam_target(); - break; - case CAM_MODE_WP_TARGET: - cam_waypoint_target(); - break; - case CAM_MODE_AC_TARGET: - cam_ac_target(); - break; +#ifdef SHOW_CAM_COORDINATES + cam_point_lon = 0; + cam_point_lat = 0; + cam_point_distance_from_home = 0; +#endif } +#endif + + +#if defined(COMMAND_CAM_PWR_SW) + if(video_tx_state){ ap_state->commands[COMMAND_CAM_PWR_SW] = MAX_PPRZ; }else{ ap_state->commands[COMMAND_CAM_PWR_SW] = MIN_PPRZ; } +#elif defined(VIDEO_TX_SWITCH) + if(video_tx_state){ LED_OFF(VIDEO_TX_SWITCH); }else{ LED_ON(VIDEO_TX_SWITCH); } +#endif } /** Computes the servo values from cam_pan_c and cam_tilt_c */ void cam_angles( void ) { float cam_pan = 0; float cam_tilt = 0; + if (cam_pan_c > RadOfDeg(CAM_PAN_MAX)){ + cam_pan_c = RadOfDeg(CAM_PAN_MAX); + + }else{ + if(cam_pan_c < RadOfDeg(CAM_PAN_MIN)){ cam_pan_c = RadOfDeg(CAM_PAN_MIN); } + } + + if (cam_tilt_c > RadOfDeg(CAM_TILT_MAX)){ + cam_tilt_c = RadOfDeg(CAM_TILT_MAX); + + }else{ + if(cam_tilt_c < RadOfDeg(CAM_TILT_MIN)){ cam_tilt_c = RadOfDeg(CAM_TILT_MIN); } + } #ifdef CAM_PAN_NEUTRAL float pan_diff = cam_pan_c - RadOfDeg(CAM_PAN_NEUTRAL); @@ -138,6 +208,8 @@ void cam_angles( void ) { cam_pan = MAX_PPRZ * (pan_diff / (RadOfDeg(CAM_PAN_MAX - CAM_PAN_NEUTRAL))); else cam_pan = MIN_PPRZ * (pan_diff / (RadOfDeg(CAM_PAN_MIN - CAM_PAN_NEUTRAL))); +#else + cam_pan = ((float)RadOfDeg(cam_pan_c - CAM_PAN_MIN)) * ((float)MAX_PPRZ / (float)RadOfDeg(CAM_PAN_MAX-CAM_PAN_MIN) ); #endif #ifdef CAM_TILT_NEUTRAL @@ -146,6 +218,8 @@ void cam_angles( void ) { cam_tilt = MAX_PPRZ * (tilt_diff / (RadOfDeg(CAM_TILT_MAX - CAM_TILT_NEUTRAL))); else cam_tilt = MIN_PPRZ * (tilt_diff / (RadOfDeg(CAM_TILT_MIN - CAM_TILT_NEUTRAL))); +#else + cam_tilt = ((float)RadOfDeg(cam_tilt_c - CAM_TILT_MIN)) * ((float)MAX_PPRZ / (float)RadOfDeg(CAM_TILT_MAX-CAM_TILT_MIN) ); #endif cam_pan = TRIM_PPRZ(cam_pan); diff --git a/sw/airborne/modules/cam_control/cam.h b/sw/airborne/modules/cam_control/cam.h index 062f021e64..5a829e1498 100644 --- a/sw/airborne/modules/cam_control/cam.h +++ b/sw/airborne/modules/cam_control/cam.h @@ -38,8 +38,24 @@ #define CAM_MODE_XY_TARGET 3 /* Input: target_x, target_y */ #define CAM_MODE_WP_TARGET 4 /* Input: waypoint no */ #define CAM_MODE_AC_TARGET 5 /* Input: ac id */ +#define CAM_MODE_STABILIZED 6 // Stabilized mode, input: camera angles from the pan and tilt radio channels, output pointing coordinates. +#define CAM_MODE_RC 7 // Manual mode, input: camera angles from the pan and tilt radio channels, output servo positions. + +#ifndef CAM_PAN_MAX +#define CAM_PAN_MAX 90 +#endif +#ifndef CAM_PAN_MIN +#define CAM_PAN_MIN -90 +#endif +#ifndef CAM_TILT_MAX +#define CAM_TILT_MAX 90 +#endif +#ifndef CAM_TILT_MIN +#define CAM_TILT_MIN -90 +#endif extern uint8_t cam_mode; +extern uint8_t cam_lock; extern float cam_phi_c, cam_theta_c; @@ -47,7 +63,7 @@ extern float cam_pan_c, cam_tilt_c; /* pan (move left and right), tilt (move up and down) */ /** Radians, for CAM_MODE_ANGLES mode */ -extern float cam_target_x, cam_target_y; +extern float cam_target_x, cam_target_y, cam_target_alt; /** For CAM_MODE_XY_TARGET mode */ extern uint8_t cam_target_wp; @@ -72,4 +88,13 @@ extern float test_cam_estimator_phi; extern float test_cam_estimator_theta; extern float test_cam_estimator_hspeed_dir; #endif // TEST_CAM + +#if defined(COMMAND_CAM_PWR_SW) || defined(VIDEO_TX_SWITCH) + +extern bool_t video_tx_state; +#define VIDEO_TX_ON() { video_tx_state = 1; 0; } +#define VIDEO_TX_OFF() { video_tx_state = 0; 0; } + +#endif + #endif // CAM_H diff --git a/sw/airborne/modules/cam_control/cam_segment.c b/sw/airborne/modules/cam_control/cam_segment.c new file mode 100644 index 0000000000..1b6d104044 --- /dev/null +++ b/sw/airborne/modules/cam_control/cam_segment.c @@ -0,0 +1,48 @@ +/* + * $Id$ + * + * Copyright (C) 2011 Gautier Hattenberger + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ +/** \file cam_segment.c + * \brief camera control to track a segment using the general cam driver (target mode) + * + * initial version: pointing towards the carrot + */ + +#include "modules/cam_control/cam_segment.h" +#include "modules/cam_control/cam.h" +#include "subsystems/nav.h" +#include "estimator.h" + +void cam_segment_init( void ) { +} + +void cam_segment_stop ( void ) { + cam_mode = CAM_MODE_OFF; +} + +void cam_segment_periodic( void ) { + cam_mode = CAM_MODE_XY_TARGET; + cam_target_x = desired_x; + cam_target_y = desired_y; + cam_target_alt = ground_alt; +} + diff --git a/sw/airborne/modules/cam_control/cam_segment.h b/sw/airborne/modules/cam_control/cam_segment.h new file mode 100644 index 0000000000..32b336b4d8 --- /dev/null +++ b/sw/airborne/modules/cam_control/cam_segment.h @@ -0,0 +1,37 @@ +/* + * $Id$ + * + * Copyright (C) 2011 Gautier Hattenberger + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ +/** \file cam_segment.c + * \brief camera control to track a segment using the general cam driver (target mode) + * + * initial version: pointing towards the carrot + */ + +#ifndef CAM_SEGMENT_H +#define CAM_SEGMENT_H + +extern void cam_segment_init( void ); +extern void cam_segment_stop ( void ); +extern void cam_segment_periodic( void ); + +#endif diff --git a/sw/airborne/modules/cam_control/cam_track.h b/sw/airborne/modules/cam_control/cam_track.h index 0cfc6e6644..d7c84f03f1 100644 --- a/sw/airborne/modules/cam_control/cam_track.h +++ b/sw/airborne/modules/cam_control/cam_track.h @@ -54,7 +54,7 @@ extern void parse_cam_buffer( uint8_t ); #define CamBuffer() CamLink(ChAvailable()) #define ReadCamBuffer() { while (CamLink(ChAvailable())&&!cam_msg_received) parse_cam_buffer(CamLink(Getch())); } #define CamUartSend1(c) CamLink(Transmit(c)) -#define CamUartInitParam(_a,_b,_c) CamLink(InitParam(_a,_b,_c)) +#define CamUartSetBaudrate(_b) CamLink(SetBaudrate(_b)) #define CamUartRunning CamLink(TxRunning) #define CamEventCheckAndHandle() { \ diff --git a/sw/airborne/modules/cam_control/point.c b/sw/airborne/modules/cam_control/point.c index 5e13c9abc5..2223e327e6 100644 --- a/sw/airborne/modules/cam_control/point.c +++ b/sw/airborne/modules/cam_control/point.c @@ -2,6 +2,8 @@ * $Id$ * * Copyright (C) 2005-2008 Arnold Schroeter + * Modified and expanded to show the coordinates of where the camera is looking at + * by Chris Efstathiou 23-Jan-2011 AD. * * This file is part of paparazzi. * @@ -72,7 +74,13 @@ */ #include +#include "cam.h" #include "point.h" +#include "autopilot.h" +#include "generated/flight_plan.h" +#include "subsystems/navigation/common_nav.h" +#include "subsystems/gps.h" +#include "math/pprz_geodetic_float.h" typedef struct { float fx; @@ -84,6 +92,18 @@ typedef struct { float fy1; float fy2; float fy3; float fz1; float fz2; float fz3;} MATRIX; +float cam_theta; +float cam_phi; +bool_t heading_positive = 0; +float memory_x, memory_y, memory_z; +#if defined(SHOW_CAM_COORDINATES) +float cam_point_x; +float cam_point_y; +unsigned int cam_point_distance_from_home; +float cam_point_lon, cam_point_lat; +float distance_correction = 1; +#endif + void vSubtractVectors(VECTOR* svA, VECTOR svB, VECTOR svC); void vMultiplyMatrixByVector(VECTOR* svA, MATRIX smB, VECTOR svC); @@ -150,8 +170,269 @@ void vPoint(float fPlaneEast, float fPlaneNorth, float fPlaneAltitude, svObjectPositionForPlane, svObjectPositionForPlane2; + static VECTOR sv_cam_projection, + sv_cam_projection_buf; + static MATRIX smRotation; +/*** BELOW IS THE CODE THAT READS THE RC PAN AND TILT CHANNELS AND CONVERTS THEM TO ANGLES (RADIANS) ***/ +/*** IT IS USED FOR CALCULATING THE COORDINATES OF THE POINT WHERE THE CAMERA IS LOOKING AT ***/ +/*** THIS IS DONE ONLY FOR THE CAM_MODE_STABILIZED OR CAM_MODE_RC. ***/ +/*** IN OTHER MODES ONLY THE CAM_POINT WAYPOINT AND THE DISTANCE FROM TARGET IS UPDATED ***/ +if (cam_mode == CAM_MODE_STABILIZED || cam_mode == CAM_MODE_RC || cam_mode == CAM_MODE_WP_TARGET || cam_mode == CAM_MODE_XY_TARGET ){ + +if (cam_mode == CAM_MODE_STABILIZED || cam_mode == CAM_MODE_RC ){ + +/*######################################## TILT CONTROL INPUT #############################################*/ +#ifdef CAM_TILT_NEUTRAL + +#if defined(RADIO_TILT) + if ((*fbw_state).channels[RADIO_TILT] >= 0){ + cam_theta = (float)RadOfDeg(CAM_TILT_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_TILT] /(float)MAX_PPRZ) * + (float)(RadOfDeg(CAM_TILT_MAX - CAM_TILT_NEUTRAL)) ); + + }else{ + cam_theta = (float)RadOfDeg(CAM_TILT_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_TILT] /(float)MIN_PPRZ) * + (float)(RadOfDeg(CAM_TILT_MIN - CAM_TILT_NEUTRAL)) ); + } +#elif defined(RADIO_PITCH) + if ((*fbw_state).channels[RADIO_PITCH] >= 0){ + cam_theta = (float)RadOfDeg(CAM_TILT_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_PITCH] /(float)MAX_PPRZ) * + (float)(RadOfDeg(CAM_TILT_MAX - CAM_TILT_NEUTRAL)) ); + + }else{ + cam_theta = (float)RadOfDeg(CAM_TILT_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_PITCH] /(float)MIN_PPRZ) * + (float)(RadOfDeg(CAM_TILT_MIN - CAM_TILT_NEUTRAL)) ); + } +#else +#error RADIO_TILT or RADIO_PITCH not defined. +#endif + +#else //#ifdef CAM_TILT_NEUTRAL + +#if defined(RADIO_TILT) + cam_theta = RadOfDeg(CAM_TILT_MIN) + (RadOfDeg(CAM_TILT_MAX - CAM_TILT_MIN) * ((float)(*fbw_state).channels[RADIO_TILT] /(float)MAX_PPRZ)); +#elif defined(RADIO_PITCH) + cam_theta = RadOfDeg(CAM_TILT_MIN) + (RadOfDeg(CAM_TILT_MAX - CAM_TILT_MIN) * ((float)(*fbw_state).channels[RADIO_PITCH] /(float)MAX_PPRZ)); +#else +#error RADIO_TILT or RADIO_PITCH not defined. +#endif + +#endif //#ifdef CAM_TILT_NEUTRAL +/*######################################## END OF TILT CONTROL INPUT ########################################*/ + +/*########################################### PAN CONTROL INPUT #############################################*/ +#ifdef CAM_PAN_NEUTRAL + +#if defined(RADIO_PAN) + if ((*fbw_state).channels[RADIO_PAN] >= 0){ + cam_phi = RadOfDeg(CAM_PAN_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_PAN] /(float)MAX_PPRZ) * + RadOfDeg(CAM_PAN_MAX - CAM_PAN_NEUTRAL) ); + + }else{ + cam_phi = RadOfDeg(CAM_PAN_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_PAN] /(float)MIN_PPRZ) * + RadOfDeg(CAM_PAN_MIN - CAM_PAN_NEUTRAL) ); + } +#elif defined(RADIO_ROLL) + if ((*fbw_state).channels[RADIO_ROLL] >= 0){ + cam_phi = RadOfDeg(CAM_PAN_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_ROLL] /(float)MAX_PPRZ) * + RadOfDeg(CAM_PAN_MAX - CAM_PAN_NEUTRAL) ); + + }else{ + cam_phi = RadOfDeg(CAM_PAN_NEUTRAL) + ( ((float)(*fbw_state).channels[RADIO_ROLL] /(float)MIN_PPRZ) * + RadOfDeg(CAM_PAN_MIN - CAM_PAN_NEUTRAL) ); + } +#else +#error RADIO_PAN or RADIO_ROLL not defined. +#endif + +#else //#ifdef CAM_PAN_NEUTRAL + +#if defined(RADIO_PAN) + cam_phi = RadOfDeg(CAM_PAN_MIN) + (RadOfDeg(CAM_PAN_MAX - CAM_PAN_MIN) * ((float)(*fbw_state).channels[RADIO_PAN] /(float)MAX_PPRZ)); +#elif defined(RADIO_ROLL) + cam_phi = RadOfDeg(CAM_PAN_MIN) + (RadOfDeg(CAM_PAN_MAX - CAM_PAN_MIN) * ((float)(*fbw_state).channels[RADIO_ROLL] /(float)MAX_PPRZ)); +#else +#error RADIO_PAN or RADIO_ROLL not defined. +#endif + +#endif //#ifdef CAM_PAN_NEUTRAL +/*######################################## END OF PAN CONTROL INPUT #############################################*/ + + // Bound Pan and Tilt angles. + if (cam_theta > RadOfDeg(CAM_TILT_MAX)){ + cam_theta = RadOfDeg(CAM_TILT_MAX); + + }else if(cam_theta < RadOfDeg(CAM_TILT_MIN)){ cam_theta = RadOfDeg(CAM_TILT_MIN); } + + if (cam_phi > RadOfDeg(CAM_PAN_MAX)){ + cam_phi = RadOfDeg(CAM_PAN_MAX); + + }else if(cam_phi < RadOfDeg(CAM_PAN_MIN)){ cam_phi = RadOfDeg(CAM_PAN_MIN); } + + + svPlanePosition.fx = fPlaneEast; + svPlanePosition.fy = fPlaneNorth; + svPlanePosition.fz = fPlaneAltitude; + +// FOR TESTING ANGLES IN THE SIMULATOR ONLY CODE UNCOMMENT THE TWO BELOW LINES +//cam_phi = RadOfDeg(90); // LOOK 45 DEGREES TO THE LEFT, -X IS TO THE LEFT AND +X IS TO THE RIGHT +//cam_theta = RadOfDeg(70); // LOOK 45 DEGREES DOWN, 0 IS STRAIGHT DOWN 90 IS STRAIGHT IN FRONT + + if ( cam_theta > RadOfDeg(80) && cam_mode == CAM_MODE_RC){ // Not much to see after 80 degrees of tilt so stop tracking. + *fPan = cam_phi; + *fTilt = cam_theta; +#ifdef SHOW_CAM_COORDINATES + cam_point_distance_from_home = 0; + cam_point_lon = 0; + cam_point_lat = 0; +#endif + return; + + }else{ + sv_cam_projection_buf.fx = svPlanePosition.fx + (tanf(cam_theta)*(fPlaneAltitude-ground_alt)); + sv_cam_projection_buf.fy = svPlanePosition.fy; + } + +#if defined(WP_CAM_POINT) + sv_cam_projection_buf.fz = waypoints[WP_CAM_POINT].a; +#else + sv_cam_projection_buf.fz = ground_alt; +#endif + + /* distance between plane and camera projection */ + vSubtractVectors(&sv_cam_projection, sv_cam_projection_buf, svPlanePosition); + + float heading_radians = RadOfDeg(90) - fYawAngle; //Convert the gps heading (radians) to standard mathematical notation. + if(heading_radians > RadOfDeg(180)){ heading_radians -= RadOfDeg(360); } + if(heading_radians < RadOfDeg(-180)){ heading_radians += RadOfDeg(360); } + //heading_radians += cam_theta; + + /* camera pan angle correction, using a clockwise rotation */ + smRotation.fx1 = (float)(cos(cam_phi)); + smRotation.fx2 = (float)(sin(cam_phi)); + smRotation.fx3 = 0.; + smRotation.fy1 = -smRotation.fx2; + smRotation.fy2 = smRotation.fx1; + smRotation.fy3 = 0.; + smRotation.fz1 = 0.; + smRotation.fz2 = 0.; + smRotation.fz3 = 1.; + + vMultiplyMatrixByVector(&sv_cam_projection_buf, smRotation, sv_cam_projection); + + /* yaw correction using a counter clockwise rotation*/ + smRotation.fx1 = (float)(cos(heading_radians)); + smRotation.fx2 = -(float)(sin(heading_radians)); + smRotation.fx3 = 0.; + smRotation.fy1 = -smRotation.fx2; + smRotation.fy2 = smRotation.fx1; + smRotation.fy3 = 0.; + smRotation.fz1 = 0.; + smRotation.fz2 = 0.; + smRotation.fz3 = 1.; + + vMultiplyMatrixByVector(&sv_cam_projection, smRotation, sv_cam_projection_buf); + +#if defined(RADIO_CAM_LOCK) + if( (float)(*fbw_state).channels[RADIO_CAM_LOCK] > MAX_PPRZ/2)) && pprz_mode == PPRZ_MODE_AUTO2){ cam_lock = TRUE; } + if( (float)(*fbw_state).channels[RADIO_CAM_LOCK] < MIN_PPRZ/2 && pprz_mode == PPRZ_MODE_AUTO2){ cam_lock = FALSE; } +#endif + // When the variable "cam_lock" is set then the last calculated position is set as the target waypoint. + if (cam_lock == FALSE){ + fObjectEast = (fPlaneEast + sv_cam_projection.fx) ; + fObjectNorth = (fPlaneNorth + sv_cam_projection.fy) ; + fAltitude = ground_alt; + memory_x = fObjectEast; + memory_y = fObjectNorth; + memory_z = fAltitude; +#if defined(WP_CAM_POINT) + waypoints[WP_CAM_POINT].x = fObjectEast; + waypoints[WP_CAM_POINT].y = fObjectNorth; + waypoints[WP_CAM_POINT].a = ground_alt; +#endif +#if defined(SHOW_CAM_COORDINATES) + cam_point_x = fObjectEast; + cam_point_y = fObjectNorth; + + cam_point_distance_from_home = distance_correction * (uint16_t) (sqrt((cam_point_x*cam_point_x) + (cam_point_y*cam_point_y) )); + + struct UtmCoor_f utm; + utm.east = gps.utm_pos.east/100. + sv_cam_projection.fx; + utm.north = gps.utm_pos.north/100. + sv_cam_projection.fy; + utm.zone = gps.utm_pos.zone; + struct LlaCoor_f lla; + lla_of_utm_f(&lla, &utm); + cam_point_lon = lla.lon*(180/M_PI); + cam_point_lat = lla.lat*(180/M_PI); +#endif + + }else{ + fObjectEast = memory_x; + fObjectNorth = memory_y; + fAltitude = memory_z; +#if defined(WP_CAM_POINT) + waypoints[WP_CAM_POINT].x = fObjectEast; + waypoints[WP_CAM_POINT].y = fObjectNorth; + waypoints[WP_CAM_POINT].a = fAltitude; +#endif + } + +if (cam_mode == CAM_MODE_RC && cam_lock == 0 ){ + *fPan = cam_phi; + *fTilt = cam_theta; + return; +} + +#if defined(WP_CAM_POINT) + else{ + waypoints[WP_CAM_POINT].x = fObjectEast; + waypoints[WP_CAM_POINT].y = fObjectNorth; + waypoints[WP_CAM_POINT].a = fAltitude; + } +#endif +/*** END OF THE CODE THAT CALCULATES THE COORDINATES OF WHERE THE CAMERA IS LOOKING AT ***/ +}else{ +/*** THE BELOW CODE IS ONLY EXECUTED IN CAM_MODE_WP_TARGET OR CAM_MODE_XY_TARGET ***/ +#ifdef SHOW_CAM_COORDINATES + cam_point_distance_from_home = distance_correction * (uint16_t) fabs( ((uint16_t) (sqrt((fObjectNorth*fObjectNorth) + (fObjectEast*fObjectEast) ))) - + ((uint16_t) (sqrt((fPlaneNorth*fPlaneNorth) + (fPlaneEast*fPlaneEast) ))) ); + + struct UtmCoor_f utm; + utm.east = nav_utm_east0 + fObjectEast; + utm.north = nav_utm_north0 + fObjectNorth; + utm.zone = gps.utm_pos.zone; + struct LlaCoor_f lla; + lla_of_utm_f(&lla, &utm); + cam_point_lon = lla.lon*(180/M_PI); + cam_point_lat = lla.lat*(180/M_PI); +#endif + + +#if defined(WP_CAM_POINT) + waypoints[WP_CAM_POINT].x = fObjectEast; + waypoints[WP_CAM_POINT].y = fObjectNorth; + waypoints[WP_CAM_POINT].a = fAltitude; +#endif + + } + +} + +//************************************************************************************************ +//************************************************************************************************ +//************************************************************************************************ +//************************************************************************************************ + +/* +By swapping coordinates (fx=fPlaneNorth, fy=fPlaneEast) we make the the circle angle go from 0 (0 is to the top of the circle) +to 360 degrees or from 0 radians to 2 PI radians in a clockwise rotation. This way the GPS reported angle can be directly +applied to the rotation matrices (in radians). +In standard mathematical notation 0 is to the right (East) of the circle, -90 is to the bottom, +-180 is to the left +and +90 is to the top (counterclockwise rotation). +When reading back the actual rotated coordinates sv_cam_projection.fx has the y coordinate and sv_cam_projection.fy has the x +represented on a circle in standard mathematical notation. +*/ svPlanePosition.fx = fPlaneNorth; svPlanePosition.fy = fPlaneEast; svPlanePosition.fz = fPlaneAltitude; @@ -270,6 +551,78 @@ void vPoint(float fPlaneEast, float fPlaneNorth, float fPlaneAltitude, /* fPan is deactivated */ *fPan = 0; +#else +#ifdef POINT_CAM_YAW_PITCH_NOSE + +/* + -45 0 45 + \ | / + \ | / + \|/ + ## + ## + _____________##______________ +left tip|_____________________________|right wing tip + ## + ## + ## + ## + ______##______ + |_____|_|_____| + | +*/ + +#if defined(CAM_PAN_MODE) && CAM_PAN_MODE == 360 + /* fixed to the plane*/ + *fPan = (float)(atan2(svObjectPositionForPlane2.fy, (svObjectPositionForPlane2.fx))); + + *fTilt = (float)(atan2( sqrt( svObjectPositionForPlane2.fx * svObjectPositionForPlane2.fx + + svObjectPositionForPlane2.fy * svObjectPositionForPlane2.fy ), + -svObjectPositionForPlane2.fz + )); + + // I need to avoid oscillations around the 180 degree mark. +/* + if (*fPan > 0 && *fPan <= RadOfDeg(175)){ heading_positive = 1; } + if (*fPan < 0 && *fPan >= RadOfDeg(-175)){ heading_positive = 0; } + + if (*fPan > RadOfDeg(175) && heading_positive == 0){ + *fPan = RadOfDeg(-180); + + }else if (*fPan < RadOfDeg(-175) && heading_positive){ + *fPan = RadOfDeg(180); + heading_positive = 0; + } +*/ +#else + *fPan = (float)(atan2(svObjectPositionForPlane2.fy, fabs(svObjectPositionForPlane2.fx))); + + *fTilt = (float)(atan2( sqrt( svObjectPositionForPlane2.fx * svObjectPositionForPlane2.fx + + svObjectPositionForPlane2.fy * svObjectPositionForPlane2.fy ), + -svObjectPositionForPlane2.fz + )); + + if (svObjectPositionForPlane2.fx < 0) + { + *fPan = -*fPan; + *fTilt = -*fTilt; + } + + // I need to avoid oscillations around the 180 degree mark. +/* + if (*fPan > 0 && *fPan <= RadOfDeg(85)){ heading_positive = 1; } + if (*fPan < 0 && *fPan >= RadOfDeg(-85)){ heading_positive = 0; } + + if (*fPan > RadOfDeg(85) && heading_positive == 0){ + *fPan = RadOfDeg(-90); + + }else if (*fPan < RadOfDeg(-85) && heading_positive){ + *fPan = RadOfDeg(90); + heading_positive = 0; + } +*/ +#endif + #else #ifdef POINT_CAM_YAW_PITCH @@ -320,7 +673,10 @@ void vPoint(float fPlaneEast, float fPlaneNorth, float fPlaneAltitude, -90 -> camera looks backwards */ /* fixed to the plane*/ - *fPan = (float)(atan2(svObjectPositionForPlane2.fx, fabs(svObjectPositionForPlane2.fy))); + *fPan = (float)(atan2(svObjectPositionForPlane2.fx, fabs(svObjectPositionForPlane2.fy)));// Or is it the opposite??? (CEF) + // (CEF) It turned out that Object_North is loaded with x and Object_East with y (reverse). See line #155 + // this means that: + // *fPan = (float)(atan2(svObjectPositionForPlane2.fy, svObjectPositionForPlane2.fy)); // makes the camera 0 to look to the nose? /* fTilt = 0 -> camera looks down 90 -> camera looks into right hemisphere @@ -376,4 +732,5 @@ void vPoint(float fPlaneEast, float fPlaneNorth, float fPlaneAltitude, #endif #endif #endif +#endif } diff --git a/sw/airborne/modules/cam_control/point.h b/sw/airborne/modules/cam_control/point.h index 3d7e6447f5..e4e9f30482 100644 --- a/sw/airborne/modules/cam_control/point.h +++ b/sw/airborne/modules/cam_control/point.h @@ -26,6 +26,12 @@ #ifndef POINT_H #define POINT_H +#if defined(SHOW_CAM_COORDINATES) +extern unsigned int cam_point_distance_from_home; +extern float cam_point_lon, cam_point_lat; +extern float distance_correction; +#endif + void vPoint(float fPlaneEast, float fPlaneNorth, float fPlaneAltitude, float fRollAngle, float fPitchAngle, float fYawAngle, float fObjectEast, float fObjectNorth, float fAltitude, diff --git a/sw/airborne/modules/digital_cam/dc.c b/sw/airborne/modules/digital_cam/dc.c index 9589bda2f5..a572f5c575 100644 --- a/sw/airborne/modules/digital_cam/dc.c +++ b/sw/airborne/modules/digital_cam/dc.c @@ -27,13 +27,27 @@ uint8_t dc_autoshoot_meter_grid = 100; uint8_t dc_autoshoot_quartersec_period = 2; dc_autoshoot_type dc_autoshoot = DC_AUTOSHOOT_STOP; +uint16_t dc_gps_count = 0; +uint8_t dc_cam_tracing = 1; +float dc_cam_angle = 0; +float dc_circle_interval = 0; +float dc_circle_start_angle = 0; +float dc_circle_last_block = 0; +float dc_circle_max_blocks = 0; +float dc_gps_dist = 0; +float dc_gps_next_dist = 0; +float dc_gps_x = 0; +float dc_gps_y = 0; + +bool_t dc_probing = FALSE; #ifdef SENSOR_SYNC_SEND uint16_t dc_photo_nr = 0; +uint16_t dc_buffer = 0; #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE @@ -44,17 +58,103 @@ uint16_t dc_photo_nr = 0; #include "estimator.h" #include "subsystems/gps.h" - void dc_send_shot_position(void) - { - int16_t phi = DegOfRad(estimator_phi*10.0f); - int16_t theta = DegOfRad(estimator_theta*10.0f); - float gps_z = ((float)gps.hmsl) / 1000.0f; - DOWNLINK_SEND_DC_SHOT(DefaultChannel, &dc_photo_nr, &gps.utm_pos.east, &gps.utm_pos.north, &gps_z, &gps.utm_pos.zone, &phi, &theta, &gps.course, &gps.gspeed, &gps.tow); +void dc_send_shot_position(void) +{ + int16_t phi = DegOfRad(estimator_phi*10.0f); + int16_t theta = DegOfRad(estimator_theta*10.0f); + float gps_z = ((float)gps.hmsl) / 1000.0f; + int16_t course = (DegOfRad(gps.course)/((int32_t)1e6)); + int16_t photo_nr = -1; + + if (dc_buffer < DC_IMAGE_BUFFER) { + dc_buffer++; dc_photo_nr++; + photo_nr = dc_photo_nr; } -#endif + DOWNLINK_SEND_DC_SHOT(DefaultChannel, + &photo_nr, + &gps.utm_pos.east, + &gps.utm_pos.north, + &gps_z, + &gps.utm_pos.zone, + &phi, + &theta, + &course, + &gps.gspeed, + &gps.tow); +} +#endif /* SENSOR_SYNC_SEND */ +uint8_t dc_info(void) { +#ifdef DOWNLINK_SEND_DC_INFO + float course = DegOfRad(estimator_psi); + DOWNLINK_SEND_DC_INFO(DefaultChannel, + &dc_autoshoot, + &estimator_x, + &estimator_y, + &course, + &dc_buffer, + &dc_gps_dist, + &dc_gps_next_dist, + &dc_gps_x, + &dc_gps_y, + &dc_circle_start_angle, + &dc_circle_interval, + &dc_circle_last_block, + &dc_gps_count, + &dc_autoshoot_quartersec_period); +#endif + return 0; +} + +/* shoot on circle */ +uint8_t dc_circle(float interval, float start) { + dc_autoshoot = DC_AUTOSHOOT_CIRCLE; + dc_gps_count = 0; + dc_circle_interval = fmodf(fmaxf(interval, 1.), 360.); + + if(start == DC_IGNORE) { + start = DegOfRad(estimator_psi); + } + + dc_circle_start_angle = fmodf(start, 360.); + if (start < 0.) + start += 360.; + //dc_circle_last_block = floorf(dc_circle_start_angle/dc_circle_interval); + dc_circle_last_block = 0; + dc_circle_max_blocks = floorf(360./dc_circle_interval); + dc_probing = TRUE; + dc_info(); + return 0; +} + +/* shoot on survey */ +uint8_t dc_survey(float interval, float x, float y) { + dc_autoshoot = DC_AUTOSHOOT_SURVEY; + dc_gps_count = 0; + dc_gps_dist = interval; + + if (x == DC_IGNORE && y == DC_IGNORE) { + dc_gps_x = estimator_x; + dc_gps_y = estimator_y; + } else if (y == DC_IGNORE) { + dc_gps_x = waypoints[(uint8_t)x].x; + dc_gps_y = waypoints[(uint8_t)x].y; + } else { + dc_gps_x = x; + dc_gps_y = y; + } + dc_gps_next_dist = interval; + dc_info(); + return 0; +} + +uint8_t dc_stop(void) { + dc_autoshoot = DC_AUTOSHOOT_STOP; + dc_info(); + return 0; +} /* @@ -89,4 +189,3 @@ static inline void dc_shoot_on_gps( void ) { } } */ - diff --git a/sw/airborne/modules/digital_cam/dc.h b/sw/airborne/modules/digital_cam/dc.h index 85170fc0a4..ac0252aef2 100644 --- a/sw/airborne/modules/digital_cam/dc.h +++ b/sw/airborne/modules/digital_cam/dc.h @@ -24,8 +24,8 @@ /** \file dc.h * \brief Standard Digital Camera Control Interface * - * -Standard IO - * -I2C Control + * -Standard IO + * -I2C Control * * Usage: (from the flight plan, the settings or any airborne code): * - dc_send_command( ) @@ -37,34 +37,65 @@ #ifndef DC_H #define DC_H +#include "float.h" #include "std.h" #include "led.h" +#include "estimator.h" +#include "subsystems/nav.h" #include "generated/airframe.h" #include "subsystems/gps.h" +/* number of images taken since the last change of dc_mode */ +extern uint16_t dc_gps_count; + +/* distance between dc shots in meters */ +extern float dc_gps_dist; + +extern float dc_gps_next_dist; + +/* angle a where first image will be taken at a + delta */ +extern float dc_circle_start_angle; + +/* angle between dc shots in degree */ +extern float dc_circle_interval; + +extern float dc_circle_max_blocks; + +/* point of reference for the distance based mode */ +extern float dc_gps_x, dc_gps_y; + +extern float dc_circle_last_block; + +extern bool_t dc_probing; + +extern uint8_t dc_buffer_timer; + +/* camera angle */ +extern float dc_cam_angle; +extern uint8_t dc_cam_tracing; /* Generic Set of Digital Camera Commands */ typedef enum { - DC_GET_STATUS = 0, + DC_GET_STATUS = 0, - DC_HOLD = 13, - DC_SHOOT = 32, + DC_HOLD = 13, + DC_SHOOT = 32, - DC_WIDER = 'w', - DC_TALLER = 't', + DC_WIDER = 'w', + DC_TALLER = 't', - DC_UP = 'u', - DC_DOWN = 'd', - DC_CENTER = 'c', - DC_LEFT = 'l', - DC_RIGHT = 'r', + DC_UP = 'u', + DC_DOWN = 'd', + DC_CENTER = 'c', + DC_LEFT = 'l', + DC_RIGHT = 'r', - DC_MENU = 'm', - DC_HOME = 'h', - DC_PLAY = 'p', + DC_MENU = 'm', + DC_HOME = 'h', + DC_PLAY = 'p', - DC_ON = 'O', - DC_OFF = 'o', + DC_ON = 'O', + DC_OFF = 'o', } dc_command_type; @@ -73,10 +104,12 @@ static inline void dc_send_command(uint8_t cmd); /* Auotmatic Digital Camera Photo Triggering */ typedef enum { - DC_AUTOSHOOT_STOP = 0, - DC_AUTOSHOOT_PERIODIC = 1, - DC_AUTOSHOOT_DISTANCE = 2, - DC_AUTOSHOOT_EXT_TRIG = 3 + DC_AUTOSHOOT_STOP = 0, + DC_AUTOSHOOT_PERIODIC = 1, + DC_AUTOSHOOT_DISTANCE = 2, + DC_AUTOSHOOT_EXT_TRIG = 3, + DC_AUTOSHOOT_SURVEY = 4, + DC_AUTOSHOOT_CIRCLE = 5 } dc_autoshoot_type; extern dc_autoshoot_type dc_autoshoot; @@ -93,9 +126,73 @@ void dc_send_shot_position(void); #define dc_send_shot_position() {} #endif +/* Macro value used to indicate a discardable argument */ +#ifndef DC_IGNORE +#define DC_IGNORE FLT_MAX +#endif + +/* Default values for buffer control */ +#ifndef DC_IMAGE_BUFFER +#define DC_IMAGE_BUFFER 255 +#endif + +#ifndef DC_IMAGE_BUFFER_TPI +#define DC_IMAGE_BUFFER_TPI 0 +#endif + /****************************************************************** * FUNCTIONS *****************************************************************/ +/** + Sets the dc control in circle mode. + The 'start' value is the reference course and 'intervall' + the minimum angle between shots. + If 'start' is 0 the current course is used instead. + + In this mode the dc control assumes a perfect circular + course. + The first picture is taken at angle start+interval. +*/ +extern uint8_t dc_circle(float interval, float start); + +#define dc_Circle(interval) dc_circle(interval, DC_IGNORE) + +/** + Sets the dc control in distance mode. + The values of 'x' and 'y' are the coordinates + of the reference point used for the distance + calculations. + If 'y' is 0 the value of 'x' is interpreted + as index of a waypoint declared in the flight plan. + If both 'x' and 'y' are 0 the current position + will be used as reference point. + + In this mode, the dc control assumes a perfect + line formed course since the distance is calculated + relative to the first given point of reference. + So not usable for circles or other comparable + shapes. +*/ +extern uint8_t dc_survey(float interval, float x, float y); + +#define dc_Survey(interval) dc_survey(interval, DC_IGNORE, DC_IGNORE) + + +/** + Sets the dc control in inactive mode, + stopping all current actions. +*/ +extern uint8_t dc_stop(void); + +#define dc_Stop(_) dc_stop() + +/** + Send an info message containing information + about position, course, buffer and all other + internal variables used by the dc control. +*/ +extern uint8_t dc_info(void); + /* get settings */ static inline void dc_init(void) @@ -108,7 +205,7 @@ static inline void dc_init(void) #endif } -/* shoot on grid */ +/* shoot on grid static inline void dc_shot_on_utm_north_close_to_100m_grid( void ) { uint32_t dist_to_100m_grid = (gps.utm_pos.north / 100) % 100; @@ -117,31 +214,83 @@ static inline void dc_shot_on_utm_north_close_to_100m_grid( void ) dc_send_command(DC_SHOOT); } } +*/ +static float dim_mod(float a, float b, float m) { + if (a < b) { + float tmp = a; + a = b; + b = tmp; + } + return fminf(a-b, b+m-a); +} /* periodic 4Hz function */ static inline void dc_periodic_4Hz( void ) { - static uint8_t dc_shutter_timer = 0; +static uint8_t dc_shutter_timer = 0; -#ifdef DC_AUTOSHOOT_QUARTERSEC_PERIOD - if (dc_autoshoot == DC_AUTOSHOOT_PERIODIC) - { - if (dc_shutter_timer) - { + switch (dc_autoshoot) { + + case DC_AUTOSHOOT_PERIODIC: + if (dc_shutter_timer) { dc_shutter_timer--; } else { - dc_send_command(DC_SHOOT); dc_shutter_timer = dc_autoshoot_quartersec_period; - } - } -#endif -#ifdef DC_AUTOSHOOT_METER_GRID - if (dc_autoshoot == DC_AUTOSHOOT_DISTANCE) + dc_send_command(DC_SHOOT); + } + break; + + case DC_AUTOSHOOT_DISTANCE: { - // Shoot - dc_shot_on_utm_north_close_to_100m_grid(); + uint32_t dist_to_100m_grid = (gps.utm_pos.north / 100) % 100; + if (dist_to_100m_grid < dc_autoshoot_meter_grid || 100 - dist_to_100m_grid < dc_autoshoot_meter_grid) + { + dc_send_command(DC_SHOOT); } -#endif + } + break; + + case DC_AUTOSHOOT_CIRCLE: { + float course = DegOfRad(estimator_psi) - dc_circle_start_angle; + if (course < 0.) + course += 360.; + float current_block = floorf(course/dc_circle_interval); + + if (dc_probing) { + if (current_block == dc_circle_last_block) { + dc_probing = FALSE; + } + } + + if (dim_mod(current_block, dc_circle_last_block, dc_circle_max_blocks) == 1) { + dc_gps_count++; + dc_circle_last_block = current_block; + dc_send_command(DC_SHOOT); + } + } + break; + + case DC_AUTOSHOOT_SURVEY : { + float dist_x = dc_gps_x - estimator_x; + float dist_y = dc_gps_y - estimator_y; + + if (dc_probing) { + if (dist_x*dist_x + dist_y*dist_y < dc_gps_dist*dc_gps_dist) { + dc_probing = FALSE; + } + } + + if (dist_x*dist_x + dist_y*dist_y >= dc_gps_next_dist*dc_gps_next_dist) { + dc_gps_next_dist += dc_gps_dist; + dc_gps_count++; + dc_send_command(DC_SHOOT); + } + } + break; + + default : + dc_autoshoot = DC_AUTOSHOOT_STOP; + } } diff --git a/sw/airborne/modules/ins/ins_module.h b/sw/airborne/modules/ins/ins_module.h index 1562cbb782..194dcb5f89 100644 --- a/sw/airborne/modules/ins/ins_module.h +++ b/sw/airborne/modules/ins/ins_module.h @@ -87,7 +87,7 @@ void parse_ins_buffer( uint8_t ); #define InsSend1(c) InsLink(Transmit(c)) #define InsUartSend1(c) InsSend1(c) #define InsSend(_dat,_len) { for (uint8_t i = 0; i< (_len); i++) InsSend1(_dat[i]); }; -#define InsUartInitParam(_a,_b,_c) InsLink(InitParam(_a,_b,_c)) +#define InsUartSetBaudrate(_b) InsLink(SetBaudrate(_b)) #define InsUartRunning InsLink(TxRunning) #endif /** !SITL */ diff --git a/sw/airborne/modules/meteo/geiger_counter.c b/sw/airborne/modules/meteo/geiger_counter.c new file mode 100644 index 0000000000..3c98c238a7 --- /dev/null +++ b/sw/airborne/modules/meteo/geiger_counter.c @@ -0,0 +1,77 @@ +/* + * $Id$ + * + * Copyright (C) 2011 Martin Mueller + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \file geiger_counter.c + * \brief I2C interface for University of Reading Geiger counter + * + */ + +#include "modules/meteo/geiger_counter.h" +#include "mcu_periph/i2c.h" +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +#ifndef GEIGER_CNT_DEV +#define GEIGER_CNT_DEV i2c0 +#endif + +#define GEIGER_CNT_I2C_ADDR 0x76 + +struct i2c_transaction geiger_trans; +uint32_t count_geiger_1, count_geiger_2; +uint16_t volt_geiger; + +void geiger_counter_init( void ) { +} + +void geiger_counter_periodic( void ) { + I2CReceive(GEIGER_CNT_DEV, geiger_trans, GEIGER_CNT_I2C_ADDR, 10); +} + +void geiger_counter_event( void ) { + if (geiger_trans.status == I2CTransSuccess) { + count_geiger_1 = (geiger_trans.buf[3] << 24) | + (geiger_trans.buf[2] << 16) | + (geiger_trans.buf[1] << 8) | + (geiger_trans.buf[0]); + count_geiger_2 = (geiger_trans.buf[7] << 24) | + (geiger_trans.buf[6] << 16) | + (geiger_trans.buf[5] << 8) | + (geiger_trans.buf[4]); + volt_geiger = (geiger_trans.buf[9] << 8) | + (geiger_trans.buf[8]); + geiger_trans.status = I2CTransDone; + + if (volt_geiger & 0x8000) { + volt_geiger &= 0x7FFF; + DOWNLINK_SEND_GEIGER_COUNTER(DefaultChannel, + &count_geiger_1, &count_geiger_2, &volt_geiger); + } + } +} diff --git a/sw/airborne/modules/meteo/geiger_counter.h b/sw/airborne/modules/meteo/geiger_counter.h new file mode 100644 index 0000000000..cbc900708d --- /dev/null +++ b/sw/airborne/modules/meteo/geiger_counter.h @@ -0,0 +1,11 @@ +#ifndef GEIGER_COUNTER_H +#define GEIGER_COUNTER_H + +#include "std.h" + +void geiger_counter_init(void); +void geiger_counter_periodic(void); +void geiger_counter_event(void); + +#endif + diff --git a/sw/airborne/modules/meteo/humid_dpicco.h b/sw/airborne/modules/meteo/humid_dpicco.h index 7272e5763e..1b95a76d0a 100644 --- a/sw/airborne/modules/meteo/humid_dpicco.h +++ b/sw/airborne/modules/meteo/humid_dpicco.h @@ -10,6 +10,8 @@ #define DPICCO_TEMP_RANGE 165.0 #define DPICCO_TEMP_OFFS -40.0 +extern float dpicco_temp; + extern void dpicco_init( void ); extern void dpicco_periodic( void ); extern void dpicco_event( void ); diff --git a/sw/airborne/modules/meteo/humid_hih.c b/sw/airborne/modules/meteo/humid_hih.c index 2e61b5ca45..6904c54d80 100644 --- a/sw/airborne/modules/meteo/humid_hih.c +++ b/sw/airborne/modules/meteo/humid_hih.c @@ -31,6 +31,8 @@ #include #include "modules/meteo/humid_hih.h" #include "modules/meteo/temp_tmp102.h" +#include "modules/meteo/humid_dpicco.h" +#include "modules/meteo/humid_sht.h" #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" #include "messages.h" @@ -58,8 +60,12 @@ void humid_hih_init( void ) { } void humid_hih_periodic( void ) { - float fvout; + float fvout, fhih_temp; + /* get temperature from external source */ + fhih_temp = ftempsht; + /****************************************/ + adc_humid_hih = buf_humid_hih.sum / buf_humid_hih.av_nb_sample; /* 36k/68k voltage divider, 3.3V full sweep, 10 bits adc */ @@ -69,8 +75,8 @@ void humid_hih_periodic( void ) { fhih_humid = ((fvout / 5.0)-0.16)/0.0062; /* temperature compensation */ - fhih_humid = fhih_humid/(1.0546 - (0.00216 * ftmp_temperature)); + fhih_humid = fhih_humid/(1.0546 - (0.00216 * fhih_temp)); - DOWNLINK_SEND_HIH_STATUS(DefaultChannel, &adc_humid_hih, &fhih_humid, &ftmp_temperature); + DOWNLINK_SEND_HIH_STATUS(DefaultChannel, &adc_humid_hih, &fhih_humid, &fhih_temp); } diff --git a/sw/airborne/modules/meteo/humid_pcap01.c b/sw/airborne/modules/meteo/humid_pcap01.c new file mode 100644 index 0000000000..345095bc3c --- /dev/null +++ b/sw/airborne/modules/meteo/humid_pcap01.c @@ -0,0 +1,263 @@ +/* + * $Id: humid_pcap01.c $ + * + * Copyright (C) 2011 Norman Wildmann, Martin Mueller + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \file humid_pcap01.c + * \brief ACAM Picocap Single-chip Solution for Capacitance Measurement + * + * This reads the values for temperature and humidity from the ACAM capacitance and resistance + * measurement unit through I2C. + */ + +#include "led.h" +#include "sys_time.h" +#include "mcu_periph/i2c.h" +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" +#include "modules/meteo/humid_pcap01.h" +#ifdef PCAP01_LOAD_FIRMWARE +#include "modules/meteo/humid_pcap01_firmware.h" +#endif + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +uint8_t pcap01_meas_started; +struct i2c_transaction pcap01_trans; +PCAP01VALUE pcap01Value; + +#ifndef PCAP01_I2C_DEV +#define PCAP01_I2C_DEV i2c0 +#endif + +void writePCAP01_SRAM(uint8_t data, uint16_t s_add) +{ + while (pcap01_trans.status == I2CTransPending); + + pcap01_trans.buf[0] = 0x90+(unsigned char)(s_add>>8); + pcap01_trans.buf[1] = (unsigned char)(s_add); + pcap01_trans.buf[2] = data; + I2CTransmit(PCAP01_I2C_DEV, pcap01_trans, PCAP01_ADDR, 3); +} + +uint8_t readPCAP01_SRAM(uint16_t s_add) +{ + while (pcap01_trans.status == I2CTransPending); + + pcap01_trans.buf[0] = 0x10+(unsigned char)(s_add>>8); + pcap01_trans.buf[1] = (unsigned char)(s_add); + I2CTransceive(PCAP01_I2C_DEV, pcap01_trans, PCAP01_ADDR, 2, 1); + while (pcap01_trans.status == I2CTransPending); + + return pcap01_trans.buf[0]; +} +/** +* \brief PCAP01_Control +* +* Function to send control commands to the PCAP01 +* +* \param control Control command +* possible commands: +* PCAP01_PU_RESET : Hard reset of the device +* PCAP01_IN_RESET : Software reset +* PCAP01_START : Start measurement +* PCAP01_START : Start measurement +* PCAP01_TERM : Stop measurement +*/ + void PCAP01_Control(uint8_t control) +{ + while (pcap01_trans.status == I2CTransPending); + + pcap01_trans.buf[0] = control; + pcap01_trans.buf[1] = 0; + pcap01_trans.buf[2] = 0; + pcap01_trans.buf[3] = 0; + I2CTransmit(PCAP01_I2C_DEV, pcap01_trans, PCAP01_ADDR, 4); +} + + void pcap01writeRegister(uint8_t reg,uint32_t value) + { + while (pcap01_trans.status == I2CTransPending); + + pcap01_trans.buf[0] = PCAP01_WRITE_REG + reg; + pcap01_trans.buf[1] = (unsigned char) (value>>16); + pcap01_trans.buf[2] = (unsigned char) (value>>8); + pcap01_trans.buf[3] = (unsigned char) (value); + I2CTransmit(PCAP01_I2C_DEV, pcap01_trans, PCAP01_ADDR, 4); + } + +#ifdef PCAP01_LOAD_FIRMWARE +void writePCAP01_firmware(void) +{ + int i = 0; + char testbyte = 44; + uint16_t testaddress = 71; + // Hard reset + PCAP01_Control(PCAP01_PU_RESET); + sys_time_usleep(50000); + //write testbyte + writePCAP01_SRAM(testbyte, testaddress); + + //check testbyte + if (readPCAP01_SRAM(testaddress) != testbyte) + return; + else + { +LED_ON(3); + //Hard reset + PCAP01_Control(PCAP01_PU_RESET); + //write firmware + for (i = 0;i< sizeof(firmware); i++) + { + writePCAP01_SRAM(firmware[i],i); + } + //fill with ffs + for (;i< 4029; i++) + { + writePCAP01_SRAM(0xff,i); + } + i++; +#ifdef PCAP01_200HZ + //write end bytes of sram + writePCAP01_SRAM(0x04,i++); + writePCAP01_SRAM(0x01,i++); + writePCAP01_SRAM(0x01,i++); +#endif +#ifdef PCAP01_STANDARD + //write end bytes of sram + writePCAP01_SRAM(0x02,i++); + writePCAP01_SRAM(0x01,i++); + writePCAP01_SRAM(0x03,i++); +#endif + } +} +#endif // PCAP01_LOAD_FIRMWARE + +void pcap01_init(void) { + pcap01_trans.status = I2CTransDone; + pcap01Value.status = PCAP01_IDLE; +#ifdef PCAP01_LOAD_FIRMWARE + writePCAP01_firmware(); +#endif + pcap01writeRegister(PCAP01_REG0, PCAP01_REG0_VALUE); + pcap01writeRegister(PCAP01_REG1, PCAP01_REG1_VALUE); + pcap01writeRegister(PCAP01_REG2, PCAP01_REG2_VALUE); + pcap01writeRegister(PCAP01_REG3, PCAP01_REG3_VALUE); + pcap01writeRegister(PCAP01_REG4, PCAP01_REG4_VALUE); + pcap01writeRegister(PCAP01_REG5, PCAP01_REG5_VALUE); + pcap01writeRegister(PCAP01_REG6, PCAP01_REG6_VALUE); + pcap01writeRegister(PCAP01_REG7, PCAP01_REG7_VALUE); + pcap01writeRegister(PCAP01_REG8, PCAP01_REG8_VALUE); + pcap01writeRegister(PCAP01_REG9, PCAP01_REG9_VALUE); + pcap01writeRegister(PCAP01_REG10, PCAP01_REG10_VALUE); + pcap01writeRegister(PCAP01_REG11, PCAP01_REG11_VALUE); + pcap01writeRegister(PCAP01_REG12, PCAP01_REG12_VALUE); + pcap01writeRegister(PCAP01_REG13, PCAP01_REG13_VALUE); + pcap01writeRegister(PCAP01_REG14, PCAP01_REG14_VALUE); + pcap01writeRegister(PCAP01_REG15, PCAP01_REG15_VALUE); + pcap01writeRegister(PCAP01_REG16, PCAP01_REG16_VALUE); + pcap01writeRegister(PCAP01_REG17, PCAP01_REG17_VALUE); + pcap01writeRegister(PCAP01_REG18, PCAP01_REG18_VALUE); + pcap01writeRegister(PCAP01_REG19, PCAP01_REG19_VALUE); + pcap01writeRegister(PCAP01_REG20, PCAP01_REG20_VALUE); + PCAP01_Control(PCAP01_IN_RESET); + sys_time_usleep(500000); + PCAP01_Control(PCAP01_START); +} + +void pcap01readRegister(uint8_t reg) + { + uint16_t byte1 = 0x40 | reg; + pcap01_trans.buf[0] = byte1; + I2CTransceive(PCAP01_I2C_DEV, pcap01_trans, PCAP01_ADDR, 1, 3); + } + +/** +* \brief pcap01_readData +* +* function where current measurement data from pcap01 is read into +* global sensor variable +* +* \param control Control command +* possible commands: +* PCAP01_PU_RESET : Hard reset of the device +* PCAP01_IN_RESET : Software reset +* PCAP01_START : Start measurement +* PCAP01_START : Start measurement +* PCAP01_TERM : Stop measurement +*/ +void pcap01_periodic(void) +{ + pcap01Value.status = PCAP01_GET_HUMID; +#ifdef PCAP01_STANDARD + pcap01readRegister(PCAP01_REG1); +#endif +#ifdef PCAP01_200HZ + pcap01readRegister(PCAP01_REG2); +#endif +} + +void pcap01_event(void) +{ + float humidity; + float temperature; + + if (pcap01_trans.status == I2CTransSuccess) { + switch (pcap01Value.status) { + + case PCAP01_GET_HUMID: + pcap01Value.C_ratio = pcap01_trans.buf[0] << 16; + pcap01Value.C_ratio |= (pcap01_trans.buf[1] << 8); + pcap01Value.C_ratio |= pcap01_trans.buf[2]; + pcap01Value.status = PCAP01_GET_TEMP; +#ifdef PCAP01_STANDARD + pcap01readRegister(PCAP01_REG13); +#endif +#ifdef PCAP01_200HZ + pcap01readRegister(PCAP01_REG3); +#endif + break; + + case PCAP01_GET_TEMP: + pcap01Value.R_ratio = pcap01_trans.buf[0] << 16; + pcap01Value.R_ratio |= (pcap01_trans.buf[1] << 8); + pcap01Value.R_ratio |= pcap01_trans.buf[2]; + humidity = pcap01Value.C_ratio * (-0.0023959245437) + 516.4124438673063; + temperature = pcap01Value.R_ratio * 61.927 - 259.74; + DOWNLINK_SEND_PCAP01_STATUS(DefaultChannel, + &pcap01Value.C_ratio, + &pcap01Value.R_ratio, + &humidity, + &temperature); + pcap01_trans.status = I2CTransDone; + pcap01Value.status = PCAP01_IDLE; + break; + + default: + pcap01_trans.status = I2CTransDone; + break; + } + } +} diff --git a/sw/airborne/modules/meteo/humid_pcap01.h b/sw/airborne/modules/meteo/humid_pcap01.h new file mode 100644 index 0000000000..0ebac83cad --- /dev/null +++ b/sw/airborne/modules/meteo/humid_pcap01.h @@ -0,0 +1,120 @@ +#ifndef PCAP01_H +#define PCAP01_H + +#include "std.h" + +//#define PCAP01_STANDARD +#define PCAP01_200HZ + +typedef struct { + uint32_t temp; + uint32_t hum_t; + uint32_t hum; + uint32_t R_ratio; + uint32_t C_ratio; + uint32_t NV_temp; + uint32_t V_rh; + uint32_t status; +}PCAP01VALUE; + +#define PCAP01_ADDR 0xA0 + +#define PCAP01_IDLE 0 +#define PCAP01_GET_HUMID 1 +#define PCAP01_GET_TEMP 2 + +//OpCodes für PCap Programmierung +#define PCAP01_PU_RESET 0x88 +#define PCAP01_IN_RESET 0x8a +#define PCAP01_START 0x8c +#define PCAP01_TERM 0x84 + +#define PCAP01_WRITE_REG 0xC0 +#define PCAP01_READ_REG 0x40 +#define PCAP01_READ_STAT 0x48 +#define PCAP01_WRITE_SRAM 0x90 +#define PCAP01_WRITE_OTP 0xA0 + +// Configuration Registers +#define PCAP01_REG0 0x00 +#define PCAP01_REG1 0x01 +#define PCAP01_REG2 0x02 +#define PCAP01_REG3 0x03 +#define PCAP01_REG4 0x04 +#define PCAP01_REG5 0x05 +#define PCAP01_REG6 0x06 +#define PCAP01_REG7 0x07 +#define PCAP01_REG8 0x08 +#define PCAP01_REG9 0x09 +#define PCAP01_REG10 0x0A +#define PCAP01_REG11 0x0B +#define PCAP01_REG12 0x0C +#define PCAP01_REG13 0x0D +#define PCAP01_REG14 0x0E +#define PCAP01_REG15 0x0F +#define PCAP01_REG16 0x10 +#define PCAP01_REG17 0x11 +#define PCAP01_REG18 0x12 +#define PCAP01_REG19 0x13 +#define PCAP01_REG20 0x14 + +#ifdef PCAP01_200HZ +// Register configuration values +#define PCAP01_REG0_VALUE 0x420F0F +#define PCAP01_REG1_VALUE 0x201004 +#define PCAP01_REG2_VALUE 0x1F460A +#define PCAP01_REG3_VALUE 0x090004 +#define PCAP01_REG4_VALUE 0x08040D +#define PCAP01_REG5_VALUE 0xC0001E +#define PCAP01_REG6_VALUE 0x000C40 +#define PCAP01_REG7_VALUE 0x1F0000 +#define PCAP01_REG8_VALUE 0x800053 +#define PCAP01_REG9_VALUE 0x00A88F +#define PCAP01_REG10_VALUE 0x18004B +#define PCAP01_REG11_VALUE 0x000000 +#define PCAP01_REG12_VALUE 0x000000 +#define PCAP01_REG13_VALUE 0x000000 +#define PCAP01_REG14_VALUE 0x000000 +#define PCAP01_REG15_VALUE 0x000000 +#define PCAP01_REG16_VALUE 0x000000 +#define PCAP01_REG17_VALUE 0x000006 +#define PCAP01_REG18_VALUE 0x0000A6 +#define PCAP01_REG19_VALUE 0x000001 +#define PCAP01_REG20_VALUE 0x000001 +#endif +#ifdef PCAP01_STANDARD +// Register configuration values +#define PCAP01_REG0_VALUE 0x4200FF +#define PCAP01_REG1_VALUE 0x201022 +#define PCAP01_REG2_VALUE 0x0F460B +#define PCAP01_REG3_VALUE 0x070010 +#define PCAP01_REG4_VALUE 0x080000 +#define PCAP01_REG5_VALUE 0x000000 +#define PCAP01_REG6_VALUE 0x000040 +#define PCAP01_REG7_VALUE 0x1F0000 +#define PCAP01_REG8_VALUE 0xA00010 +#define PCAP01_REG9_VALUE 0xFF000F +#define PCAP01_REG10_VALUE 0x180047 +#define PCAP01_REG11_VALUE 0x000000 +#define PCAP01_REG12_VALUE 0x000000 +#define PCAP01_REG13_VALUE 0x000000 +#define PCAP01_REG14_VALUE 0x000000 +#define PCAP01_REG15_VALUE 0x000000 +#define PCAP01_REG16_VALUE 0x000000 +#define PCAP01_REG17_VALUE 0x000000 +#define PCAP01_REG18_VALUE 0x000000 +#define PCAP01_REG19_VALUE 0x200000 +#define PCAP01_REG20_VALUE 0x000001 +#endif + +void writePCAP01_SRAM(uint8_t data, uint16_t s_add); +uint8_t readPCAP01_SRAM(uint16_t s_add); +void PCAP01_Control(uint8_t control); +void pcap01readRegister(uint8_t reg); +void pcap01writeRegister(uint8_t reg,uint32_t value); +void writePCAP01_firmware(void); +void pcap01_init(void); +void pcap01_periodic(void); +void pcap01_event(void); + +#endif diff --git a/sw/airborne/modules/meteo/humid_sht.h b/sw/airborne/modules/meteo/humid_sht.h index cdfbe421d0..7419aca52f 100644 --- a/sw/airborne/modules/meteo/humid_sht.h +++ b/sw/airborne/modules/meteo/humid_sht.h @@ -9,11 +9,17 @@ /* GPIO P0.x defaults */ #ifndef DAT_PIN +/* ADC1 Port, ADC_4, P0.30 */ #define DAT_PIN 30 +/* IRH Port, IRH_2, P0.25 */ +// #define DAT_PIN 25 #endif #ifndef SCK_PIN +/* ADC1 Port, ADC_3, P0.4 */ #define SCK_PIN 4 +/* IRH Port, IRH_1, P0.22 */ +// #define SCK_PIN 22 #endif #define noACK 0 diff --git a/sw/airborne/modules/meteo/humid_sht_i2c.c b/sw/airborne/modules/meteo/humid_sht_i2c.c index 3360eaa1a2..94b4e7d06e 100644 --- a/sw/airborne/modules/meteo/humid_sht_i2c.c +++ b/sw/airborne/modules/meteo/humid_sht_i2c.c @@ -49,8 +49,8 @@ struct i2c_transaction sht_trans; uint8_t sht_status; uint8_t sht_serial[8] = {0}; uint32_t sht_serial1=0, sht_serial2=0; -uint16_t humidsht, tempsht; -float fhumidsht, ftempsht; +uint16_t humidsht_i2c, tempsht_i2c; +float fhumidsht_i2c, ftempsht_i2c; int8_t humid_sht_crc(volatile uint8_t* data) { uint8_t i, bit, crc = 0; @@ -70,126 +70,126 @@ int8_t humid_sht_crc(volatile uint8_t* data) { return 0; } -void humid_sht_init(void) { - sht_status = SHT_UNINIT; +void humid_sht_init_i2c(void) { + sht_status = SHT2_UNINIT; } -void humid_sht_periodic( void ) { +void humid_sht_periodic_i2c( void ) { switch (sht_status) { - case SHT_UNINIT: + case SHT2_UNINIT: /* do soft reset, then wait at least 15ms */ - sht_status = SHT_RESET; - sht_trans.buf[0] = SHT_SOFT_RESET; + sht_status = SHT2_RESET; + sht_trans.buf[0] = SHT2_SOFT_RESET; I2CTransmit(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 1); break; - case SHT_SERIAL: + case SHT2_SERIAL: /* get serial number part 1 */ - sht_status = SHT_SERIAL1; + sht_status = SHT2_SERIAL1; sht_trans.buf[0] = 0xFA; sht_trans.buf[1] = 0x0F; I2CTransceive(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 2, 8); break; - case SHT_SERIAL1: - case SHT_SERIAL2: + case SHT2_SERIAL1: + case SHT2_SERIAL2: break; default: /* trigger temp measurement, no master hold */ - sht_trans.buf[0] = SHT_TRIGGER_TEMP; - sht_status = SHT_TRIG_TEMP; + sht_trans.buf[0] = SHT2_TRIGGER_TEMP; + sht_status = SHT2_TRIG_TEMP; I2CTransmit(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 1); /* send serial number every 30 seconds */ - RunOnceEvery((4*30), DOWNLINK_SEND_SHT_SERIAL(DefaultChannel, &sht_serial1, &sht_serial2)); + RunOnceEvery((4*30), DOWNLINK_SEND_SHT_I2C_SERIAL(DefaultChannel, &sht_serial1, &sht_serial2)); break; } } /* needs 85ms delay from temp trigger measurement */ void humid_sht_p_temp( void ) { - if (sht_status == SHT_GET_TEMP) { + if (sht_status == SHT2_GET_TEMP) { /* get temp */ - sht_status = SHT_READ_TEMP; + sht_status = SHT2_READ_TEMP; I2CReceive(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 3); } } /* needs 29ms delay from humid trigger measurement */ void humid_sht_p_humid( void ) { - if (sht_status == SHT_GET_HUMID) { + if (sht_status == SHT2_GET_HUMID) { /* read humid */ - sht_status = SHT_READ_HUMID; + sht_status = SHT2_READ_HUMID; I2CReceive(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 3); } } -void humid_sht_event( void ) { +void humid_sht_event_i2c( void ) { if (sht_trans.status == I2CTransSuccess) { switch (sht_status) { - case SHT_TRIG_TEMP: - sht_status = SHT_GET_TEMP; + case SHT2_TRIG_TEMP: + sht_status = SHT2_GET_TEMP; sht_trans.status = I2CTransDone; break; - case SHT_READ_TEMP: + case SHT2_READ_TEMP: /* read temperature */ - tempsht = (sht_trans.buf[0] << 8) | sht_trans.buf[1]; - tempsht &= 0xFFFC; + tempsht_i2c = (sht_trans.buf[0] << 8) | sht_trans.buf[1]; + tempsht_i2c &= 0xFFFC; if (humid_sht_crc(sht_trans.buf) == 0) { /* trigger humid measurement, no master hold */ - sht_trans.buf[0] = SHT_TRIGGER_HUMID; - sht_status = SHT_TRIG_HUMID; + sht_trans.buf[0] = SHT2_TRIGGER_HUMID; + sht_status = SHT2_TRIG_HUMID; I2CTransmit(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 1); } else { /* checksum error, restart */ - sht_status = SHT_IDLE; + sht_status = SHT2_IDLE; sht_trans.status == I2CTransDone; } break; - case SHT_TRIG_HUMID: - sht_status = SHT_GET_HUMID; + case SHT2_TRIG_HUMID: + sht_status = SHT2_GET_HUMID; sht_trans.status = I2CTransDone; break; - case SHT_READ_HUMID: + case SHT2_READ_HUMID: /* read humidity */ - humidsht = (sht_trans.buf[0] << 8) | sht_trans.buf[1]; - humidsht &= 0xFFFC; - fhumidsht = -6. + 125. / 65536. * humidsht; - ftempsht = -46.85 + 175.72 / 65536. * tempsht; + humidsht_i2c = (sht_trans.buf[0] << 8) | sht_trans.buf[1]; + humidsht_i2c &= 0xFFFC; + fhumidsht_i2c = -6. + 125. / 65536. * humidsht_i2c; + ftempsht_i2c = -46.85 + 175.72 / 65536. * tempsht_i2c; - sht_status = SHT_IDLE; + sht_status = SHT2_IDLE; sht_trans.status = I2CTransDone; if (humid_sht_crc(sht_trans.buf) == 0) { - DOWNLINK_SEND_SHT_STATUS(DefaultChannel, &humidsht, &tempsht, &fhumidsht, &ftempsht); + DOWNLINK_SEND_SHT_I2C_STATUS(DefaultChannel, &humidsht_i2c, &tempsht_i2c, &fhumidsht_i2c, &ftempsht_i2c); } break; - case SHT_RESET: - sht_status = SHT_SERIAL; + case SHT2_RESET: + sht_status = SHT2_SERIAL; sht_trans.status = I2CTransDone; break; - case SHT_SERIAL1: + case SHT2_SERIAL1: /* read serial number part 1 */ sht_serial[5] = sht_trans.buf[0]; sht_serial[4] = sht_trans.buf[2]; sht_serial[3] = sht_trans.buf[4]; sht_serial[2] = sht_trans.buf[6]; /* get serial number part 2 */ - sht_status = SHT_SERIAL2; + sht_status = SHT2_SERIAL2; sht_trans.buf[0] = 0xFC; sht_trans.buf[1] = 0xC9; I2CTransceive(SHT_I2C_DEV, sht_trans, SHT_SLAVE_ADDR, 2, 6); break; - case SHT_SERIAL2: + case SHT2_SERIAL2: /* read serial number part 2 */ sht_serial[1] = sht_trans.buf[0]; sht_serial[0] = sht_trans.buf[1]; @@ -197,8 +197,8 @@ void humid_sht_event( void ) { sht_serial[6] = sht_trans.buf[4]; sht_serial1=sht_serial[7]<<24|sht_serial[6]<<16|sht_serial[5]<<8|sht_serial[4]; sht_serial2=sht_serial[3]<<24|sht_serial[2]<<16|sht_serial[1]<<8|sht_serial[0]; - DOWNLINK_SEND_SHT_SERIAL(DefaultChannel, &sht_serial1, &sht_serial2); - sht_status = SHT_IDLE; + DOWNLINK_SEND_SHT_I2C_SERIAL(DefaultChannel, &sht_serial1, &sht_serial2); + sht_status = SHT2_IDLE; sht_trans.status = I2CTransDone; break; diff --git a/sw/airborne/modules/meteo/humid_sht_i2c.h b/sw/airborne/modules/meteo/humid_sht_i2c.h index 746717a607..1c26fe5f8d 100644 --- a/sw/airborne/modules/meteo/humid_sht_i2c.h +++ b/sw/airborne/modules/meteo/humid_sht_i2c.h @@ -3,37 +3,37 @@ #include "std.h" -#define SHT_WRITE_USER 0xE6 -#define SHT_READ_USER 0xE7 -#define SHT_TRIGGER_TEMP 0xF3 -#define SHT_TRIGGER_HUMID 0xF5 -#define SHT_SOFT_RESET 0xFE +#define SHT2_WRITE_USER 0xE6 +#define SHT2_READ_USER 0xE7 +#define SHT2_TRIGGER_TEMP 0xF3 +#define SHT2_TRIGGER_HUMID 0xF5 +#define SHT2_SOFT_RESET 0xFE -enum sht_stat{ - SHT_UNINIT, - SHT_IDLE, - SHT_RESET, - SHT_SERIAL, - SHT_SERIAL1, - SHT_SERIAL2, - SHT_SET_CONFIG, - SHT_READ_SERIAL, - SHT_TRIG_TEMP, - SHT_GET_TEMP, - SHT_READ_TEMP, - SHT_TRIG_HUMID, - SHT_GET_HUMID, - SHT_READ_HUMID +enum sht_stat_i2c{ + SHT2_UNINIT, + SHT2_IDLE, + SHT2_RESET, + SHT2_SERIAL, + SHT2_SERIAL1, + SHT2_SERIAL2, + SHT2_SET_CONFIG, + SHT2_READ_SERIAL, + SHT2_TRIG_TEMP, + SHT2_GET_TEMP, + SHT2_READ_TEMP, + SHT2_TRIG_HUMID, + SHT2_GET_HUMID, + SHT2_READ_HUMID }; int8_t humid_sht_crc(volatile uint8_t* data); -void humid_sht_init(void); -void humid_sht_periodic(void); +void humid_sht_init_i2c(void); +void humid_sht_periodic_i2c(void); void humid_sht_p_temp(void); void humid_sht_p_humid(void); -void humid_sht_event(void); +void humid_sht_event_i2c(void); -extern uint16_t humidsht, tempsht; -extern float fhumidsht, ftempsht; +extern uint16_t humidsht_i2c, tempsht_i2c; +extern float fhumidsht_i2c, ftempsht_i2c; #endif diff --git a/sw/airborne/modules/meteo/light_solar.c b/sw/airborne/modules/meteo/light_solar.c new file mode 100644 index 0000000000..38b20450a0 --- /dev/null +++ b/sw/airborne/modules/meteo/light_solar.c @@ -0,0 +1,80 @@ +/* + * $Id: light_solar.c $ + * + * Copyright (C) 2011 Martin Mueller + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \file light_solar.c + * \brief University of Reading solar radiation sensor interface + * + * This reads the values for intensity from the University of Reading solar sensor. + */ + + +#include "mcu_periph/adc.h" +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" +#include "modules/meteo/light_solar.h" + +#ifndef ADC_CHANNEL_LIGHT_SOLAR_UP +#define ADC_CHANNEL_LIGHT_SOLAR_UP ADC_1 +#endif +#ifndef ADC_CHANNEL_LIGHT_SOLAR_DN +#define ADC_CHANNEL_LIGHT_SOLAR_DN ADC_2 +#endif + +#ifndef ADC_CHANNEL_LIGHT_NB_SAMPLES +#define ADC_CHANNEL_LIGHT_NB_SAMPLES 16 +#endif + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +uint16_t up[LIGHT_NB], dn[LIGHT_NB]; +int32_t light_cnt; + +static struct adc_buf buf_light_sol_up; +static struct adc_buf buf_light_sol_dn; + +void light_solar_init( void ) { + adc_buf_channel(ADC_CHANNEL_LIGHT_SOLAR_UP, &buf_light_sol_up, ADC_CHANNEL_LIGHT_NB_SAMPLES); + adc_buf_channel(ADC_CHANNEL_LIGHT_SOLAR_DN, &buf_light_sol_dn, ADC_CHANNEL_LIGHT_NB_SAMPLES); + + light_cnt = 0; +} + +void light_solar_periodic( void ) { + up[light_cnt] = buf_light_sol_up.sum / buf_light_sol_up.av_nb_sample; + dn[light_cnt] = buf_light_sol_dn.sum / buf_light_sol_dn.av_nb_sample; + + /* 10k/10k voltage divider, 10 bits adc, 3.3V max */ + + if (++light_cnt >= LIGHT_NB) { + DOWNLINK_SEND_SOLAR_RADIATION(DefaultChannel, + &up[0], &dn[0], &up[1], &dn[1], &up[2], &dn[2], &up[3], &dn[3], + &up[4], &dn[4], &up[5], &dn[5], &up[6], &dn[6], &up[7], &dn[7], + &up[8], &dn[8], &up[9], &dn[9]); + light_cnt = 0; + } +} + diff --git a/sw/airborne/modules/meteo/light_solar.h b/sw/airborne/modules/meteo/light_solar.h new file mode 100644 index 0000000000..7fbcb1bd01 --- /dev/null +++ b/sw/airborne/modules/meteo/light_solar.h @@ -0,0 +1,14 @@ +#ifndef TEMP_SOLAR_H +#define TEMP_SOLAR_H + +#include "std.h" + +#define LIGHT_NB 10 + +extern uint16_t up[LIGHT_NB], dn[LIGHT_NB]; +extern int32_t light_cnt; + +void light_solar_init(void); +void light_solar_periodic(void); + +#endif diff --git a/sw/airborne/modules/meteo/temp_tcouple_adc.c b/sw/airborne/modules/meteo/temp_tcouple_adc.c new file mode 100644 index 0000000000..048f8ea826 --- /dev/null +++ b/sw/airborne/modules/meteo/temp_tcouple_adc.c @@ -0,0 +1,91 @@ +/* + * $Id: temp_tcouple_adc.c $ + * + * Copyright (C) 2011 Martin Mueller + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \file temp_tcouple_adc.c + * \brief Universitaet Tuebingen thermocouple interface + * + * This reads the values for reference and measurement temperature + * from the Universitaet Tuebingen thermocouple sensor. + */ + + +#include "mcu_periph/adc.h" +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" +#include "modules/meteo/temp_tcouple_adc.h" + +#ifndef ADC_CHANNEL_TEMP_REF +#define ADC_CHANNEL_TEMP_REF ADC_4 +#endif +#ifndef ADC_CHANNEL_TEMP_VAL +#define ADC_CHANNEL_TEMP_VAL ADC_3 +#endif + +#ifndef ADC_CHANNEL_TEMP_TCOUPLE_NB_SAMPLES +#define ADC_CHANNEL_TEMP_TCOUPLE_NB_SAMPLES 16 +#endif + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +uint16_t ref[TCOUPLE_NB], val[TCOUPLE_NB]; +float fref[TCOUPLE_NB], fval[TCOUPLE_NB]; +int32_t temp_cnt; + +static struct adc_buf buf_temp_tcouple_ref; +static struct adc_buf buf_temp_tcouple_val; + +void temp_tcouple_adc_init( void ) { + adc_buf_channel(ADC_CHANNEL_TEMP_REF, + &buf_temp_tcouple_ref, + ADC_CHANNEL_TEMP_TCOUPLE_NB_SAMPLES); + adc_buf_channel(ADC_CHANNEL_TEMP_VAL, + &buf_temp_tcouple_val, + ADC_CHANNEL_TEMP_TCOUPLE_NB_SAMPLES); + temp_cnt = 0; +} + +void temp_tcouple_adc_periodic( void ) { + val[temp_cnt] = buf_temp_tcouple_val.sum / buf_temp_tcouple_val.av_nb_sample; + ref[temp_cnt] = buf_temp_tcouple_ref.sum / buf_temp_tcouple_ref.av_nb_sample; + + /* no voltage divider, 10 bits adc, 3.3V max */ + /* T = U * 52.288899706 - 7.977784737996595 */ + fval[temp_cnt] = ((float)(val[temp_cnt] * 3.3) / 1023.) + * 52.288899706 - 7.977784737996595; + fref[temp_cnt] = ((float)(ref[temp_cnt] * 3.3) / 1023.) + * 100. - 13.; + + if (++temp_cnt >= TCOUPLE_NB) { + DOWNLINK_SEND_TEMP_TCOUPLE(DefaultChannel, + &fval[0], &fval[1], &fval[2], &fval[3], + &fref[0], &fref[1], &fref[2], &fref[3], + &val[0], &val[1], &val[2], &val[3], + &ref[0], &ref[1], &ref[2], &ref[3]); + temp_cnt = 0; + } +} + diff --git a/sw/airborne/modules/meteo/temp_tcouple_adc.h b/sw/airborne/modules/meteo/temp_tcouple_adc.h new file mode 100644 index 0000000000..95f8a1b23f --- /dev/null +++ b/sw/airborne/modules/meteo/temp_tcouple_adc.h @@ -0,0 +1,13 @@ +#ifndef TEMP_TCOUPLE_ADC_H +#define TEMP_TCOUPLE_ADC_H + +#include "std.h" + +#define TCOUPLE_NB 4 + +extern int32_t tcouple_cnt; + +void temp_tcouple_adc_init(void); +void temp_tcouple_adc_periodic(void); + +#endif diff --git a/sw/airborne/modules/sensors/AOA_adc.c b/sw/airborne/modules/sensors/AOA_adc.c new file mode 100644 index 0000000000..7c4774293e --- /dev/null +++ b/sw/airborne/modules/sensors/AOA_adc.c @@ -0,0 +1,83 @@ +/* + * Copyright (C) 2010 The Paparazzi Team + * + * Autor: Bruzzlee + * Angle of Attack ADC Sensor + * US DIGITAL MA3-A10-236-N + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#include "modules/sensors/AOA_adc.h" +#include "mcu_periph/adc.h" +#include BOARD_CONFIG +#include "generated/airframe.h" +#include "estimator.h" +#include "std.h" +//Messages +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" + +uint16_t adc_AOA_val; + +//Downlink +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +#ifndef SITL // Use ADC if not in simulation + +#ifndef ADC_CHANNEL_AOA +#error "ADC_CHANNEL_AOA needs to be defined to use AOA_adc module" +#endif + +#ifndef ADC_CHANNEL_AOA_NB_SAMPLES +#define ADC_CHANNEL_AOA_NB_SAMPLES DEFAULT_AV_NB_SAMPLE +#endif + +struct adc_buf buf_AOA; +float AOA_offset, AOA_filter; +float AOA, AOA_old; +#endif + + +void AOA_adc_init( void ) { + AOA_offset = AOA_OFFSET; + AOA_filter = AOA_FILTER; + AOA_old = 0; +#ifndef SITL + adc_buf_channel(ADC_CHANNEL_AOA, &buf_AOA, ADC_CHANNEL_AOA_NB_SAMPLES); +#endif +} + +void AOA_adc_update( void ) { +#ifndef SITL + adc_AOA_val = buf_AOA.sum / buf_AOA.av_nb_sample; + +// PT1 filter and convert to rad + AOA = AOA_filter * AOA_old + (1 - AOA_filter) * (adc_AOA_val*(2*M_PI)/1024-M_PI+AOA_offset); + AOA_old = AOA; +#endif + RunOnceEvery(30, DOWNLINK_SEND_AOA_adc(DefaultChannel, &adc_AOA_val, &AOA)); + +#ifdef USE_AOA + EstimatorSetAOA(AOA); +#endif +} diff --git a/sw/airborne/modules/sensors/AOA_adc.h b/sw/airborne/modules/sensors/AOA_adc.h new file mode 100644 index 0000000000..ae8bafbe91 --- /dev/null +++ b/sw/airborne/modules/sensors/AOA_adc.h @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2010 The Paparazzi Team + * + * Autor: Bruzzlee + * Angle of Attack ADC Sensor + * US DIGITAL MA3-A10-236-N + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#ifndef AOA_ADC_H +#define AOA_ADC_H + +#include + +extern uint16_t adc_AOA_val; +extern float AOA_offset, AOA_filter; + +void AOA_adc_init( void ); +void AOA_adc_update( void ); + +#endif /* AOA_ADC_H */ diff --git a/sw/airborne/modules/sensors/airspeed_amsys.c b/sw/airborne/modules/sensors/airspeed_amsys.c new file mode 100755 index 0000000000..7ed75a25cd --- /dev/null +++ b/sw/airborne/modules/sensors/airspeed_amsys.c @@ -0,0 +1,161 @@ +/* + * Driver for a Amsys Differential Presure Sensor I2C + * AMS 5812-0003-D + * + * Copyright (C) 2010 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "sensors/airspeed_amsys.h" +#include "estimator.h" +#include "mcu_periph/i2c.h" +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" +#include +//#include + +#ifndef USE_AIRSPEED +// Just a Warning --> We do't use it. +//#ifndef SENSOR_SYNC_SEND +//#warning either set USE_AIRSPEED or SENSOR_SYNC_SEND to use amsys_airspeed +//#endif +#endif + +#define AIRSPEED_AMSYS_ADDR 0xF4 // original F0 +#ifndef AIRSPEED_AMSYS_SCALE +#define AIRSPEED_AMSYS_SCALE 1 +#endif +#ifndef AIRSPEED_AMSYS_OFFSET +#define AIRSPEED_AMSYS_OFFSET 0 +#endif +#define AIRSPEED_AMSYS_OFFSET_MAX 29491 +#define AIRSPEED_AMSYS_OFFSET_MIN 3277 +#define AIRSPEED_AMSYS_OFFSET_NBSAMPLES_INIT 40 +#define AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG 60 +#define AIRSPEED_AMSYS_NBSAMPLES_AVRG 10 +#ifndef AIRSPEED_AMSYS_MAXPRESURE +#define AIRSPEED_AMSYS_MAXPRESURE 2068//2073 //Pascal +#endif +#ifndef AIRSPEED_AMSYS_I2C_DEV +#define AIRSPEED_AMSYS_I2C_DEV i2c0 +#endif +#ifdef MEASURE_AMSYS_TEMPERATURE +#define TEMPERATURE_AMSYS_OFFSET_MAX 29491 +#define TEMPERATURE_AMSYS_OFFSET_MIN 3277 +#define TEMPERATURE_AMSYS_MAX 110 +#define TEMPERATURE_AMSYS_MIN -25 +#endif + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +// Global variables +uint16_t airspeed_amsys_raw; +uint16_t tempAS_amsys_raw; +bool_t airspeed_amsys_valid; +float airspeed_tmp; +float pressure_amsys; //Pascal +float airspeed_amsys; //mps +float airspeed_scale; +float airspeed_filter; +struct i2c_transaction airspeed_amsys_i2c_trans; + +// Local variables +volatile bool_t airspeed_amsys_i2c_done; +float airspeed_temperature = 0.0; +float airspeed_old = 0.0; + + +void airspeed_amsys_init( void ) { + airspeed_amsys_raw = 0; + airspeed_amsys = 0.0; + pressure_amsys = 0.0; + airspeed_amsys_i2c_done = TRUE; + airspeed_amsys_valid = TRUE; + airspeed_scale = AIRSPEED_SCALE; + airspeed_filter = AIRSPEED_FILTER; + airspeed_amsys_i2c_trans.status = I2CTransDone; +} + +void airspeed_amsys_read_periodic( void ) { +#ifndef SITL + if (airspeed_amsys_i2c_trans.status == I2CTransDone) +#ifndef MEASURE_AMSYS_TEMPERATURE + I2CReceive(AIRSPEED_AMSYS_I2C_DEV, airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 2); +#else + I2CReceive(AIRSPEED_AMSYS_I2C_DEV, airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 4); +#endif + +#else // SITL + extern float sim_air_speed; + EstimatorSetAirspeed(sim_air_speed); +#endif //SITL +} + +void airspeed_amsys_read_event( void ) { + + // Get raw airspeed from buffer + airspeed_amsys_raw = 0; + airspeed_amsys_raw = (airspeed_amsys_i2c_trans.buf[0]<<8) | airspeed_amsys_i2c_trans.buf[1]; +#ifdef MEASURE_AMSYS_TEMPERATURE + tempAS_amsys_raw = (airspeed_amsys_i2c_trans.buf[2]<<8) | airspeed_amsys_i2c_trans.buf[3]; + airspeed_temperature = (float)((float)(tempAS_amsys_raw-TEMPERATURE_AMSYS_OFFSET_MIN)/((float)(TEMPERATURE_AMSYS_OFFSET_MAX-TEMPERATURE_AMSYS_OFFSET_MIN)/TEMPERATURE_AMSYS_MAX)+TEMPERATURE_AMSYS_MIN);// Tmin=-25, Tmax=85 +#endif + + // Check if this is valid airspeed + if (airspeed_amsys_raw == 0) + airspeed_amsys_valid = FALSE; + else + airspeed_amsys_valid = TRUE; + + // Continue only if a new airspeed value was received + if (airspeed_amsys_valid) { + + // raw not under offest min + if (airspeed_amsys_rawAIRSPEED_AMSYS_OFFSET_MAX) + airspeed_amsys_raw = AIRSPEED_AMSYS_OFFSET_MAX; + + // calculate raw to pressure + pressure_amsys = (float)(airspeed_amsys_raw-AIRSPEED_AMSYS_OFFSET_MIN)*AIRSPEED_AMSYS_MAXPRESURE/(float)(AIRSPEED_AMSYS_OFFSET_MAX-AIRSPEED_AMSYS_OFFSET_MIN); + + airspeed_tmp = sqrtf(2*(pressure_amsys)*airspeed_scale/1.2041); //without offset + + // Lowpass filter + airspeed_amsys = airspeed_filter * airspeed_old + (1 - airspeed_filter) * airspeed_tmp; + airspeed_old = airspeed_amsys; + +#ifdef USE_AIRSPEED + EstimatorSetAirspeed(airspeed_amsys); +#endif +#ifdef SENSOR_SYNC_SEND + DOWNLINK_SEND_AMSYS_AIRSPEED(DefaultChannel, &airspeed_amsys_raw, &pressure_amsys, &airspeed_tmp, &airspeed_amsys, &airspeed_temperature); +#else + RunOnceEvery(10, DOWNLINK_SEND_AMSYS_AIRSPEED(DefaultChannel, &airspeed_amsys_raw, &pressure_amsys, &airspeed_tmp, &airspeed_amsys, &airspeed_temperature)); +#endif + } + + // Transaction has been read + airspeed_amsys_i2c_trans.status = I2CTransDone; +} + diff --git a/sw/airborne/modules/sensors/airspeed_amsys.h b/sw/airborne/modules/sensors/airspeed_amsys.h new file mode 100755 index 0000000000..ac518b750a --- /dev/null +++ b/sw/airborne/modules/sensors/airspeed_amsys.h @@ -0,0 +1,42 @@ +/* + * Driver for a Amsys Differential Presure Sensor I2C + * AMS 5812-0003-D + * + * Copyright (C) 2010 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef AIRSPEED_AMSYS_H +#define AIRSPEED_AMSYS_H + +#include "std.h" +#include "mcu_periph/i2c.h" + +extern float airspeed_scale; +extern float airspeed_filter; + +extern struct i2c_transaction airspeed_amsys_i2c_trans; + +extern void airspeed_amsys_init( void ); +extern void airspeed_amsys_read_periodic( void ); +extern void airspeed_amsys_read_event( void ); + +#define AirspeedAmsysEvent() { if (airspeed_amsys_i2c_trans.status == I2CTransSuccess) airspeed_amsys_read_event(); } + +#endif // AIRSPEED_AMSYS_H diff --git a/sw/airborne/modules/sensors/baro_amsys.c b/sw/airborne/modules/sensors/baro_amsys.c new file mode 100755 index 0000000000..64102bc0eb --- /dev/null +++ b/sw/airborne/modules/sensors/baro_amsys.c @@ -0,0 +1,202 @@ +/* + * Driver for a Amsys Barometric Sensor I2C + * AMS 5812-0150-A + * ----measuring only--- + * + * Copyright (C) 2010 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "sensors/baro_amsys.h" +#include "mcu_periph/i2c.h" +#include "estimator.h" +#include +#include "generated/flight_plan.h" // for ground alt + +#ifdef SITL +#include "subsystems/gps.h" +#endif + +//Messages +#include "mcu_periph/uart.h" +#include "messages.h" +#include "downlink.h" +//#include "gps.h" +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +#ifdef SITL +#include "gps.h" +#endif + +#define BARO_AMSYS_ADDR 0xF2 +#define BARO_AMSYS_REG 0x07 +#define BARO_AMSYS_SCALE 0.32 +#define BARO_AMSYS_MAX_PRESSURE 103400 // Pascal +#define BARO_AMSYS_OFFSET_MAX 29491 +#define BARO_AMSYS_OFFSET_MIN 3277 +#define BARO_AMSYS_OFFSET_NBSAMPLES_INIT 40 +#define BARO_AMSYS_OFFSET_NBSAMPLES_AVRG 60 + +#ifdef MEASURE_AMSYS_TEMPERATURE +#define TEMPERATURE_AMSYS_OFFSET_MAX 29491 +#define TEMPERATURE_AMSYS_OFFSET_MIN 3277 +#define TEMPERATURE_AMSYS_MAX 110 +#define TEMPERATURE_AMSYS_MIN -25 +#endif + +//#define BARO_AMSYS_R 0.5 +//#define BARO_AMSYS_SIGMA2 0.1 +//#define BARO_ALT_CORRECTION 0.0 +#ifndef BARO_AMSYS_I2C_DEV +#define BARO_AMSYS_I2C_DEV i2c0 +#endif + +// Global variables +uint16_t pBaroRaw; +uint16_t tBaroRaw; +float baro_amsys_offset; +bool_t baro_amsys_valid; +float baro_amsys_altitude; +float baro_amsys_temp; +float baro_amsys_p; +float baro_amsys_offset_altitude; +float baro_amsys_abs_altitude; +float ref_alt_init; //Altitude by initialising +float baro_filter; +float baro_old; + +//float baro_amsys_r; +//float baro_amsys_sigma2; + + +struct i2c_transaction baro_amsys_i2c_trans; + +// Local variables +bool_t baro_amsys_offset_init; +double baro_amsys_offset_tmp; +uint16_t baro_amsys_cnt; + +void baro_amsys_init( void ) { + baro_filter=BARO_FILTER; + pBaroRaw = 0; + tBaroRaw = 0; + baro_amsys_altitude = 0.0; + baro_amsys_p=0.0; + baro_amsys_offset = 0; + baro_amsys_offset_tmp = 0; + baro_amsys_valid = TRUE; + baro_amsys_offset_init = FALSE; +// baro_amsys_enabled = TRUE; + baro_amsys_cnt = BARO_AMSYS_OFFSET_NBSAMPLES_INIT + BARO_AMSYS_OFFSET_NBSAMPLES_AVRG; +// baro_amsys_r = BARO_AMSYS_R; +// baro_amsys_sigma2 = BARO_AMSYS_SIGMA2; +// baro_head=0; + ref_alt_init = 0; + baro_amsys_i2c_trans.status = I2CTransDone; +} + +void baro_amsys_read_periodic( void ) { + // Initiate next read +#ifndef SITL + if (baro_amsys_i2c_trans.status == I2CTransDone){ +#ifndef MEASURE_AMSYS_TEMPERATURE + I2CReceive(BARO_AMSYS_I2C_DEV, baro_amsys_i2c_trans, BARO_AMSYS_ADDR, 2); +#else + I2CReceive(BARO_AMSYS_I2C_DEV, baro_amsys_i2c_trans, BARO_AMSYS_ADDR, 4); +#endif + } +#else // SITL + pBaroRaw = 0; + baro_amsys_altitude = gps.hmsl / 1000.0; + baro_amsys_valid = TRUE; + EstimatorSetAlt(baro_amsys_altitude); +#endif +} + +void baro_amsys_read_event( void ) { + pBaroRaw = 0; + // Get raw altimeter from buffer + pBaroRaw = (baro_amsys_i2c_trans.buf[0] << 8) | baro_amsys_i2c_trans.buf[1]; +#ifdef MEASURE_AMSYS_TEMPERATURE + tBaroRaw = (baro_amsys_i2c_trans.buf[2] << 8) | baro_amsys_i2c_trans.buf[3]; + baro_amsys_temp = (float)(tBaroRaw-TEMPERATURE_AMSYS_OFFSET_MIN)*TEMPERATURE_AMSYS_MAX/(float)(TEMPERATURE_AMSYS_OFFSET_MAX-TEMPERATURE_AMSYS_OFFSET_MIN)+(float)TEMPERATURE_AMSYS_MIN; +#endif + // Check if this is valid altimeter + if (pBaroRaw == 0) + baro_amsys_valid = FALSE; + else + baro_amsys_valid = TRUE; + + + // Continue only if a new altimeter value was received + //if (baro_amsys_valid && GpsFixValid()) { + if (baro_amsys_valid) { + //Cut RAW Min and Max + if (pBaroRaw < BARO_AMSYS_OFFSET_MIN) + pBaroRaw = BARO_AMSYS_OFFSET_MIN; + if (pBaroRaw > BARO_AMSYS_OFFSET_MAX) + pBaroRaw = BARO_AMSYS_OFFSET_MAX; + + //Convert to pressure + baro_amsys_p = (float)(pBaroRaw-BARO_AMSYS_OFFSET_MIN)*BARO_AMSYS_MAX_PRESSURE/(float)(BARO_AMSYS_OFFSET_MAX-BARO_AMSYS_OFFSET_MIN); + if (!baro_amsys_offset_init) { + --baro_amsys_cnt; + // Check if averaging completed + if (baro_amsys_cnt == 0) { + // Calculate average + baro_amsys_offset = (float)(baro_amsys_offset_tmp / BARO_AMSYS_OFFSET_NBSAMPLES_AVRG); + ref_alt_init = GROUND_ALT; + baro_amsys_offset_init = TRUE; + + // hight over Sea level at init point + //baro_amsys_offset_altitude = 288.15 / 0.0065 * (1 - pow((baro_amsys_p)/1013.25 , 1/5.255)); + } + // Check if averaging needs to continue + else if (baro_amsys_cnt <= BARO_AMSYS_OFFSET_NBSAMPLES_AVRG) + baro_amsys_offset_tmp += baro_amsys_p; + + baro_amsys_altitude = 0.0; + + } + else { + // Lowpassfiltering and convert pressure to altitude + baro_amsys_altitude = baro_filter * baro_old + (1 - baro_filter) * (baro_amsys_offset-baro_amsys_p)/(1.2041*9.81); + baro_old = baro_amsys_altitude; + + + //New value available + //EstimatorSetAlt(baro_amsys_abs_altitude); + } + baro_amsys_abs_altitude=baro_amsys_altitude+ref_alt_init; + } /*else { + baro_amsys_abs_altitude = 0.0; + }*/ + + + // Transaction has been read + baro_amsys_i2c_trans.status = I2CTransDone; +#ifdef SENSOR_SYNC_SEND + DOWNLINK_SEND_AMSYS_BARO(DefaultChannel, &pBaroRaw, &baro_amsys_p, &baro_amsys_offset, &ref_alt_init, &baro_amsys_abs_altitude, &baro_amsys_altitude, &baro_amsys_temp) +#else + RunOnceEvery(10, DOWNLINK_SEND_AMSYS_BARO(DefaultChannel, &pBaroRaw, &baro_amsys_p, &baro_amsys_offset, &ref_alt_init, &baro_amsys_abs_altitude, &baro_amsys_altitude, &baro_amsys_temp)); +#endif + +} diff --git a/sw/airborne/modules/sensors/baro_amsys.h b/sw/airborne/modules/sensors/baro_amsys.h new file mode 100755 index 0000000000..9e0884944d --- /dev/null +++ b/sw/airborne/modules/sensors/baro_amsys.h @@ -0,0 +1,51 @@ +/* + * Driver for a Amsys Barometric Sensor I2C + * AMS 5812-0150-A + * + * Copyright (C) 2010 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef BARO_AMSYS_H +#define BARO_AMSYS_H + +#include "std.h" +#include "mcu_periph/i2c.h" + +#define BARO_AMSYS_DT 0.05 + +// extern uint16_t baro_amsys_adc; +// extern float baro_amsys_offset; +// extern bool_t baro_amsys_valid; +// extern bool_t baro_amsys_updated; +// extern bool_t baro_amsys_enabled; +extern float baro_amsys_altitude; +// extern float baro_amsys_r; +// extern float baro_amsys_sigma2; +extern float baro_filter; + +extern struct i2c_transaction baro_amsys_i2c_trans; + +extern void baro_amsys_init( void ); +extern void baro_amsys_read_periodic( void ); +extern void baro_amsys_read_event( void ); + +#define BaroAmsysEvent() { if (baro_amsys_i2c_trans.status == I2CTransSuccess) baro_amsys_read_event(); } + +#endif // BARO_AMSYS_H diff --git a/sw/airborne/modules/sensors/baro_bmp.c b/sw/airborne/modules/sensors/baro_bmp.c index cb28db06c1..0aa51e660f 100644 --- a/sw/airborne/modules/sensors/baro_bmp.c +++ b/sw/airborne/modules/sensors/baro_bmp.c @@ -130,7 +130,7 @@ void baro_bmp_event( void ) { /* get uncompensated pressure, oss=3 */ bmp_up = (bmp_trans.buf[0] << 11) | (bmp_trans.buf[1] << 3) | - bmp_trans.buf[2]; + (bmp_trans.buf[2] >> 5); /* start temp measurement */ bmp_trans.buf[0] = BMP085_CTRL_REG; bmp_trans.buf[1] = BMP085_START_TEMP; @@ -157,7 +157,7 @@ void baro_bmp_event( void ) { if (bmp_b7 < 0x80000000) bmp_p = (bmp_b7 * 2) / bmp_b4; else - bmp_p = (bmp_b7 * bmp_b4) * 2; + bmp_p = (bmp_b7 / bmp_b4) * 2; bmp_x1 = (bmp_p / (1<<8)) * (bmp_p / (1<<8)); bmp_x1 = (bmp_x1 * 3038) / (1<<16); bmp_x2 = (-7357 * bmp_p) / (1<<16); @@ -166,7 +166,7 @@ void baro_bmp_event( void ) { baro_bmp_temperature = bmp_t; baro_bmp_pressure = bmp_p; #ifdef SENSOR_SYNC_SEND - DOWNLINK_SEND_BMP_STATUS(DefaultChannel, &bmp_p, &bmp_t); + DOWNLINK_SEND_BMP_STATUS(DefaultChannel, &bmp_up, &bmp_ut, &bmp_p, &bmp_t); #endif } } diff --git a/sw/airborne/modules/ins/ins_ppzuavimu.c b/sw/airborne/modules/sensors/imu_ppzuav.c similarity index 98% rename from sw/airborne/modules/ins/ins_ppzuavimu.c rename to sw/airborne/modules/sensors/imu_ppzuav.c index be8bf19f3b..ba8b137cc8 100644 --- a/sw/airborne/modules/ins/ins_ppzuavimu.c +++ b/sw/airborne/modules/sensors/imu_ppzuav.c @@ -19,10 +19,13 @@ */ #include -#include "ins_ppzuavimu.h" +#include "imu_ppzuav.h" #include "mcu_periph/i2c.h" #include "led.h" +// Set SPI_CS High +#include "mcu_periph/gpio_arch.h" + // Downlink #include "mcu_periph/uart.h" #include "messages.h" @@ -60,6 +63,8 @@ struct Imu imu; void imu_impl_init(void) { + GPIO_ARCH_SET_SPI_CS_HIGH(); + ///////////////////////////////////////////////////////////////////// // ITG3200 ppzuavimu_itg3200.type = I2CTransTx; diff --git a/sw/airborne/modules/ins/ins_ppzuavimu.h b/sw/airborne/modules/sensors/imu_ppzuav.h similarity index 100% rename from sw/airborne/modules/ins/ins_ppzuavimu.h rename to sw/airborne/modules/sensors/imu_ppzuav.h diff --git a/sw/airborne/obsolete/3dmg.c b/sw/airborne/obsolete/3dmg.c index 589dcc14e8..32fa008c47 100644 --- a/sw/airborne/obsolete/3dmg.c +++ b/sw/airborne/obsolete/3dmg.c @@ -40,7 +40,7 @@ void _3dmg_set_continuous_mode ( void ) { uint8_t msg[REQ_CONT_LEN] = { 0x10, 0x00, 0x31, 0x00, 0x41}; uint8_t i; for (i=0; i DegOfRad(300)) { - Vector_Scale(Omega_I,Omega_I,0.5f*DegOfRad(300)/Integrator_magnitude); + if (Integrator_magnitude > RadOfDeg(300)) { + Vector_Scale(Omega_I,Omega_I,0.5f*RadOfDeg(300)/Integrator_magnitude); } diff --git a/sw/airborne/subsystems/gps.h b/sw/airborne/subsystems/gps.h index 21a30c6bb1..2d46b16c0d 100644 --- a/sw/airborne/subsystems/gps.h +++ b/sw/airborne/subsystems/gps.h @@ -38,6 +38,7 @@ #endif #define GPS_FIX_NONE 0x00 +#define GPS_FIX_2D 0x02 #define GPS_FIX_3D 0x03 #define GpsFixValid() (gps.fix == GPS_FIX_3D) @@ -78,6 +79,7 @@ struct GpsState { uint8_t nb_channels; ///< Number of scanned satellites struct SVinfo svinfos[GPS_NB_CHANNELS]; + uint32_t last_fix_ticks; ///< cpu time in ticks at last valid fix uint16_t last_fix_time; ///< cpu time in sec at last valid fix uint16_t reset; ///< hotstart, warmstart, coldstart }; diff --git a/sw/airborne/subsystems/gps/gps_mtk.c b/sw/airborne/subsystems/gps/gps_mtk.c new file mode 100644 index 0000000000..812521670c --- /dev/null +++ b/sw/airborne/subsystems/gps/gps_mtk.c @@ -0,0 +1,401 @@ +/* + * Copyright (C) 2011 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** @file gps_mtk.h + * @brief Mediatek MT3329 specific code + * + * supports: + * DIYDrones V1.4 protocol (AXN1.30_2278) + * DIYDrones V1.6 protocol (AXN1.30_2389) + * + * documentation is partly incorrect, see mtk.xml for what seems + * to be "real" + * + */ + +#include "subsystems/gps.h" + +#include "led.h" + +#include "subsystems/nav.h" +#include "math/pprz_geodetic_float.h" +#include "sys_time.h" + +#define MTK_DIY_OUTPUT_RATE MTK_DIY_OUTPUT_4HZ +#define OUTPUT_RATE 4 + +/* parser status */ +#define UNINIT 0 +#define GOT_SYNC1_14 1 +#define GOT_SYNC2_14 2 +#define GOT_CLASS_14 3 +#define GOT_SYNC1_16 4 +#define GOT_SYNC2_16 5 +#define GOT_ID 6 +#define GOT_PAYLOAD 7 +#define GOT_CHECKSUM1 8 + +/* last error type */ +#define GPS_MTK_ERR_NONE 0 +#define GPS_MTK_ERR_OVERRUN 1 +#define GPS_MTK_ERR_MSG_TOO_LONG 2 +#define GPS_MTK_ERR_CHECKSUM 3 +#define GPS_MTK_ERR_UNEXPECTED 4 +#define GPS_MTK_ERR_OUT_OF_SYNC 5 + +/* defines for UTC-GPS time conversion */ +#define SECS_MINUTE (60) +#define SECS_HOUR (60*60) +#define SECS_DAY (60*60*24) +#define SECS_WEEK (60*60*24*7) + +#define isleap(x) ((((x)%400)==0) || (!(((x)%100)==0) && (((x)%4)==0))) + +const int8_t DAYS_MONTH[12] = { 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }; + +struct GpsMtk gps_mtk; + +#ifdef GPS_CONFIGURE +bool_t gps_configuring; +static uint8_t gps_status_config; +#endif + +void gps_impl_init(void) { + gps_mtk.status = UNINIT; + gps_mtk.msg_available = FALSE; + gps_mtk.error_cnt = 0; + gps_mtk.error_last = GPS_MTK_ERR_NONE; +#ifdef GPS_CONFIGURE + gps_status_config = 0; + gps_configuring = TRUE; +#endif +} + +static void gps_mtk_time2itow(uint32_t gps_date, uint32_t gps_time, + int16_t* gps_week, uint32_t* gps_itow) { + /* convert UTC date/time to GPS week/itow, we have no idea about GPS + leap seconds for now */ + uint16_t gps_msecond = gps_time % 1000; + uint8_t gps_second = (gps_time / 1000) % 100; + uint8_t gps_minute = (gps_time / 100000) % 100; + uint8_t gps_hour = (gps_time / 10000000) % 100; + uint16_t gps_year = 2000 + (gps_date % 100); + uint8_t gps_month = (gps_date / 100) % 100; + uint8_t gps_day = (gps_date / 10000) % 100; + int32_t i, days; + + *gps_week = 0; + *gps_itow = 0; + + /* sanity checks */ + if (gps_month > 12) return; + if (gps_day > (DAYS_MONTH[gps_month] + + ((gps_month == 1) ? isleap(gps_year):0))) return; + if (gps_hour > 23) return; + if (gps_minute > 59) return; + if (gps_second > 59) return; + + /* days since 6-JAN-1980 */ + days = -6; + for (i = 1980; i < gps_year; i++) days += (365 + isleap(i)); + + /* add days in gps_year */ + for (i = 0; i < gps_month-1; i++) { + days += DAYS_MONTH[i] + ((i == 1) ? isleap(gps_year):0); + } + days += gps_day; + + /* convert */ + *gps_week = (uint16_t) (days / 7); + *gps_itow = ((days % 7) * SECS_DAY + + gps_hour * SECS_HOUR + + gps_minute * SECS_MINUTE + + gps_second) * 1000 + + gps_msecond; +} + +void gps_mtk_read_message(void) { + if (gps_mtk.msg_class == MTK_DIY14_ID) { + if (gps_mtk.msg_id == MTK_DIY14_NAV_ID) { +#ifdef GPS_TIMESTAMP + /* get hardware clock ticks */ + SysTimeTimerStart(gps.t0); + gps.t0_tow = MTK_DIY14_NAV_ITOW(gps_mtk.msg_buf); + gps.t0_tow_frac = 0; +#endif + gps.lla_pos.lat = RadOfDeg(MTK_DIY14_NAV_LAT(gps_mtk.msg_buf))*10; + gps.lla_pos.lon = RadOfDeg(MTK_DIY14_NAV_LON(gps_mtk.msg_buf))*10; + // FIXME: with MTK you do not receive vertical speed + if (cpu_time_sec - gps.last_fix_time < 2) { + gps.ned_vel.z = ((gps.hmsl - + MTK_DIY14_NAV_HEIGHT(gps_mtk.msg_buf)*10)*OUTPUT_RATE)/10; + } else gps.ned_vel.z = 0; + gps.hmsl = MTK_DIY14_NAV_HEIGHT(gps_mtk.msg_buf)*10; + // FIXME: with MTK you do not receive ellipsoid altitude + gps.lla_pos.alt = gps.hmsl; + gps.gspeed = MTK_DIY14_NAV_GSpeed(gps_mtk.msg_buf); + // FIXME: with MTK you do not receive speed 3D + gps.speed_3d = gps.gspeed; + gps.course = (RadOfDeg(MTK_DIY14_NAV_Heading(gps_mtk.msg_buf)))*10; + gps.num_sv = MTK_DIY14_NAV_numSV(gps_mtk.msg_buf); + switch (MTK_DIY14_NAV_GPSfix(gps_mtk.msg_buf)) { + case MTK_DIY_FIX_3D: + gps.fix = GPS_FIX_3D; + break; + case MTK_DIY_FIX_2D: + gps.fix = GPS_FIX_2D; + break; + default: + gps.fix = GPS_FIX_NONE; + } + gps.tow = MTK_DIY14_NAV_ITOW(gps_mtk.msg_buf);; + // FIXME: with MTK DIY 1.4 you do not receive GPS week + gps.week = 0; + /* Computes from (lat, long) in the referenced UTM zone */ + struct LlaCoor_f lla_f; + lla_f.lat = ((float) gps.lla_pos.lat) / 1e7; + lla_f.lon = ((float) gps.lla_pos.lon) / 1e7; + struct UtmCoor_f utm_f; + utm_f.zone = nav_utm_zone0; + /* convert to utm */ + utm_of_lla_f(&utm_f, &lla_f); + /* copy results of utm conversion */ + gps.utm_pos.east = utm_f.east*100; + gps.utm_pos.north = utm_f.north*100; + gps.utm_pos.alt = utm_f.alt*1000; + gps.utm_pos.zone = nav_utm_zone0; +#ifdef GPS_LED + if (gps.fix == GPS_FIX_3D) { + LED_ON(GPS_LED); + } + else { + LED_TOGGLE(GPS_LED); + } +#endif + } + } + + if (gps_mtk.msg_class == MTK_DIY16_ID) { + if (gps_mtk.msg_id == MTK_DIY16_NAV_ID) { + uint32_t gps_date, gps_time; + gps_date = MTK_DIY16_NAV_UTC_DATE(gps_mtk.msg_buf); + gps_time = MTK_DIY16_NAV_UTC_TIME(gps_mtk.msg_buf); + gps_mtk_time2itow(gps_date, gps_time, &gps.week, &gps.tow); +#ifdef GPS_TIMESTAMP + /* get hardware clock ticks */ + SysTimeTimerStart(gps.t0); + gps.t0_tow = gps.tow; + gps.t0_tow_frac = 0; +#endif + gps.lla_pos.lat = RadOfDeg(MTK_DIY16_NAV_LAT(gps_mtk.msg_buf))*10; + gps.lla_pos.lon = RadOfDeg(MTK_DIY16_NAV_LON(gps_mtk.msg_buf))*10; + // FIXME: with MTK you do not receive vertical speed + if (cpu_time_sec - gps.last_fix_time < 2) { + gps.ned_vel.z = ((gps.hmsl - + MTK_DIY16_NAV_HEIGHT(gps_mtk.msg_buf)*10)*OUTPUT_RATE)/10; + } else gps.ned_vel.z = 0; + gps.hmsl = MTK_DIY16_NAV_HEIGHT(gps_mtk.msg_buf)*10; + // FIXME: with MTK you do not receive ellipsoid altitude + gps.lla_pos.alt = gps.hmsl; + gps.gspeed = MTK_DIY16_NAV_GSpeed(gps_mtk.msg_buf); + // FIXME: with MTK you do not receive speed 3D + gps.speed_3d = gps.gspeed; + gps.course = (RadOfDeg(MTK_DIY16_NAV_Heading(gps_mtk.msg_buf)*10000)) * 10; + gps.num_sv = MTK_DIY16_NAV_numSV(gps_mtk.msg_buf); + switch (MTK_DIY16_NAV_GPSfix(gps_mtk.msg_buf)) { + case MTK_DIY_FIX_3D: + gps.fix = GPS_FIX_3D; + break; + case MTK_DIY_FIX_2D: + gps.fix = GPS_FIX_2D; + break; + default: + gps.fix = GPS_FIX_NONE; + } + /* HDOP? */ + /* Computes from (lat, long) in the referenced UTM zone */ + struct LlaCoor_f lla_f; + lla_f.lat = ((float) gps.lla_pos.lat) / 1e7; + lla_f.lon = ((float) gps.lla_pos.lon) / 1e7; + struct UtmCoor_f utm_f; + utm_f.zone = nav_utm_zone0; + /* convert to utm */ + utm_of_lla_f(&utm_f, &lla_f); + /* copy results of utm conversion */ + gps.utm_pos.east = utm_f.east*100; + gps.utm_pos.north = utm_f.north*100; + gps.utm_pos.alt = utm_f.alt*1000; + gps.utm_pos.zone = nav_utm_zone0; +#ifdef GPS_LED + if (gps.fix == GPS_FIX_3D) { + LED_ON(GPS_LED); + } + else { + LED_TOGGLE(GPS_LED); + } +#endif + } + } +} + +/* byte parsing */ +void gps_mtk_parse( uint8_t c ) { + if (gps_mtk.status < GOT_PAYLOAD) { + gps_mtk.ck_a += c; + gps_mtk.ck_b += gps_mtk.ck_a; + } + switch (gps_mtk.status) { + case UNINIT: + if (c == MTK_DIY14_SYNC1) + gps_mtk.status = GOT_SYNC1_14; + if (c == MTK_DIY16_ID) + gps_mtk.msg_class = c; + gps_mtk.status = GOT_SYNC1_16; + break; + /* MTK_DIY_VER_14 */ + case GOT_SYNC1_14: + if (c != MTK_DIY14_SYNC2) { + gps_mtk.error_last = GPS_MTK_ERR_OUT_OF_SYNC; + goto error; + } + if (gps_mtk.msg_available) { + /* Previous message has not yet been parsed: discard this one */ + gps_mtk.error_last = GPS_MTK_ERR_OVERRUN; + goto error; + } + gps_mtk.ck_a = 0; + gps_mtk.ck_b = 0; + gps_mtk.status++; + gps_mtk.len = MTK_DIY14_NAV_LENGTH; + break; + case GOT_SYNC2_14: + if (c != MTK_DIY14_ID) { + gps_mtk.error_last = GPS_MTK_ERR_OUT_OF_SYNC; + goto error; + } + gps_mtk.msg_class = c; + gps_mtk.msg_idx = 0; + gps_mtk.status++; + break; + case GOT_CLASS_14: + if (c != MTK_DIY14_NAV_ID) { + gps_mtk.error_last = GPS_MTK_ERR_OUT_OF_SYNC; + goto error; + } + gps_mtk.msg_id = c; + gps_mtk.status = GOT_ID; + break; + /* MTK_DIY_VER_16 */ + case GOT_SYNC1_16: + if (c != MTK_DIY16_NAV_ID) { + gps_mtk.error_last = GPS_MTK_ERR_OUT_OF_SYNC; + goto error; + } + if (gps_mtk.msg_available) { + /* Previous message has not yet been parsed: discard this one */ + gps_mtk.error_last = GPS_MTK_ERR_OVERRUN; + goto error; + } + gps_mtk.msg_id = c; + gps_mtk.ck_a = 0; + gps_mtk.ck_b = 0; + gps_mtk.status++; + break; + case GOT_SYNC2_16: + gps_mtk.len = c; + gps_mtk.msg_idx = 0; + gps_mtk.status = GOT_ID; + break; + case GOT_ID: + gps_mtk.msg_buf[gps_mtk.msg_idx] = c; + gps_mtk.msg_idx++; + if (gps_mtk.msg_idx >= gps_mtk.len) { + gps_mtk.status++; + } + break; + case GOT_PAYLOAD: + if (c != gps_mtk.ck_a) { + gps_mtk.error_last = GPS_MTK_ERR_CHECKSUM; + goto error; + } + gps_mtk.status++; + break; + case GOT_CHECKSUM1: + if (c != gps_mtk.ck_b) { + gps_mtk.error_last = GPS_MTK_ERR_CHECKSUM; + goto error; + } + gps_mtk.msg_available = TRUE; + goto restart; + break; + default: + gps_mtk.error_last = GPS_MTK_ERR_UNEXPECTED; + goto error; + } + return; + error: + gps_mtk.error_cnt++; + restart: + gps_mtk.status = UNINIT; + return; +} + + +/* + * + * + * GPS dynamic configuration + * + * + */ +#ifdef GPS_CONFIGURE + +static void MtkSend_CFG(char* dat) { + while (*dat != 0) GpsLink(Transmit(*dat++)); +} + +void gps_configure_uart(void) { +} + +#ifdef USER_GPS_CONFIGURE +#include USER_GPS_CONFIGURE +#else +static bool_t user_gps_configure(bool_t cpt) { + switch (cpt) { + case 0: + MtkSend_CFG(MTK_DIY_SET_BINARY); + break; + case 1: + MtkSend_CFG(MTK_DIY_OUTPUT_RATE); + return FALSE; + } + return TRUE; /* Continue, except for the last case */ +} +#endif // ! USER_GPS_CONFIGURE + +void gps_configure( void ) { + static uint32_t count=0; + /* start configuring after having received 50 bytes */ + if (count++ > 50) + gps_configuring = user_gps_configure(gps_status_config++); +} + +#endif /* GPS_CONFIGURE */ diff --git a/sw/airborne/subsystems/gps/gps_mtk.h b/sw/airborne/subsystems/gps/gps_mtk.h new file mode 100644 index 0000000000..c467778afa --- /dev/null +++ b/sw/airborne/subsystems/gps/gps_mtk.h @@ -0,0 +1,137 @@ +/* + * Copyright (C) 2011 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + + +#ifndef MTK_H +#define MTK_H + +#include "mcu_periph/uart.h" + +/** Includes macros generated from mtk.xml */ +#include "mtk_protocol.h" + +#define GPS_MTK_MAX_PAYLOAD 255 + +struct GpsMtk { + bool_t msg_available; + uint8_t msg_buf[GPS_MTK_MAX_PAYLOAD] __attribute__ ((aligned)); + uint8_t msg_id; + uint8_t msg_class; + + uint8_t status; + uint16_t len; + uint8_t msg_idx; + uint8_t ck_a, ck_b; + uint8_t send_ck_a, send_ck_b; + uint8_t error_cnt; + uint8_t error_last; + + uint8_t status_flags; + uint8_t sol_flags; +}; + +extern struct GpsMtk gps_mtk; + + +/* + * This part is used by the autopilot to read data from a uart + */ +#define __GpsLink(dev, _x) dev##_x +#define _GpsLink(dev, _x) __GpsLink(dev, _x) +#define GpsLink(_x) _GpsLink(GPS_LINK, _x) + +#define GpsBuffer() GpsLink(ChAvailable()) + +#ifdef GPS_CONFIGURE +extern bool_t gps_configuring; +#define GpsConfigure() { \ + if (gps_configuring) \ + gps_configure(); \ + } +#else +#define GpsConfigure() {} +#endif + +#define GpsEvent(_sol_available_callback) { \ + if (GpsBuffer()) { \ + ReadGpsBuffer(); \ + GpsConfigure(); \ + } \ + if (gps_mtk.msg_available) { \ + gps_mtk_read_message(); \ + if (gps_mtk.msg_class == MTK_DIY14_ID && \ + gps_mtk.msg_id == MTK_DIY14_NAV_ID) { \ + if (gps.fix == GPS_FIX_3D) { \ + gps.last_fix_time = cpu_time_sec; \ + } \ + _sol_available_callback(); \ + } \ + if (gps_mtk.msg_class == MTK_DIY16_ID && \ + gps_mtk.msg_id == MTK_DIY16_NAV_ID) { \ + if (gps.fix == GPS_FIX_3D) { \ + gps.last_fix_ticks = cpu_time_ticks; \ + gps.last_fix_time = cpu_time_sec; \ + } \ + _sol_available_callback(); \ + } \ + gps_mtk.msg_available = FALSE; \ + } \ + } + +#define ReadGpsBuffer() { \ + while (GpsLink(ChAvailable())&&!gps_mtk.msg_available) \ + gps_mtk_parse(GpsLink(Getch())); \ + } + + +extern void gps_mtk_read_message(void); +extern void gps_mtk_parse(uint8_t c); + +#define MTK_DIY_FIX_3D 3 +#define MTK_DIY_FIX_2D 2 +#define MTK_DIY_FIX_NONE 1 + +/* + * dynamic GPS configuration + */ +#ifdef GPS_CONFIGURE +#define MTK_DIY_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n" +#define MTK_DIY_SET_NMEA "$PGCMD,16,1,1,1,1,1*6B\r\n" + +#define MTK_DIY_OUTPUT_1HZ "$PMTK220,1000*1F\r\n" +#define MTK_DIY_OUTPUT_2HZ "$PMTK220,500*2B\r\n" +#define MTK_DIY_OUTPUT_4HZ "$PMTK220,250*29\r\n" +#define MTK_DIY_OTUPUT_5HZ "$PMTK220,200*2C\r\n" +#define MTK_DIY_OUTPUT_10HZ "$PMTK220,100*2F\r\n" + +#define MTK_BAUD_RATE_38400 "$PMTK251,38400*27\r\n" + +#define MTK_DIY_SBAS_ON "$PMTK313,1*2E\r\n" +#define MTK_DIY_SBAS_OFF "$PMTK313,0*2F\r\n" + +#define MTK_DIY_WAAS_ON "$PSRF151,1*3F\r\n" +#define MTK_DIY_WAAS_OFF "$PSRF151,0*3E\r\n" + +extern void gps_configure(void); +extern void gps_configure_uart(void); +#endif + +#endif /* MTK_H */ diff --git a/sw/airborne/subsystems/gps/gps_nmea.h b/sw/airborne/subsystems/gps/gps_nmea.h index 3e330915ff..a1d4059a2c 100644 --- a/sw/airborne/subsystems/gps/gps_nmea.h +++ b/sw/airborne/subsystems/gps/gps_nmea.h @@ -69,6 +69,7 @@ extern struct GpsNmea gps_nmea; nmea_parse_msg(); \ if (gps_nmea.pos_available) { \ if (gps.fix == GPS_FIX_3D) { \ + gps.last_fix_ticks = cpu_time_ticks; \ gps.last_fix_time = cpu_time_sec; \ } \ _sol_available_callback(); \ diff --git a/sw/airborne/subsystems/gps/gps_skytraq.h b/sw/airborne/subsystems/gps/gps_skytraq.h index fea8398af0..ed435db45d 100644 --- a/sw/airborne/subsystems/gps/gps_skytraq.h +++ b/sw/airborne/subsystems/gps/gps_skytraq.h @@ -96,6 +96,7 @@ extern struct GpsSkytraq gps_skytraq; gps_skytraq_read_message(); \ if (gps_skytraq.msg_id == SKYTRAQ_ID_NAVIGATION_DATA) { \ if (gps.fix == GPS_FIX_3D) \ + gps.last_fix_ticks = cpu_time_ticks; \ gps.last_fix_time = cpu_time_sec; \ _sol_available_callback(); \ } \ diff --git a/sw/airborne/subsystems/gps/gps_ubx.c b/sw/airborne/subsystems/gps/gps_ubx.c index 6a8d3fd61c..2c09d4908a 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.c +++ b/sw/airborne/subsystems/gps/gps_ubx.c @@ -93,6 +93,7 @@ void gps_impl_init(void) { gps_status_config = 0; gps_configuring = TRUE; #endif + gps_ubx.have_velned = 0; } @@ -172,6 +173,7 @@ void gps_ubx_read_message(void) { // First x 10 for loosing less resolution, then to radians, then multiply x 10 again gps.course = (RadOfDeg(UBX_NAV_VELNED_Heading(gps_ubx.msg_buf)*10)) * 10; gps.tow = UBX_NAV_VELNED_ITOW(gps_ubx.msg_buf); + gps_ubx.have_velned = 1; } else if (gps_ubx.msg_id == UBX_NAV_SVINFO_ID) { gps.nb_channels = Min(UBX_NAV_SVINFO_NCH(gps_ubx.msg_buf), GPS_NB_CHANNELS); diff --git a/sw/airborne/subsystems/gps/gps_ubx.h b/sw/airborne/subsystems/gps/gps_ubx.h index 46b8b9567b..14e84e4411 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.h +++ b/sw/airborne/subsystems/gps/gps_ubx.h @@ -51,6 +51,7 @@ struct GpsUbx { uint8_t status_flags; uint8_t sol_flags; + uint8_t have_velned; }; extern struct GpsUbx gps_ubx; @@ -89,8 +90,10 @@ extern bool_t gps_configuring; GpsParseOrConfigure(); \ if (gps_ubx.msg_class == UBX_NAV_ID && \ (gps_ubx.msg_id == UBX_NAV_VELNED_ID || \ - gps_ubx.msg_id == UBX_NAV_SOL_ID)) { \ + (gps_ubx.msg_id == UBX_NAV_SOL_ID && \ + gps_ubx.have_velned == 0))) { \ if (gps.fix == GPS_FIX_3D) { \ + gps.last_fix_ticks = cpu_time_ticks; \ gps.last_fix_time = cpu_time_sec; \ } \ _sol_available_callback(); \ diff --git a/sw/airborne/subsystems/imu/imu_aspirin.h b/sw/airborne/subsystems/imu/imu_aspirin.h index 60a54b49e3..f14a8f0bc7 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin.h +++ b/sw/airborne/subsystems/imu/imu_aspirin.h @@ -79,7 +79,7 @@ extern struct ImuAspirin imu_aspirin; #define foo_handler() {} #define ImuMagEvent(_mag_handler) { \ - MagEvent(foo_handler); \ + MagEvent(foo_handler); \ if (hmc5843.data_available) { \ imu.mag_unscaled.x = hmc5843.data.value[IMU_MAG_X_CHAN]; \ imu.mag_unscaled.y = hmc5843.data.value[IMU_MAG_Y_CHAN]; \ @@ -92,7 +92,7 @@ extern struct ImuAspirin imu_aspirin; /* underlying architecture */ #include "subsystems/imu/imu_aspirin_arch.h" /* must be implemented by underlying architecture */ -extern void imu_b2_arch_init(void); +extern void imu_aspirin_arch_init(void); static inline void gyro_read_i2c(void) { @@ -134,7 +134,7 @@ static inline void imu_aspirin_event(void (* _gyro_handler)(void), void (* _acce _accel_handler(); } imu_aspirin_arch_int_enable(); - + // Reset everything if we've been waiting too long if (imu_aspirin.time_since_last_reading > ASPIRIN_GYRO_TIMEOUT) { i2c2_er_irq_handler(); @@ -144,7 +144,7 @@ static inline void imu_aspirin_event(void (* _gyro_handler)(void), void (* _acce } // Try again later if transaction is in progress - if (imu_aspirin.i2c_trans_gyro.status == I2CTransPending || imu_aspirin.i2c_trans_gyro.status == I2CTransRunning) + if (imu_aspirin.i2c_trans_gyro.status == I2CTransPending || imu_aspirin.i2c_trans_gyro.status == I2CTransRunning) { return; } diff --git a/sw/airborne/subsystems/navigation/poly_survey_adv.c b/sw/airborne/subsystems/navigation/poly_survey_adv.c index b56ff6f579..0edfc465b7 100644 --- a/sw/airborne/subsystems/navigation/poly_survey_adv.c +++ b/sw/airborne/subsystems/navigation/poly_survey_adv.c @@ -4,7 +4,10 @@ #include "estimator.h" #include "autopilot.h" #include "generated/flight_plan.h" -//#include "modules/digital_cam/dc.h" + +#ifdef DIGITAL_CAM +#include "modules/digital_cam/dc.h" +#endif /** @@ -108,41 +111,41 @@ static bool_t get_two_intersects(point2d *x, point2d *y, point2d a, point2d b) point2d tmp; for (i=0;i fabs(dir_vec.y)) { - if ((y->x - x->x) / dir_vec.x < 0.0){ - tmp = *x; - *x = *y; - *y = tmp; - } + if ((y->x - x->x) / dir_vec.x < 0.0){ + tmp = *x; + *x = *y; + *y = tmp; + } } else - if ((y->y - x->y) / dir_vec.y < 0.0) { - tmp = *x; - *x = *y; - *y = tmp; - } + if ((y->y - x->y) / dir_vec.y < 0.0) { + tmp = *x; + *x = *y; + *y = tmp; + } return TRUE; } @@ -179,32 +182,32 @@ bool_t init_poly_survey_adv(uint8_t first_wp, uint8_t size, float angle, float s if (return_angle > 359) return_angle -= 360; if (angle <= 45.0 || angle >= 315.0) { - //north - dir_vec.y = 1.0; - dir_vec.x = 1.0*tanf(angle_rad); - sweep.x = 1.0; - sweep.y = - dir_vec.x / dir_vec.y; + //north + dir_vec.y = 1.0; + dir_vec.x = 1.0*tanf(angle_rad); + sweep.x = 1.0; + sweep.y = - dir_vec.x / dir_vec.y; } else if (angle <= 135.0) { - //east - dir_vec.x = 1.0; - dir_vec.y = 1.0/tanf(angle_rad); - sweep.y = - 1.0; - sweep.x = dir_vec.y / dir_vec.x; + //east + dir_vec.x = 1.0; + dir_vec.y = 1.0/tanf(angle_rad); + sweep.y = - 1.0; + sweep.x = dir_vec.y / dir_vec.x; } else if (angle <= 225.0) { - //south - dir_vec.y = -1.0; - dir_vec.x = -1.0*tanf(angle_rad); - sweep.x = -1.0; - sweep.y = dir_vec.x / dir_vec.y; + //south + dir_vec.y = -1.0; + dir_vec.x = -1.0*tanf(angle_rad); + sweep.x = -1.0; + sweep.y = dir_vec.x / dir_vec.y; } else { - //west - dir_vec.x = -1.0; - dir_vec.y = -1.0/tanf(angle_rad); - sweep.y = 1.0; - sweep.x = - dir_vec.y / dir_vec.x; + //west + dir_vec.x = -1.0; + dir_vec.y = -1.0/tanf(angle_rad); + sweep.y = 1.0; + sweep.x = - dir_vec.y / dir_vec.x; } //normalize @@ -225,18 +228,18 @@ bool_t init_poly_survey_adv(uint8_t first_wp, uint8_t size, float angle, float s //cacluate the leftmost point if one sees the dir vec as going "up" and the sweep vec as going right if (div < 0.0) { - for(i=1;i 0.0) { - small.x = waypoints[poly_first+i].x; - small.y = waypoints[poly_first+i].y; - } + for(i=1;i 0.0) { + small.x = waypoints[poly_first+i].x; + small.y = waypoints[poly_first+i].y; + } } else - for(i=1;i 0.0) { - small.x = waypoints[poly_first+i].x; - small.y = waypoints[poly_first+i].y; - } + for(i=1;i 0.0) { + small.x = waypoints[poly_first+i].x; + small.y = waypoints[poly_first+i].y; + } //calculate the line the defines the first flyover seg_start.x = small.x + 0.5*sweep_vec.x; @@ -244,8 +247,8 @@ bool_t init_poly_survey_adv(uint8_t first_wp, uint8_t size, float angle, float s VEC_CALC(seg_end, seg_start, dir_vec, +); if (!get_two_intersects(&seg_start, &seg_end, seg_start, seg_end)) { - psa_stage = ERR; - return FALSE; + psa_stage = ERR; + return FALSE; } //center of the entry circle @@ -270,62 +273,68 @@ bool_t poly_survey_adv(void) { //entry circle around entry-center until the desired altitude is reached if (psa_stage == ENTRY) { - nav_circle_XY(entry_center.x, entry_center.y, -psa_min_rad); - if (NavCourseCloseTo(segment_angle) - && nav_approaching_xy(seg_start.x, seg_start.y, last_x, last_y, CARROT) - && fabs(estimator_z - psa_altitude) <= 20) { - psa_stage = SEG; - NavVerticalAutoThrottleMode(0.0); - nav_init_stage(); - //dc_distance(psa_shot_dist, seg_start.x - dir_vec.x*psa_shot_dist*0.5, seg_start.y - dir_vec.y*psa_shot_dist*0.5); - } + nav_circle_XY(entry_center.x, entry_center.y, -psa_min_rad); + if (NavCourseCloseTo(segment_angle) + && nav_approaching_xy(seg_start.x, seg_start.y, last_x, last_y, CARROT) + && fabs(estimator_z - psa_altitude) <= 20) { + psa_stage = SEG; + NavVerticalAutoThrottleMode(0.0); + nav_init_stage(); +#ifdef DIGITAL_CAM + dc_survey(psa_shot_dist, seg_start.x - dir_vec.x*psa_shot_dist*0.5, seg_start.y - dir_vec.y*psa_shot_dist*0.5); +#endif + } } //fly the segment until seg_end is reached if (psa_stage == SEG) { - nav_points(seg_start, seg_end); - //calculate all needed points for the next flyover - if (nav_approaching_xy(seg_end.x, seg_end.y, seg_start.x, seg_start.y, 0)) { - //dc_stop(); - VEC_CALC(seg_center1, seg_end, rad_vec, -); - ret_start.x = seg_end.x - 2*rad_vec.x; - ret_start.y = seg_end.y - 2*rad_vec.y; + nav_points(seg_start, seg_end); + //calculate all needed points for the next flyover + if (nav_approaching_xy(seg_end.x, seg_end.y, seg_start.x, seg_start.y, 0)) { +#ifdef DIGITAL_CAM + dc_stop(); +#endif + VEC_CALC(seg_center1, seg_end, rad_vec, -); + ret_start.x = seg_end.x - 2*rad_vec.x; + ret_start.y = seg_end.y - 2*rad_vec.y; - //if we get no intersection the survey is finished - if (!get_two_intersects(&seg_start, &seg_end, vec_add(seg_start, sweep_vec), vec_add(seg_end, sweep_vec))) - return FALSE; + //if we get no intersection the survey is finished + if (!get_two_intersects(&seg_start, &seg_end, vec_add(seg_start, sweep_vec), vec_add(seg_end, sweep_vec))) + return FALSE; - ret_end.x = seg_start.x - sweep_vec.x - 2*rad_vec.x; - ret_end.y = seg_start.y - sweep_vec.y - 2*rad_vec.y; + ret_end.x = seg_start.x - sweep_vec.x - 2*rad_vec.x; + ret_end.y = seg_start.y - sweep_vec.y - 2*rad_vec.y; - seg_center2.x = seg_start.x - 0.5*(2.0*rad_vec.x+sweep_vec.x); - seg_center2.y = seg_start.y - 0.5*(2.0*rad_vec.y+sweep_vec.y); + seg_center2.x = seg_start.x - 0.5*(2.0*rad_vec.x+sweep_vec.x); + seg_center2.y = seg_start.y - 0.5*(2.0*rad_vec.y+sweep_vec.y); - psa_stage = TURN1; - nav_init_stage(); - } + psa_stage = TURN1; + nav_init_stage(); + } } //turn from stage to return else if (psa_stage == TURN1) { - nav_circle_XY(seg_center1.x, seg_center1.y, -psa_min_rad); - if (NavCourseCloseTo(return_angle)) { - psa_stage = RET; - nav_init_stage(); - } - //return + nav_circle_XY(seg_center1.x, seg_center1.y, -psa_min_rad); + if (NavCourseCloseTo(return_angle)) { + psa_stage = RET; + nav_init_stage(); + } + //return } else if (psa_stage == RET) { - nav_points(ret_start, ret_end); - if (nav_approaching_xy(ret_end.x, ret_end.y, ret_start.x, ret_start.y, 0)) { - psa_stage = TURN2; - nav_init_stage(); - } - //turn from return to stage + nav_points(ret_start, ret_end); + if (nav_approaching_xy(ret_end.x, ret_end.y, ret_start.x, ret_start.y, 0)) { + psa_stage = TURN2; + nav_init_stage(); + } + //turn from return to stage } else if (psa_stage == TURN2) { - nav_circle_XY(seg_center2.x, seg_center2.y, -(2*psa_min_rad+psa_sweep_width)*0.5); - if (NavCourseCloseTo(segment_angle)) { - psa_stage = SEG; - nav_init_stage(); - //dc_distance(psa_shot_dist, seg_start.x - dir_vec.x*psa_shot_dist*0.5, seg_start.y - dir_vec.y*psa_shot_dist*0.5); - } + nav_circle_XY(seg_center2.x, seg_center2.y, -(2*psa_min_rad+psa_sweep_width)*0.5); + if (NavCourseCloseTo(segment_angle)) { + psa_stage = SEG; + nav_init_stage(); +#ifdef DIGITAL_CAM + dc_survey(psa_shot_dist, seg_start.x - dir_vec.x*psa_shot_dist*0.5, seg_start.y - dir_vec.y*psa_shot_dist*0.5); +#endif + } } return TRUE; diff --git a/sw/airborne/subsystems/navigation/spiral.c b/sw/airborne/subsystems/navigation/spiral.c index 219e778603..e05b26df5e 100644 --- a/sw/airborne/subsystems/navigation/spiral.c +++ b/sw/airborne/subsystems/navigation/spiral.c @@ -12,7 +12,10 @@ #include "estimator.h" #include "autopilot.h" #include "generated/flight_plan.h" -//#include "modules/digital_cam/dc.h" + +#ifdef DIGITAL_CAM +#include "modules/digital_cam/dc.h" +#endif enum SpiralStatus { Outside, StartCircle, Circle, IncSpiral }; static enum SpiralStatus CSpiralStatus; @@ -37,7 +40,6 @@ static float SRad; static float IRad; static float Alphalimit; static float Segmente; -// static float CamAngle; static float ZPoint; static float nav_radius_min; @@ -68,11 +70,11 @@ bool_t InitializeSpiral(uint8_t CenterWP, uint8_t EdgeWP, float StartRad, float DistanceFromCenter = sqrt(TransCurrentX*TransCurrentX+TransCurrentY*TransCurrentY); // SpiralTheta = atan2(TransCurrentY,TransCurrentX); - // Fly2X = Spiralradius*cos(SpiralTheta+3.14)+WaypointX(Center); - // Fly2Y = Spiralradius*sin(SpiralTheta+3.14)+WaypointY(Center); + // Fly2X = Spiralradius*cos(SpiralTheta+M_PI)+WaypointX(Center); + // Fly2Y = Spiralradius*sin(SpiralTheta+M_PI)+WaypointY(Center); // Alphalimit denotes angle, where the radius will be increased - Alphalimit = 2*3.14 / Segments; + Alphalimit = 2*M_PI / Segments; //current position FlyFromX = estimator_x; FlyFromY = estimator_y; @@ -103,7 +105,9 @@ bool_t SpiralNav(void) // center reached? if (nav_approaching_xy(WaypointX(Center), WaypointY(Center), FlyFromX, FlyFromY, 0)) { // nadir image - //dc_shutter(); +#ifdef DIGITAL_CAM + dc_send_command(DC_SHOOT); +#endif CSpiralStatus = StartCircle; } break; @@ -117,7 +121,9 @@ bool_t SpiralNav(void) LastCircleY = estimator_y; CSpiralStatus = Circle; // Start helix - //dc_Circle(360/Segmente); +#ifdef DIGITAL_CAM + dc_Circle(360/Segmente); +#endif } break; case Circle: { @@ -143,17 +149,20 @@ bool_t SpiralNav(void) if(SRad + IRad < Spiralradius) { SRad = SRad + IRad; - /*if (dc_cam_tracing) { - // calculating Camwinkel for camera alignment +#ifdef DIGITAL_CAM + if (dc_cam_tracing) { + // calculating Cam angle for camera alignment TransCurrentZ = estimator_z - ZPoint; - CamAngle = atan(SRad/TransCurrentZ) * 180 / 3.14; - //dc_cam_angle = CamAngle; - }*/ + dc_cam_angle = atan(SRad/TransCurrentZ) * 180 / M_PI; + } +#endif } else { SRad = Spiralradius; +#ifdef DIGITAL_CAM // Stopps DC - //dc_stop(); + dc_stop(); +#endif } CSpiralStatus = Circle; break; diff --git a/sw/airborne/subsystems/settings.c b/sw/airborne/subsystems/settings.c index 04754e2ead..3f8447efb7 100644 --- a/sw/airborne/subsystems/settings.c +++ b/sw/airborne/subsystems/settings.c @@ -7,15 +7,16 @@ bool_t settings_store_now; void settings_init(void) { #ifdef USE_PERSISTENT_SETTINGS - if (persistent_read((uint32_t)&pers_settings, sizeof(struct PersistentSettings))) + if (persistent_read((uint32_t)&pers_settings, sizeof(struct PersistentSettings))) return; // return -1 ? - persitent_settings_load(); + persistent_settings_load(); #endif } void settings_store(void) { - persitent_settings_store(); +#ifdef USE_PERSISTENT_SETTINGS + persistent_settings_store(); persistent_write((uint32_t)&pers_settings, sizeof(struct PersistentSettings)); +#endif } - diff --git a/sw/ground_segment/cockpit/speech.ml b/sw/ground_segment/cockpit/speech.ml index 124d90986b..ddce7617e6 100644 --- a/sw/ground_segment/cockpit/speech.ml +++ b/sw/ground_segment/cockpit/speech.ml @@ -1,38 +1,39 @@ +(* + * $Id$ + * + * Speech support for GCS alerts + * + * Copyright (C) 2011 + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + *) + let active = ref false -let current_os = ref "not_set" - -(* These two functions are from sw/lib/defivybus.ml *) -let read_process_output command = - let buffer_size = 2048 in - let buffer = Buffer.create buffer_size in - let string = String.create buffer_size in - let in_channel = Unix.open_process_in command in - let chars_read = ref 1 in - while !chars_read <> 0 do - chars_read := input in_channel string 0 buffer_size; - Buffer.add_substring buffer string 0 !chars_read - done; - ignore (Unix.close_process_in in_channel); - Buffer.contents buffer - -let contains s substring = - try ignore (Str.search_forward (Str.regexp_string substring) s 0); true - with Not_found -> false - let say = fun s -> - ( if !active then ( - (* Checks if the os is known and gets the uname if not *) - if contains !current_os "not_set" then ( - current_os := read_process_output "uname"; - ); - (* If the os is Darwin, then use "say" *) - if contains !current_os "Darwin" then ( - ignore (Sys.command (Printf.sprintf "say '%s'&" s)); - ) - (* If the os is anything else, use "spd-say" (add additional cases here if necessary) *) - else ( - ignore (Sys.command (Printf.sprintf "spd-say '%s'&" s)); - ) - ));; + let os = (Os_calls.os_name) in + match os with + (* If the os is Darwin, then use "say" *) + "Linux" -> ignore (Sys.command (Printf.sprintf "spd-say '%s'&" s)) + (* If the os is Linux, use "spd-say" *) + | "Darwin" -> ignore (Sys.command (Printf.sprintf "say '%s'&" s)) + (* Add more cases here to enhance support *) + | _ -> ignore (Sys.command (Printf.sprintf "echo Current OS not supported by -speech option")) + ) diff --git a/sw/lib/ocaml/Makefile b/sw/lib/ocaml/Makefile index d403f96eec..24a8a92e10 100644 --- a/sw/lib/ocaml/Makefile +++ b/sw/lib/ocaml/Makefile @@ -39,7 +39,7 @@ OCAMLYACC=ocamlyacc OCAMLLIBDIR=$(shell ocamlc -where) -SRC = fig.ml debug.ml base64.ml serial.ml ocaml_tools.ml expr_syntax.ml expr_parser.ml expr_lexer.ml extXml.ml env.ml xml2h.ml latlong.ml egm96.ml srtm.ml http.ml gm.ml iGN.ml geometry_2d.ml cserial.o convert.o ubx.ml pprz.ml xbee.ml logpprz.ml xmlCom.ml editAirframe.ml defivybus.ml +SRC = fig.ml debug.ml base64.ml serial.ml ocaml_tools.ml expr_syntax.ml expr_parser.ml expr_lexer.ml extXml.ml env.ml xml2h.ml latlong.ml egm96.ml srtm.ml http.ml maps_support.ml gm.ml iGN.ml geometry_2d.ml cserial.o convert.o ubx.ml pprz.ml xbee.ml logpprz.ml xmlCom.ml os_calls.ml editAirframe.ml defivybus.ml CMO = $(SRC:.ml=.cmo) CMX = $(SRC:.ml=.cmx) diff --git a/sw/lib/ocaml/defivybus.ml b/sw/lib/ocaml/defivybus.ml index 56ed92608a..86fe47a8cb 100644 --- a/sw/lib/ocaml/defivybus.ml +++ b/sw/lib/ocaml/defivybus.ml @@ -23,29 +23,10 @@ * Boston, MA 02111-1307, USA. * *) - -let read_process_output command = - let buffer_size = 2048 in - let buffer = Buffer.create buffer_size in - let string = String.create buffer_size in - let in_channel = Unix.open_process_in command in - let chars_read = ref 1 in - while !chars_read <> 0 do - chars_read := input in_channel string 0 buffer_size; - Buffer.add_substring buffer string 0 !chars_read - done; - ignore (Unix.close_process_in in_channel); - Buffer.contents buffer - -let contains s substring = - try ignore (Str.search_forward (Str.regexp_string substring) s 0); true - with Not_found -> false - let default_ivy_bus = String.copy ( try (Sys.getenv "IVY_BUS" ) with Not_found -> - (if contains (read_process_output "uname") "Darwin" then + (if Os_calls.contains (Os_calls.os_name) "Darwin" then "224.255.255.255:2010" else - "127.255.255.255:2010")) - + "127.255.255.255:2010")) diff --git a/sw/lib/ocaml/gm.ml b/sw/lib/ocaml/gm.ml index aeed0df518..327644d264 100644 --- a/sw/lib/ocaml/gm.ml +++ b/sw/lib/ocaml/gm.ml @@ -196,7 +196,7 @@ let ms_key = fun key -> done; (ms_key, ms_key.[n-2]) -let google_version = 87 +let google_version = Maps_support.google_version let url_of_tile_key = fun maps_source s -> let (x, y, z) = xyz_of_qsrt s in diff --git a/sw/lib/ocaml/maps_support.ml b/sw/lib/ocaml/maps_support.ml new file mode 100644 index 0000000000..9e1dbc5652 --- /dev/null +++ b/sw/lib/ocaml/maps_support.ml @@ -0,0 +1,38 @@ +(* + * $Id$ + * + * Support for obtaining google maps api information at runtime + * + * Copyright (C) 2011 Stephen Dwyer + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + *) +let google_ver = ref 0 + +let home = Env.paparazzi_home +let (//) = Filename.concat +let maps_xml_path = home // "conf" // "maps.xml" + +let maps_xml = ExtXml.parse_file maps_xml_path + +let google_version = ( + if !google_ver == 0 then ( + google_ver := ExtXml.int_attrib maps_xml "google_version" ); + !google_ver + ) diff --git a/sw/lib/ocaml/maps_support.mli b/sw/lib/ocaml/maps_support.mli new file mode 100644 index 0000000000..f822cd9828 --- /dev/null +++ b/sw/lib/ocaml/maps_support.mli @@ -0,0 +1 @@ +val google_version : int diff --git a/sw/lib/ocaml/os_calls.ml b/sw/lib/ocaml/os_calls.ml new file mode 100644 index 0000000000..5255d96ba4 --- /dev/null +++ b/sw/lib/ocaml/os_calls.ml @@ -0,0 +1,50 @@ +(* + * $Id$ + * + * Support for obtaining os specific information at runtime + * + * Copyright (C) 2011 Eric Parsonage and Stephen Dwyer + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + *) +let current_os = ref "not_set" + +let read_process_output command = + let buffer_size = 2048 in + let buffer = Buffer.create buffer_size in + let string = String.create buffer_size in + let in_channel = Unix.open_process_in command in + let chars_read = ref 1 in + while !chars_read <> 0 do + chars_read := input in_channel string 0 buffer_size; + Buffer.add_substring buffer string 0 !chars_read + done; + ignore (Unix.close_process_in in_channel); + try Buffer.sub buffer 0 ((Buffer.length buffer) - 1) + with _ -> Buffer.contents buffer + +let contains s substring = + try ignore (Str.search_forward (Str.regexp_string substring) s 0); true + with Not_found -> false + +let os_name = String.copy ( + if contains !current_os "not_set" then ( + current_os := read_process_output "uname" ); + !current_os + ) diff --git a/sw/lib/ocaml/os_calls.mli b/sw/lib/ocaml/os_calls.mli new file mode 100644 index 0000000000..3aa9819f00 --- /dev/null +++ b/sw/lib/ocaml/os_calls.mli @@ -0,0 +1,2 @@ +val contains : string -> string -> bool +val os_name : string diff --git a/sw/logalizer/Makefile b/sw/logalizer/Makefile index 4768fac813..01dd11580b 100644 --- a/sw/logalizer/Makefile +++ b/sw/logalizer/Makefile @@ -27,7 +27,7 @@ OCAMLC = ocamlc OCAMLOPT = ocamlopt INCLUDES= $(shell ocamlfind query -r -i-format xml-light) $(shell ocamlfind query -r -i-format lablgtk2) -I ../lib/ocaml -all: play plotter plot sd2log +all: play plotter plot sd2log plotprofile play : log_file.cmo play_core.cmo play.cmo @echo OL $@ @@ -105,6 +105,9 @@ MORE_CFLAGS = -DHAVE_DLFCN_H=1 -DSTDC_HEADERS=1 -I. -I. -I.. -g -O2 -I/usr/ disp3d: disp3d.c $(CC) $(MORE_CFLAGS) -g -o $@ $^ $(MORE_FLAGS) +plotprofile: plotprofile.c + gcc -g -O2 -Wall `pkg-config glib-2.0 --cflags` -o $@ $^ `pkg-config glib-2.0 --libs` `pcre-config --libs` -lglibivy + test1: test1.c $(CC) $(MORE_CFLAGS) -g -o $@ $^ $(MORE_FLAGS) -lglut diff --git a/sw/logalizer/plotprofile.c b/sw/logalizer/plotprofile.c new file mode 100644 index 0000000000..39f0cdcf2a --- /dev/null +++ b/sw/logalizer/plotprofile.c @@ -0,0 +1,138 @@ + +/* + +http://users.softlab.ntua.gr/~ttsiod/gnuplotStreaming.html + +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define HEIGHT_SPAN 20000 + +FILE *Gplt, *Gplh; +int32_t alt = 0; +int32_t temp[HEIGHT_SPAN] = {0}; +int32_t humid[HEIGHT_SPAN] = {0}; + +void on_GPS(IvyClientPtr app, void *user_data, int argc, char *argv[]){ +/* + + + + + + + + + + + + + + +7.73 11 GPS 0 55577549 665183336 0 -4310 0 0 1642 345957748 31 0 +*/ + + int32_t _alt; + + _alt = atoi(argv[5]); + alt = _alt / 100; +// if ((_alt/100) < HEIGHT_SPAN) alt = _alt; + +// printf("alt %f\n", (float) _alt/100.); +} + +void on_TMP_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]){ +/* + + + + +*/ + + float _temp; + int i; + + _temp = atof(argv[2]); + if (alt < HEIGHT_SPAN) temp[alt] = _temp * 100; + +// printf("temp %f\n", _temp); + fprintf(Gplt, "plot '-' w points pt 0 title \"Temp\"\n"); + for (i = 0; i < HEIGHT_SPAN; i++){ + if (temp[i] != 0) fprintf(Gplt, "%f %d\n", temp[i]/100., i); + } + fprintf(Gplt,"e\n"); +} + +void on_SHT_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]){ +/* + + + + + + +*/ + + float _humid; + int i; + + _humid = atof(argv[3]); + if (alt < HEIGHT_SPAN) humid[alt] = _humid * 100; + +// printf("humid %f\n", _humid); + fprintf(Gplh, "plot '-' w points pt 0 title \"Humid\"\n"); + for (i = 0; i < HEIGHT_SPAN; i++){ + if (humid[i] != 0) fprintf(Gplh, "%f %d\n", humid[i]/100., i); + } + fprintf(Gplh,"e\n"); +} + +int main( int argc, char* argv[] ) +{ + double xmint, xmaxt, xminh, xmaxh, ymin, ymax; + GMainLoop *ml; + + ml = g_main_loop_new(NULL, FALSE); + + IvyInit ("IvyPlotProfile", "IvyPlotProfile READY", NULL, NULL, NULL, NULL); + IvyBindMsg(on_GPS, NULL, "^(\\S*) GPS (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); + IvyBindMsg(on_TMP_STATUS, NULL, "^(\\S*) TMP_STATUS (\\S*) (\\S*)"); + IvyBindMsg(on_SHT_STATUS, NULL, "^(\\S*) SHT_STATUS (\\S*) (\\S*) (\\S*) (\\S*)"); +// IvyBindMsg(on_SHT_STATUS, NULL, "^(\\S*) DPICCO_STATUS (\\S*) (\\S*) (\\S*) (\\S*)"); + IvyStart("127.255.255.255"); + + xmint = 5; + xmaxt = 35; + xminh = 0; + xmaxh = 100; + ymin = 500; + ymax = 2300; + + Gplt = popen("gnuplot -geometry 300x300 -noraise","w"); + setlinebuf(Gplt); + fprintf(Gplt, "set xrange[%f:%f]\n", xmint, xmaxt); + fprintf(Gplt, "set yrange[%f:%f]\n", ymin, ymax); + + Gplh = popen("gnuplot -geometry 300x300 -noraise","w"); + setlinebuf(Gplh); + fprintf(Gplh, "set xrange[%f:%f]\n", xminh, xmaxh); + fprintf(Gplh, "set yrange[%f:%f]\n", ymin, ymax); + + g_main_loop_run(ml); + + fclose(Gplt); + fclose(Gplh); + return 0; +} diff --git a/sw/simulator/sim_ac_jsbsim.c b/sw/simulator/sim_ac_jsbsim.c index 55f66a17a8..a72840fd36 100644 --- a/sw/simulator/sim_ac_jsbsim.c +++ b/sw/simulator/sim_ac_jsbsim.c @@ -57,7 +57,11 @@ static void sim_parse_options(int argc, char** argv); static void sim_init(void); static gboolean sim_periodic(gpointer data); +#ifdef __APPLE__ +string ivyBus = "224.255.255.255"; +#else string ivyBus = "127.255.255.255"; +#endif string fgAddress = "127.0.0.1"; static void ivy_transport_init(void); diff --git a/sw/supervision/pc_aircraft.ml b/sw/supervision/pc_aircraft.ml index 97d54c82a8..585af46b47 100644 --- a/sw/supervision/pc_aircraft.ml +++ b/sw/supervision/pc_aircraft.ml @@ -84,7 +84,12 @@ let parse_conf_xml = fun vbox -> Gtk_tools.combo ("" :: !strings) vbox let editor = - try Sys.getenv "EDITOR" with _ -> "gedit" + try Sys.getenv "EDITOR" with _ -> ( + if Os_calls.contains (Os_calls.os_name) "Darwin" then + "open" + else + "gedit" + ) let edit = fun file -> ignore (Sys.command (sprintf "%s %s&" editor file)) diff --git a/sw/supervision/pc_common.ml b/sw/supervision/pc_common.ml index e0ef23c6c8..b4ba138bb1 100644 --- a/sw/supervision/pc_common.ml +++ b/sw/supervision/pc_common.ml @@ -2,7 +2,7 @@ * $Id$ * * Paparazzi center utilities - * + * * Copyright (C) 2007 ENAC, Pascal Brisset, Antoine Drouin * * This file is part of paparazzi. @@ -20,7 +20,7 @@ * You should have received a copy of the GNU General Public License * along with paparazzi; see the file COPYING. If not, write to * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. + * Boston, MA 02111-1307, USA. * *) @@ -37,7 +37,7 @@ let my_open_process_in = fun cmd -> Unix.close in_write; pid, inchan -let buf_size = 128 +let buf_size = 1024 let run_and_log = fun log com -> let com = com ^ " 2>&1" in @@ -46,14 +46,18 @@ let run_and_log = fun log com -> let cb = fun ev -> if List.mem `IN ev then begin let buf = String.create buf_size in - let n = input com_stdout buf 0 buf_size in - if n < buf_size then - log (String.sub buf 0 n) - else begin - log buf; - end; + (* loop until input returns zero *) + let rec log_input = fun out -> + let n = input out buf 0 buf_size in + if n < buf_size then log (String.sub buf 0 n) + else begin + log buf; + log_input out + end; + in + log_input com_stdout; true - end else begin + end else begin log (sprintf "\nDONE (%s)\n\n" com); false end in @@ -68,7 +72,7 @@ let strip_prefix = fun dir file -> raise Exit end else String.sub file (n+1) (String.length file - n - 1) - + let choose_xml_file = fun ?(multiple = false) title subdir cb -> let dir = conf_dir // subdir in @@ -91,7 +95,6 @@ let choose_xml_file = fun ?(multiple = false) title subdir cb -> - let run_and_monitor = fun ?(once = false) ?file gui log com_name com args -> let c = sprintf "%s %s" com args in let p = new Gtk_process.hbox_program ?file () in @@ -105,9 +108,12 @@ let run_and_monitor = fun ?(once = false) ?file gui log com_name com args -> let c = p#entry_program#text in log (sprintf "Run '%s'\n" c); let (pi, out, unixfd, io_watch) = run_and_log log ("exec "^c) in + let stop_cb_delay = 500 in (* ms *) pid := pi; outchan := unixfd; - let io_watch' = Glib.Io.add_watch [`HUP;`OUT] (fun _ -> callback true;false) out in + let io_watch' = Glib.Io.add_watch [`HUP;`OUT] (fun _ -> + ignore (Glib.Timeout.add stop_cb_delay (fun () -> callback true; false)); + false) out in watches := [ io_watch; io_watch'] in let remove_callback = fun () -> @@ -116,26 +122,26 @@ let run_and_monitor = fun ?(once = false) ?file gui log com_name com args -> let rec callback = fun stop -> match p#button_stop#label, stop with "gtk-stop", _ -> - List.iter Glib.Io.remove !watches; - close_in !outchan; - ignore (Unix.kill !pid Sys.sigkill); - ignore (Unix.waitpid [] !pid); - p#button_stop#set_label "gtk-redo"; - p#button_remove#misc#set_sensitive true; - if once then - remove_callback () - else if stop && p#checkbutton_autolaunch#active then - callback false + List.iter Glib.Io.remove !watches; + close_in !outchan; + ignore (Unix.kill !pid Sys.sigkill); + ignore (Unix.waitpid [] !pid); + p#button_stop#set_label "gtk-redo"; + p#button_remove#misc#set_sensitive true; + if once then + remove_callback () + else if stop && p#checkbutton_autolaunch#active then + callback false | "gtk-redo", false -> - p#button_stop#set_label "gtk-stop"; - run callback; - p#button_remove#misc#set_sensitive false + p#button_stop#set_label "gtk-stop"; + run callback; + p#button_remove#misc#set_sensitive false | _ -> () in ignore (p#button_stop#connect#clicked ~callback:(fun () -> callback false)); ignore (p#entry_program#connect#activate ~callback:(fun () -> callback false)); run callback; - + (* Stop the program if the box is closed *) let callback = fun () -> callback true in @@ -173,11 +179,11 @@ let druid = fun home -> fp#set_text (sprintf "Configuration files need to be installed in your Paparazzi home (%s). To use another directory, please exit this utility, set the PAPARAZZI_HOME variable to the desired folder and restart." home); d#append_page fp; ignore (fp#connect#next - (fun _ -> - basic_command prerr_endline "" "init"; - false - )) - + (fun _ -> + basic_command prerr_endline "" "init"; + false + )) + end; begin @@ -186,15 +192,15 @@ let druid = fun home -> d#append_page ep ; ignore (ep#connect#finish - (fun _ -> - w#destroy (); - GMain.quit () - )) + (fun _ -> + w#destroy (); + GMain.quit () + )) end; w#show (); GMain.main () -let _ = +let _ = let home = Env.paparazzi_home in if not (conf_is_set home) then druid home @@ -207,6 +213,3 @@ let build_aircrafts = fun () -> List.iter (fun aircraft -> Hashtbl.add aircrafts (ExtXml.attrib aircraft "name") aircraft) (Xml.children conf_xml) - - - diff --git a/sw/tools/Makefile b/sw/tools/Makefile index 3189eca6b7..cda3739635 100644 --- a/sw/tools/Makefile +++ b/sw/tools/Makefile @@ -30,7 +30,7 @@ OCAMLNETCMA=$(shell ocamlfind query -r -a-format -predicates byte netstring) OCAMLLEX=ocamllex OCAMLYACC=ocamlyacc -all: gen_common.cmo gen_aircraft.out gen_airframe.out gen_messages2.out gen_messages.out gen_ubx.out gen_flight_plan.out gen_radio.out gen_periodic.out gen_settings.out gen_tuning.out gen_xsens.out gen_modules.out gen_abi.out find_free_msg_id.out +all: gen_common.cmo gen_aircraft.out gen_airframe.out gen_messages2.out gen_messages.out gen_ubx.out gen_mtk.out gen_flight_plan.out gen_radio.out gen_periodic.out gen_settings.out gen_tuning.out gen_xsens.out gen_modules.out gen_abi.out find_free_msg_id.out FP_CMO = fp_proc.cmo gen_flight_plan.cmo ABS_FP = $(FP_CMO:%=$$PAPARAZZI_SRC/sw/tools/%) diff --git a/sw/tools/calibration/calibrate.py b/sw/tools/calibration/calibrate.py index 66579ad30f..3d19454108 100755 --- a/sw/tools/calibration/calibrate.py +++ b/sw/tools/calibration/calibrate.py @@ -22,7 +22,7 @@ # - +import sys import os from optparse import OptionParser import scipy @@ -50,6 +50,9 @@ def main(): else: print args[0] + " not found" sys.exit(1) + if options.sensor == "GYRO": + print "You can't calibate gyros with this!" + sys.exit(1) ac_ids = calibration_utils.get_ids_in_log(filename) # import code; code.interact(local=locals()) if options.ac_id == None and len(ac_ids) == 1: diff --git a/sw/tools/gen_flight_plan.ml b/sw/tools/gen_flight_plan.ml index bf24fff948..34378230e1 100644 --- a/sw/tools/gen_flight_plan.ml +++ b/sw/tools/gen_flight_plan.ml @@ -437,6 +437,13 @@ let rec print_stage = fun index_of_waypoints x -> let r = parsed_attrib x "radius" in let _vmode = output_vmode x center "" in lprintf "Eight(%s, %s, %s);\n" center turn_about r; + begin + try + let c = parsed_attrib x "until" in + lprintf "if (%s) NextStageAndBreak();\n" c + with + ExtXml.Error _ -> () + end; lprintf "break;\n" | "oval" -> stage (); diff --git a/sw/tools/gen_mtk.ml b/sw/tools/gen_mtk.ml new file mode 100644 index 0000000000..692745152d --- /dev/null +++ b/sw/tools/gen_mtk.ml @@ -0,0 +1,176 @@ +(* + * $Id$ + * + * XML preprocessing for Mediatek (DIYDrones 1.4/1.6) protocol + * + * Copyright (C) 2003 Pascal Brisset, Antoine Drouin + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + *) + +open Printf + +let out = stdout + +let sizeof = function + "U4" | "I4" -> 4 + | "U2" | "I2" -> 2 + | "U1" | "I1" -> 1 + | "U4BE" | "I4BE" -> 4 + | "U2BE" | "I2BE" -> 2 + | x -> failwith (sprintf "sizeof: unknown format '%s'" x) + +let (+=) = fun r x -> r := !r + x + +let c_type = fun format -> + match format with + "I2" -> "int16_t" + | "I4" -> "int32_t" + | "U2" -> "uint16_t" + | "U4" -> "uint32_t" + | "U1" -> "uint8_t" + | "I1" -> "int8_t" + | "I2BE" -> "int16_t" + | "I4BE" -> "int32_t" + | "U2BE" -> "uint16_t" + | "U4BE" -> "uint32_t" + | _ -> failwith (sprintf "Gen_mtk.c_type: unknown format '%s'" format) + +let get_at = fun offset format block_size -> + let t = c_type format in + let block_offset = + if block_size = 0 then "" else sprintf "+%d*_mtk_block" block_size in + match format with + "U4" | "I4" -> sprintf "(%s)(*((uint8_t*)_mtk_payload+%d%s)|*((uint8_t*)_mtk_payload+1+%d%s)<<8|((%s)*((uint8_t*)_mtk_payload+2+%d%s))<<16|((%s)*((uint8_t*)_mtk_payload+3+%d%s))<<24)" t offset block_offset offset block_offset t offset block_offset t offset block_offset + | "U2" | "I2" -> sprintf "(%s)(*((uint8_t*)_mtk_payload+%d%s)|*((uint8_t*)_mtk_payload+1+%d%s)<<8)" t offset block_offset offset block_offset + | "U1" | "I1" -> sprintf "(%s)(*((uint8_t*)_mtk_payload+%d%s))" t offset block_offset + | "U4BE" | "I4BE" -> sprintf "(%s)(*((uint8_t*)_mtk_payload+3+%d%s)|*((uint8_t*)_mtk_payload+2+%d%s)<<8|((%s)*((uint8_t*)_mtk_payload+1+%d%s))<<16|((%s)*((uint8_t*)_mtk_payload+%d%s))<<24)" t offset block_offset offset block_offset t offset block_offset t offset block_offset + | "U2BE" | "I2BE" -> sprintf "(%s)(*((uint8_t*)_mtk_payload+1+%d%s)|*((uint8_t*)_mtk_payload+%d%s)<<8)" t offset block_offset offset block_offset + | _ -> failwith (sprintf "Gen_mtk.c_type: unknown format '%s'" format) + +let define = fun x y -> + fprintf out "#define %s %s\n" x y + +exception Length_error of Xml.xml*int*int + + + + +let parse_message = fun class_name m -> + let msg_name = Xml.attrib m "name" in + + fprintf out "\n"; + let msg_id = sprintf "MTK_%s_%s_ID" class_name msg_name in + define msg_id (Xml.attrib m "ID"); + + let field_name = fun f -> ExtXml.attrib f "name" in + let format = fun f -> Xml.attrib f "format" in + + let offset = ref 0 in + let rec gen_access_macro = fun block_size f -> + match Xml.tag f with + "field" -> + let fn = field_name f + and fmt = format f in + let block_no = if block_size = 0 then "" else ",_mtk_block" in + define (sprintf "MTK_%s_%s_%s(_mtk_payload%s)" class_name msg_name fn block_no) (get_at !offset fmt block_size); + offset += sizeof fmt + | "block" -> + let s = int_of_string (Xml.attrib f "length") in + let o = !offset in + List.iter (gen_access_macro s) (Xml.children f); + let s' = !offset - o in + if s <> s' then raise (Length_error (f, s, s')) + | x -> failwith ("Unexpected field: " ^ x) + in + + List.iter (gen_access_macro 0) (Xml.children m); + begin + try + let l = int_of_string (Xml.attrib m "length") in + if l <> !offset then raise (Length_error (m, l, !offset)) + with + Xml.No_attribute("length") -> () (** Undefined length authorized *) + end; + + (** Generating send function *) + let param_name = fun f -> String.lowercase (field_name f) in + let rec param_names = fun f r -> + if Xml.tag f = "field" then + param_name f :: r + else + List.fold_right param_names (Xml.children f) r in + let param_type = fun f -> c_type (format f) in + fprintf out "\n#define MtkSend_%s_%s(" class_name msg_name; + fprintf out "%s" (String.concat "," (param_names m [])); + fprintf out ") { \\\n"; + fprintf out " MtkHeader(MTK_%s_ID, %s, %d);\\\n" class_name msg_id !offset; + let rec send_one_field = fun f -> + match Xml.tag f with + "field" -> + let s = sizeof (format f) in + let p = param_name f in + let t = param_type f in + fprintf out " %s _%s = %s; MtkSend%dByAddr((uint8_t*)&_%s);\\\n" t p p s p + | "block" -> + List.iter send_one_field (Xml.children f) + | _ -> assert (false) in + List.iter send_one_field (Xml.children m); + fprintf out " MtkTrailer();\\\n"; + fprintf out "}\n\n#define MTK_%s_%s_LENGTH %d\n" class_name msg_name !offset + + +let parse_class = fun c -> + let _class_id = int_of_string (Xml.attrib c "id") + and class_name = Xml.attrib c "name" in + + fprintf out "\n"; + define (sprintf "MTK_%s_ID" class_name) (Xml.attrib c "ID"); + + List.iter (parse_message class_name) (Xml.children c) + + +let _ = + if Array.length Sys.argv <> 2 then begin + failwith (sprintf "Usage: %s <.xml mtk protocol file>" Sys.argv.(0)) + end; + let xml_file = Sys.argv.(1) in + try + let xml = Xml.parse_file xml_file in + fprintf out "/* Generated from %s */\n" xml_file; + fprintf out "/* Please DO NOT EDIT */\n\n"; + + define "MTK_DIY14_SYNC1" "0xB5"; + define "MTK_DIY14_SYNC2" "0x62"; + + List.iter parse_class (Xml.children xml) + with + Xml.Error (em, ep) -> + let l = Xml.line ep + and c1, c2 = Xml.range ep in + fprintf stderr "File \"%s\", line %d, characters %d-%d:\n" xml_file l c1 c2; + fprintf stderr "%s\n" (Xml.error_msg em); + exit 1 + | Length_error (m, l1, l2) -> + fprintf stderr "File \"%s\", inconsistent length: %d expected, %d found from fields in message:\n %s\n" xml_file l1 l2 (Xml.to_string_fmt m); + exit 1 + | Dtd.Check_error e -> + fprintf stderr "File \"%s\", DTD check error: %s\n" xml_file (Dtd.check_error e) + | Dtd.Prove_error e -> + fprintf stderr "\nFile \"%s\", DTD check error: %s\n\n" xml_file (Dtd.prove_error e) diff --git a/sw/tools/gen_settings.ml b/sw/tools/gen_settings.ml index a537587827..0fc95e35ff 100644 --- a/sw/tools/gen_settings.ml +++ b/sw/tools/gen_settings.ml @@ -138,7 +138,7 @@ let print_dl_settings = fun settings -> left() (* - Generate code for persitent settings + Generate code for persistent settings *) let print_persistent_settings = fun settings -> let settings = flatten settings [] in @@ -160,7 +160,7 @@ let print_persistent_settings = fun settings -> lprintf "extern struct PersistentSettings pers_settings;\n\n"; (* Inline function to store persistent settings *) idx := 0; - lprintf "static inline void persitent_settings_store( void ) {\n"; + lprintf "static inline void persistent_settings_store( void ) {\n"; right(); List.iter (fun s -> @@ -171,7 +171,7 @@ let print_persistent_settings = fun settings -> lprintf "}\n\n"; (* Inline function to load persistent settings *) idx := 0; - lprintf "static inline void persitent_settings_load( void ) {\n"; + lprintf "static inline void persistent_settings_load( void ) {\n"; right(); List.iter (fun s ->