diff --git a/.gitignore b/.gitignore index 1e2145660d..56364c34ca 100644 --- a/.gitignore +++ b/.gitignore @@ -2,6 +2,8 @@ *.[oa] *.out +*~ + *.pyc *.cmo diff --git a/Makefile b/Makefile index 1b291aebc9..af0bd3282c 100644 --- a/Makefile +++ b/Makefile @@ -58,12 +58,12 @@ MESSAGES_XML = $(CONF)/messages.xml UBX_XML = $(CONF)/ubx.xml XSENS_XML = $(CONF)/xsens_MTi-G.xml TOOLS=$(PAPARAZZI_SRC)/sw/tools -HAVE_ARM_NONE_EABI_GCC := $(wildcard /usr/bin/arm-none-eabi-gcc) +HAVE_ARM_NONE_EABI_GCC := $(shell which arm-none-eabi-gcc) ifeq ($(strip $(HAVE_ARM_NONE_EABI_GCC)),) #ARMGCC=/opt/paparazzi/bin/arm-elf-gcc ARMGCC=/usr/bin/arm-elf-gcc else -ARMGCC=/usr/bin/arm-none-eabi-gcc +ARMGCC=$(HAVE_ARM_NONE_EABI_GCC) endif diff --git a/conf/Makefile.lpc21 b/conf/Makefile.lpc21 index 9f29195229..334e243b74 100644 --- a/conf/Makefile.lpc21 +++ b/conf/Makefile.lpc21 @@ -34,6 +34,7 @@ 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 @@ -42,6 +43,7 @@ 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 @@ -91,6 +93,7 @@ CFLAGS += -Wredundant-decls -Wreturn-type -Wshadow -Wunused CFLAGS += -Wa,-adhlns=$(OBJDIR)/$(notdir $(subst $(suffix $<),.lst,$<)) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) CFLAGS += -ffunction-sections -fdata-sections +CFLAGS += -finline-limit=1200 --param inline-unit-growth=100 # flags only for C CFLAGS + = -Wstrict-prototypes -Wmissing-declarations diff --git a/conf/airframes/airframe.dtd b/conf/airframes/airframe.dtd index ca0def88fe..9a741787b0 100644 --- a/conf/airframes/airframe.dtd +++ b/conf/airframes/airframe.dtd @@ -26,7 +26,7 @@ - + - - - #empty - - - + ap.srcs += $(SRC_BOOZ_ARCH)/booz2_pwm_hw.c sim.srcs += $(SRC_BOOZ_SIM)/booz2_pwm_hw.c diff --git a/conf/airframes/mm/fixed-wing/funjetgfi8.xml b/conf/airframes/mm/fixed-wing/funjetgfi8.xml index 116595be4d..2f28f49668 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi8.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi8.xml @@ -1,8 +1,7 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -38,7 +76,7 @@ - + @@ -81,8 +119,6 @@
- -
@@ -91,8 +127,6 @@ - - @@ -125,7 +159,6 @@ -
@@ -140,10 +173,6 @@ - - -
@@ -160,87 +189,14 @@ -
- -
- - - - - -
- -
- -
-
- -
+
+ + + + + +
- -CONFIG = \"tiny_2_1.h\" - -include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile - -FLASH_MODE=IAP - -ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1 -ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c - -ap.srcs += commands.c - -ap.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -ap.srcs += $(SRC_ARCH)/servos_4017_hw.c actuators.c - -ap.CFLAGS += -DRADIO_CONTROL -ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c - -ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600 -ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c xbee.c - -#TRANSPARENT -#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B9600 -#ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c - - -ap.CFLAGS += -DINTER_MCU -ap.srcs += inter_mcu.c - -ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 -ap.srcs += $(SRC_ARCH)/adc_hw.c - -ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART0 -DGPS_LINK=Uart0 -DUART0_BAUD=B38400 -DGPS_USE_LATLONG -# -DGPS_LED=2 -ap.srcs += gps_ubx.c gps.c latlong.c - -ap.CFLAGS += -DUSE_INFRARED -DALT_KALMAN -DWIND_INFO -DWIND_INFO_RET -ap.srcs += infrared.c estimator.c - -ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM -ap.srcs += nav.c fw_h_ctl.c fw_v_ctl.c - -ap.srcs += nav_line.c -ap.srcs += nav_survey_rectangle.c - -ap.srcs += humid_sht.c -ap.CFLAGS += -DUSE_HUMID_SHT -DDAT_PIN=3 -DSCK_PIN=2 - -ap.srcs += baro_scp.c -ap.CFLAGS += -DUSE_BARO_SCP - -ap.srcs += joystick.c -ap.CFLAGS += -DUSE_JOYSTICK - -# Config for SITL simulation -include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile -sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN -sim.srcs += nav_line.c nav_survey_rectangle.c - -sim.srcs += joystick.c -sim.CFLAGS += -DUSE_JOYSTICK - - - diff --git a/conf/autopilot/fixedwing.makefile b/conf/autopilot/fixedwing.makefile index 8b2808e155..b22a99c9cb 100644 --- a/conf/autopilot/fixedwing.makefile +++ b/conf/autopilot/fixedwing.makefile @@ -5,47 +5,51 @@ # - +CFG_SHARED=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/shared CFG_FIXEDWING=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/fixedwing SRC_FIXEDWING=. -SRC_ARCH=$(SRC_FIXEDWING)/arch/$(ARCH) +SRC_ARCH=arch/$(ARCH) SRC_FIXEDWING_TEST=$(SRC_FIXEDWING)/ SRC_FIRMWARE=firmwares/fixedwing SRC_SUBSYSTEMS=subsystems -FIXEDWING_INC = -I$(SRC_FIRMWARE) -I$(SRC_FIXEDWING) -I$(SRC_FIXEDWING_ARCH) +FIXEDWING_INC = -I$(SRC_FIRMWARE) -I$(SRC_FIXEDWING) # Standard Fixed Wing Code include $(CFG_FIXEDWING)/autopilot.makefile +# automatically include correct actuators for the ap target +ifeq ($(TARGET),ap) -ifeq ($(ACTUATORS),) - ifeq ($(BOARD),tiny) - ifeq ($(BOARD_VERSION),1.1) - include $(CFG_FIXEDWING)/actuators_4015.makefile - else - ifeq ($(BOARD_VERSION),0.99) - include $(CFG_FIXEDWING)/actuators_4015.makefile + ifeq ($(ACTUATORS),) + ifeq ($(BOARD),tiny) + ifeq ($(BOARD_VERSION),1.1) + include $(CFG_SHARED)/actuators_4015.makefile else - include $(CFG_FIXEDWING)/actuators_4017.makefile + ifeq ($(BOARD_VERSION),0.99) + include $(CFG_SHARED)/actuators_4015.makefile + else + include $(CFG_SHARED)/actuators_4017.makefile + endif endif endif - endif - ifeq ($(BOARD),twog) - include $(CFG_FIXEDWING)/actuators_4017.makefile + ifeq ($(BOARD),twog) + include $(CFG_SHARED)/actuators_4017.makefile + endif + + ifeq ($(BOARD),lisa_l) + include $(CFG_SHARED)/actuators_direct.makefile + endif + + else + include $(CFG_FIXEDWING)/$(ACTUATORS).makefile endif - ifeq ($(BOARD),lisa_l) - include $(CFG_FIXEDWING)/actuators_direct.makefile - endif - -else - include $(CFG_FIXEDWING)/$(ACTUATORS).makefile endif diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile index 1065e3fc00..58d2468a6e 100644 --- a/conf/autopilot/rotorcraft.makefile +++ b/conf/autopilot/rotorcraft.makefile @@ -30,6 +30,7 @@ # MODEM_BAUD # +CFG_SHARED=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/shared CFG_ROTORCRAFT=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/rotorcraft SRC_BOOZ=booz diff --git a/conf/autopilot/setup.makefile b/conf/autopilot/setup.makefile index 02fa4b7fee..c889667725 100644 --- a/conf/autopilot/setup.makefile +++ b/conf/autopilot/setup.makefile @@ -4,14 +4,13 @@ # -CFG_SETUP=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/SETUP +CFG_SHARED=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/shared +#CFG_SETUP=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/setup +SRC_ARCH=arch/$(ARCH) +SRC_FIRMWARE=firmwares/setup -SRC_SETUP=. -SRC_SETUP_ARCH=$(SRC_SETUP)/$(ARCH) -SRC_SETUP_TEST=$(SRC_SETUP)/ - -SETUP_INC = -I$(SRC_SETUP) -I$(SRC_SETUP_ARCH) +SETUP_INC = -I$(SRC_FIRMWARE) # for the usb_tunnel we need to set PCLK higher @@ -49,9 +48,36 @@ usb_tunnel_1.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c + +ifeq ($(ACTUATORS),) + ifeq ($(BOARD),tiny) + ifeq ($(BOARD_VERSION),1.1) + include $(CFG_SHARED)/actuators_4015.makefile + else + ifeq ($(BOARD_VERSION),0.99) + include $(CFG_SHARED)/actuators_4015.makefile + else + include $(CFG_SHARED)/actuators_4017.makefile + endif + endif + endif + ifeq ($(BOARD),twog) + include $(CFG_SHARED)/actuators_4017.makefile + endif + + ifeq ($(BOARD),lisa_l) + include $(CFG_SHARED)/actuators_direct.makefile + endif + +else + include $(CFG_SHARED)/$(ACTUATORS).makefile +endif + + # a test program to setup actuators -setup_actuators.CFLAGS += -DFBW -DLED -DTIME_LED=1 -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 +setup_actuators.CFLAGS += -DFBW -DLED -DTIME_LED=1 setup_actuators.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 -DDOWNLINK_DEVICE=Uart1 -DPPRZ_UART=Uart1 setup_actuators.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=PPRZ setup_actuators.CFLAGS += -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c downlink.c actuators.c setup_actuators.c $(SRC_ARCH)/uart_hw.c $(SRC_ARCH)/servos_4017_hw.c main.c +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)/uart_hw.c firmwares/fixedwing/main.c diff --git a/conf/autopilot/subsystems/fixedwing/actuators_4015.makefile b/conf/autopilot/subsystems/fixedwing/actuators_4015.makefile deleted file mode 100644 index 793add2d01..0000000000 --- a/conf/autopilot/subsystems/fixedwing/actuators_4015.makefile +++ /dev/null @@ -1,6 +0,0 @@ -# for Tiny v1.1 - -ap.CFLAGS += -DACTUATORS=\"servos_4015_MAT_hw.h\" -DSERVOS_4015_MAT -ap.srcs += $(SRC_ARCH)/servos_4015_MAT_hw.c -ap.srcs += $(SRC_FIXEDWING)/actuators.c - diff --git a/conf/autopilot/subsystems/fixedwing/actuators_4017.makefile b/conf/autopilot/subsystems/fixedwing/actuators_4017.makefile deleted file mode 100644 index 02452e3c35..0000000000 --- a/conf/autopilot/subsystems/fixedwing/actuators_4017.makefile +++ /dev/null @@ -1,5 +0,0 @@ -# for Tiny v2 or Twog v1 - -ap.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -ap.srcs += $(SRC_ARCH)/servos_4017_hw.c $(SRC_FIXEDWING)/actuators.c - diff --git a/conf/autopilot/subsystems/fixedwing/actuators_direct.makefile b/conf/autopilot/subsystems/fixedwing/actuators_direct.makefile deleted file mode 100644 index 06a9e8000a..0000000000 --- a/conf/autopilot/subsystems/fixedwing/actuators_direct.makefile +++ /dev/null @@ -1,13 +0,0 @@ -# for lisa_l - -ap.CFLAGS += -DACTUATORS=\"servos_direct_hw.h\" -DSERVOS_DIRECT -ap.srcs += $(SRC_ARCH)/servos_direct_hw.c $(SRC_FIXEDWING)/actuators.c - - -# TODO TODO UGLY HACK: We re-use the booz actuators: Should become universal actuator code!! -# Carefull: paths might get broken with this silly rotorcraft/fixedwing mixup of directories - -ifeq ($(ARCH), stm32) -ap.srcs += firmwares/rotorcraft/actuators/arch/stm32/actuators_pwm_arch.c -ap.CFLAGS += -Ifirmwares/rotorcraft/actuators/arch/stm32 -endif diff --git a/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h_hitl.makefile b/conf/autopilot/subsystems/fixedwing/gps_ublox_lea5h_hitl.makefile old mode 100755 new mode 100644 diff --git a/conf/autopilot/subsystems/fixedwing/payload_hum_baro.makefile b/conf/autopilot/subsystems/fixedwing/payload_hum_baro.makefile deleted file mode 100644 index 0513988cbb..0000000000 --- a/conf/autopilot/subsystems/fixedwing/payload_hum_baro.makefile +++ /dev/null @@ -1,7 +0,0 @@ -# Payload: Sensirion humidity/temp, VTI pressure/temp - -ap.srcs += humid_sht.c -ap.CFLAGS += -DUSE_HUMID_SHT -DDAT_PIN=3 -DSCK_PIN=2 - -ap.srcs += baro_scp.c -ap.CFLAGS += -DUSE_BARO_SCP diff --git a/conf/autopilot/subsystems/fixedwing/testing.makefile b/conf/autopilot/subsystems/fixedwing/testing.makefile index 734699c308..909daa7715 100644 --- a/conf/autopilot/subsystems/fixedwing/testing.makefile +++ b/conf/autopilot/subsystems/fixedwing/testing.makefile @@ -21,7 +21,7 @@ test_adcs.CFLAGS += -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1 -DADC -DUSE_ADC_ test_adcs.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DXBEE_UART=Uart0 -DDATALINK=XBEE -DUART0_BAUD=B9600 test_adcs.srcs += downlink.c $(SRC_ARCH)/uart_hw.c xbee.c -test_adcs.srcs += sys_time.c $(SRC_ARCH)/adc_hw.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test_adcs.c +test_adcs.srcs += sys_time.c $(SRC_ARCH)/adc_hw.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c test/test_adcs.c # pprz_transport.c diff --git a/conf/autopilot/subsystems/rotorcraft/radio_control_ppm.makefile b/conf/autopilot/subsystems/rotorcraft/radio_control_ppm.makefile deleted file mode 100644 index bfcc102eb7..0000000000 --- a/conf/autopilot/subsystems/rotorcraft/radio_control_ppm.makefile +++ /dev/null @@ -1,31 +0,0 @@ -# -# Autopilot -# -ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) -ap.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/ppm.h\" -ap.CFLAGS += -DRADIO_CONTROL_TYPE_PPM -ap.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ - $(SRC_SUBSYSTEMS)/radio_control/ppm.c \ - $(SRC_ARCH)/subsystems/radio_control/ppm_arch.c -ap.CFLAGS += -DUSE_TIM2_IRQ - -# -# Simulator -# -sim.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_LED=1 -sim.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/ppm.h\" -sim.CFLAGS += -DRADIO_CONTROL_TYPE_PPM -sim.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ - $(SRC_SUBSYSTEMS)/radio_control/ppm.c \ - $(SRC_ARCH)/subsystems/radio_control/ppm_arch.c - -# -# test_rc_ppm -# -# configuration -# SYS_TIME_LED -# MODEM_PORT -# MODEM_BAUD -# RADIO_CONTROL_LED -# - diff --git a/conf/autopilot/subsystems/rotorcraft/radio_control_spektrum.makefile b/conf/autopilot/subsystems/rotorcraft/radio_control_spektrum.makefile deleted file mode 100644 index 6e1beda4be..0000000000 --- a/conf/autopilot/subsystems/rotorcraft/radio_control_spektrum.makefile +++ /dev/null @@ -1,22 +0,0 @@ -# -# Makefile for radio_control susbsytem in rotorcraft firmware -# -ifndef RADIO_CONTROL_SPEKTRUM_MODEL -RADIO_CONTROL_SPEKTRUM_MODEL=\"subsystems/radio_control/spektrum_dx7se.h\" -endif - -ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_BIND_IMPL_FUNC=radio_control_spektrum_try_bind -ap.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/spektrum.h\" -ifeq ($(BOARD), booz) -ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_MODEL_H=$(RADIO_CONTROL_SPEKTRUM_MODEL) -endif -ifdef RADIO_CONTROL_LED -ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) -endif -ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_PRIMARY_PORT=$(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT) -ap.CFLAGS += -DOVERRIDE_$(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT)_IRQ_HANDLER -DUSE_TIM6_IRQ - -ap.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ - $(SRC_SUBSYSTEMS)/radio_control/spektrum.c \ - $(SRC_ARCH)/subsystems/radio_control/spektrum_arch.c - diff --git a/conf/autopilot/subsystems/shared/actuators_4015.makefile b/conf/autopilot/subsystems/shared/actuators_4015.makefile new file mode 100644 index 0000000000..6451c757b0 --- /dev/null +++ b/conf/autopilot/subsystems/shared/actuators_4015.makefile @@ -0,0 +1,4 @@ +# for Tiny v1.1 + +$(TARGET).CFLAGS += -DACTUATORS=\"servos_4015_MAT_hw.h\" -DSERVOS_4015_MAT +$(TARGET).srcs += $(SRC_ARCH)/servos_4015_MAT_hw.c actuators.c diff --git a/conf/autopilot/subsystems/shared/actuators_4017.makefile b/conf/autopilot/subsystems/shared/actuators_4017.makefile new file mode 100644 index 0000000000..471e3c3433 --- /dev/null +++ b/conf/autopilot/subsystems/shared/actuators_4017.makefile @@ -0,0 +1,4 @@ +# for Tiny v2 or Twog v1 + +$(TARGET).CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 +$(TARGET).srcs += $(SRC_ARCH)/servos_4017_hw.c actuators.c diff --git a/conf/autopilot/subsystems/shared/actuators_direct.makefile b/conf/autopilot/subsystems/shared/actuators_direct.makefile new file mode 100644 index 0000000000..07865d71d1 --- /dev/null +++ b/conf/autopilot/subsystems/shared/actuators_direct.makefile @@ -0,0 +1,13 @@ +# for lisa_l + +$(TARGET).CFLAGS += -DACTUATORS=\"servos_direct_hw.h\" -DSERVOS_DIRECT +$(TARGET).srcs += $(SRC_ARCH)/servos_direct_hw.c actuators.c + + +# TODO TODO UGLY HACK: We re-use the booz actuators: Should become universal actuator code!! +# Carefull: paths might get broken with this silly rotorcraft/fixedwing mixup of directories + +ifeq ($(ARCH), stm32) +$(TARGET).srcs += firmwares/rotorcraft/actuators/arch/stm32/actuators_pwm_arch.c +$(TARGET).CFLAGS += -Ifirmwares/rotorcraft/actuators/arch/stm32 +endif diff --git a/conf/autopilot/subsystems/fixedwing/radio_control_ppm.makefile b/conf/autopilot/subsystems/shared/radio_control_ppm.makefile similarity index 52% rename from conf/autopilot/subsystems/fixedwing/radio_control_ppm.makefile rename to conf/autopilot/subsystems/shared/radio_control_ppm.makefile index 71f8ac63ba..e5479f0e9e 100644 --- a/conf/autopilot/subsystems/fixedwing/radio_control_ppm.makefile +++ b/conf/autopilot/subsystems/shared/radio_control_ppm.makefile @@ -1,3 +1,6 @@ +# +# Makefile for shared radio_control ppm susbsytem +# NORADIO = False @@ -7,25 +10,11 @@ ifeq ($(BOARD),classix) endif endif - - -ifeq ($(ARCH),stm32) - ap.CFLAGS += -DRADIO_CONTROL -ifdef RADIO_CONTROL_LED - ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) -endif - ap.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/ppm.h\" - ap.CFLAGS += -DRADIO_CONTROL_TYPE_PPM - ap.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ - $(SRC_SUBSYSTEMS)/radio_control/ppm.c \ - $(SRC_ARCH)/subsystems/radio_control/ppm_arch.c - ap.CFLAGS += -DUSE_TIM2_IRQ - - NORADIO = True -endif - ifeq ($(NORADIO), False) $(TARGET).CFLAGS += -DRADIO_CONTROL + ifdef RADIO_CONTROL_LED + ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) + endif $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/ppm.h\" $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_PPM $(TARGET).srcs += $(SRC_SUBSYSTEMS)/radio_control.c @@ -33,4 +22,7 @@ ifeq ($(NORADIO), False) ifneq ($(ARCH),jsbsim) $(TARGET).srcs += $(SRC_ARCH)/subsystems/radio_control/ppm_arch.c endif + ifeq ($(ARCH),stm32) + ap.CFLAGS += -DUSE_TIM2_IRQ + endif endif diff --git a/conf/autopilot/subsystems/fixedwing/radio_control_spektrum.makefile b/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile similarity index 90% rename from conf/autopilot/subsystems/fixedwing/radio_control_spektrum.makefile rename to conf/autopilot/subsystems/shared/radio_control_spektrum.makefile index 6fa6e23738..ae53bd7a26 100644 --- a/conf/autopilot/subsystems/fixedwing/radio_control_spektrum.makefile +++ b/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile @@ -1,5 +1,5 @@ # -# Makefile for radio_control susbsytem in fixedwing firmware +# Makefile for shared radio_control spektrum susbsytem # ifndef RADIO_CONTROL_SPEKTRUM_MODEL RADIO_CONTROL_SPEKTRUM_MODEL=\"subsystems/radio_control/spektrum_dx7se.h\" @@ -7,7 +7,7 @@ endif ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_BIND_IMPL_FUNC=radio_control_spektrum_try_bind ap.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/spektrum.h\" -ifeq ($(BOARD), booz) +ifeq ($(ARCH), lpc21) ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_MODEL_H=$(RADIO_CONTROL_SPEKTRUM_MODEL) endif ifdef RADIO_CONTROL_LED diff --git a/conf/flight_plans/basic_booz.xml b/conf/flight_plans/basic_booz.xml index 83ad26c841..434d3c9a5a 100644 --- a/conf/flight_plans/basic_booz.xml +++ b/conf/flight_plans/basic_booz.xml @@ -1,9 +1,6 @@ -
- #include "booz_fms.h" -
@@ -63,15 +60,6 @@ - - - diff --git a/conf/modules/baro_scp.xml b/conf/modules/baro_scp.xml index f76579e90f..8bb3c9d8b2 100644 --- a/conf/modules/baro_scp.xml +++ b/conf/modules/baro_scp.xml @@ -14,6 +14,8 @@ + + diff --git a/conf/modules/digital_cam.xml b/conf/modules/digital_cam.xml index 8507667bfd..f03907a0b3 100644 --- a/conf/modules/digital_cam.xml +++ b/conf/modules/digital_cam.xml @@ -1,21 +1,42 @@ - -
- -
- - - - + + + +
+ +
+ + + + + + + + + + + +
diff --git a/conf/modules/digital_cam_i2c.xml b/conf/modules/digital_cam_i2c.xml new file mode 100644 index 0000000000..17a91367ce --- /dev/null +++ b/conf/modules/digital_cam_i2c.xml @@ -0,0 +1,29 @@ + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + +
+ diff --git a/conf/settings/dc.xml b/conf/settings/dc.xml index 6cb5d9c9a7..b2e44f1e56 100644 --- a/conf/settings/dc.xml +++ b/conf/settings/dc.xml @@ -1,21 +1,24 @@ - - - - - - - - - - + + - - - + + + + + + + + + + + + + + diff --git a/sw/airborne/arch/lpc21/lpcusb/Makefile b/sw/airborne/arch/lpc21/lpcusb/Makefile index b52b324be7..505dae4dbc 100644 --- a/sw/airborne/arch/lpc21/lpcusb/Makefile +++ b/sw/airborne/arch/lpc21/lpcusb/Makefile @@ -5,7 +5,7 @@ PKG_NAME = target DATE = $$(date +%Y%m%d) # Tool definitions -HAVE_ARM_NONE_EABI_GCC := $(wildcard /usr/bin/arm-none-eabi-gcc) +HAVE_ARM_NONE_EABI_GCC := $(shell which arm-none-eabi-gcc) ifeq ($(strip $(HAVE_ARM_NONE_EABI_GCC)),) CC = arm-elf-gcc diff --git a/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h index 955d692fc5..f8ebd1d4e7 100644 --- a/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h +++ b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h @@ -73,27 +73,27 @@ extern const int16_t rc_spk_throw[RADIO_CONTROL_NB_CHANNEL]; rc_spk_parser_idx++; \ if (rc_spk_parser_idx >= 2*RADIO_CONTROL_NB_CHANNEL) { \ rc_spk_parser_status = RC_SPK_STA_UNINIT; \ - radio_control.frame_cpt++; \ - radio_control.time_since_last_frame = 0; \ - radio_control.status = RC_OK; \ - uint8_t i; \ - for (i=0;i> 10;*/ \ - const int16_t val = (tmp&0x03FF) - 512; \ - radio_control.values[i] = val; \ - radio_control.values[i] *= rc_spk_throw[i]; \ - if (i==RADIO_CONTROL_THROTTLE) { \ - radio_control.values[i] += MAX_PPRZ; \ - radio_control.values[i] /= 2; \ - } \ - } \ - _received_frame_handler(); \ + radio_control.frame_cpt++; \ + radio_control.time_since_last_frame = 0; \ + radio_control.status = RC_OK; \ + uint8_t i; \ + for (i=0;i> 10;*/ \ + const int16_t val = (tmp&0x03FF) - 512; \ + radio_control.values[i] = val; \ + radio_control.values[i] *= rc_spk_throw[i]; \ + if (i==RADIO_CONTROL_THROTTLE) { \ + radio_control.values[i] += MAX_PPRZ; \ + radio_control.values[i] /= 2; \ + } \ + } \ + _received_frame_handler(); \ } \ break; \ - default: \ - rc_spk_parser_status = RC_SPK_STA_UNINIT; \ + default: \ + rc_spk_parser_status = RC_SPK_STA_UNINIT; \ } \ } \ } diff --git a/sw/airborne/datalink.c b/sw/airborne/datalink.c index 29e565e2f5..86aa3b7c62 100644 --- a/sw/airborne/datalink.c +++ b/sw/airborne/datalink.c @@ -39,6 +39,10 @@ #include "traffic_info.h" #endif // TRAFFIC_INFO +#if defined NAV || defined WIND_INFO +#include "estimator.h" +#endif + #ifdef USE_JOYSTICK #include "joystick.h" #endif @@ -52,7 +56,7 @@ #endif -#include "common_nav.h" +#include "nav.h" #include "generated/settings.h" #include "latlong.h" diff --git a/sw/airborne/firmwares/fixedwing/guidance/guidance_v_n.c b/sw/airborne/firmwares/fixedwing/guidance/guidance_v_n.c index 4e15561d24..66b382041d 100644 --- a/sw/airborne/firmwares/fixedwing/guidance/guidance_v_n.c +++ b/sw/airborne/firmwares/fixedwing/guidance/guidance_v_n.c @@ -33,7 +33,7 @@ #include "estimator.h" #include "nav.h" #include "generated/airframe.h" -#include "autopilot.h" +#include "firmwares/fixedwing/autopilot.h" /* mode */ uint8_t v_ctl_mode; diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index bbd23299bd..f1a3577d7c 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -44,7 +44,7 @@ #include "gyro.h" #include "ap_downlink.h" #include "nav.h" -#include "autopilot.h" +#include "firmwares/fixedwing/autopilot.h" #include "estimator.h" #include "generated/settings.h" #include "link_mcu.h" diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 644ff5ad6d..92a9e53135 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -50,7 +50,7 @@ #include "firmwares/fixedwing/actuators.h" #include "subsystems/radio_control.h" #include "fbw_downlink.h" -#include "autopilot.h" +#include "firmwares/fixedwing/autopilot.h" #include "paparazzi.h" #include "estimator.h" diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c index bc8d33725a..0594546b02 100644 --- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c +++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c @@ -36,7 +36,7 @@ #include "nav.h" #include "generated/airframe.h" #include "firmwares/fixedwing/guidance/guidance_v.h" -#include "autopilot.h" +#include "firmwares/fixedwing/autopilot.h" /* outer loop parameters */ diff --git a/sw/airborne/setup_actuators.c b/sw/airborne/firmwares/setup/setup_actuators.c similarity index 100% rename from sw/airborne/setup_actuators.c rename to sw/airborne/firmwares/setup/setup_actuators.c diff --git a/sw/airborne/joystick.h b/sw/airborne/joystick.h index bd8b2c0289..acbe1c14ad 100644 --- a/sw/airborne/joystick.h +++ b/sw/airborne/joystick.h @@ -3,6 +3,7 @@ #include "std.h" #include "firmwares/fixedwing/stabilization/stabilization_attitude.h" +#include "autopilot.h" extern uint8_t joystick_block; diff --git a/sw/airborne/max1167.c b/sw/airborne/max1167.c deleted file mode 100644 index e8b4123212..0000000000 --- a/sw/airborne/max1167.c +++ /dev/null @@ -1,15 +0,0 @@ -#include "max1167.h" - - -volatile uint8_t max1167_status; -uint16_t max1167_values[MAX1167_NB_CHAN]; - -extern void max1167_init( void ) { - max1167_hw_init(); - - uint8_t i; - for (i=0; i 0) + { + + if (gps_msg_counter == 0) + { + DC_PUSH(DC_SHUTTER_LED); + + dc_send_shot_position(); + } + else if (gps_msg_counter == DC_GPS_TRIGGER_START) + { + DC_RELEASE(DC_SHUTTER_LED); + } + + gps_msg_counter++; + if (gps_msg_counter >= DC_GPS_TRIGGER_STOP) + gps_msg_counter = 0; + } } +*/ diff --git a/sw/airborne/modules/digital_cam/dc.h b/sw/airborne/modules/digital_cam/dc.h index 9d5bb6e063..06fc9d1f0e 100644 --- a/sw/airborne/modules/digital_cam/dc.h +++ b/sw/airborne/modules/digital_cam/dc.h @@ -1,7 +1,5 @@ /* - * Paparazzi $Id$ - * - * Copyright (C) 2003-2008 Pascal Brisset, Antoine Drouin + * Copyright (C) 2010 The Paparazzi Team * * This file is part of paparazzi. * @@ -22,29 +20,18 @@ * */ + /** \file dc.h - * \brief Digital Camera Control + * \brief Standard Digital Camera Control Interface * - * Provides the control of the shutter and the zoom of a digital camera - * through standard binary IOs of the board. + * -Standard IO + * -I2C Control * - * Configuration: - * Since the API of led.h is used, connected pins must be defined as led - * numbers (usually in the airframe file): - * - * - * Related bank and pin must also be defined: - * - * - * The required initialization (dc_init()) and periodic (4Hz) process - * (dc_periodic()) are called if the DIGITAL_CAM flag is set: - * ap.CFLAGS += -DDIGITAL_CAM - * - * Usage (from the flight plan, the settings or any airborne code): - * - dc_Shutter(_) sets the DC_SHUTTER_LED pin output to 1 for 0.5s and sends - * a DC_SHOT message - * - dc_Zoom(_) sets the DC_ZOOM_LED pin output to 1 for 0.5s - * - dc_Periodic(s) activates a periodic call to dc_Shutter() every s seconds + * Usage: (from the flight plan, the settings or any airborne code): + * - dc_send_command( ) + * - set the appropriate autoshoot mode (off/time/distance/trigger) + * - use the module periodic function to set the autorepeat interval + * - define SENSOR_SYNC_SEND to get the DC_SHOT_MESSAGE on every SHOOT command */ #ifndef DC_H @@ -53,124 +40,111 @@ #include "std.h" #include "led.h" #include "generated/airframe.h" -#include "estimator.h" #include "gps.h" -extern uint8_t dc_timer; +/* Generic Set of Digital Camera Commands */ +typedef enum { + DC_GET_STATUS = 0, -extern uint8_t dc_periodic_shutter; -/* In s. If non zero, period of automatic calls to dc_shutter() */ -extern uint8_t dc_shutter_timer; -/* In s. Related counter */ + DC_HOLD = 13, + DC_SHOOT = 32, -extern uint8_t dc_utm_threshold; -/* In m. If non zero, automatic shots when greater than utm_north % 100 */ + DC_WIDER = 'w', + DC_TALLER = 't', -/* Picture Number starting from zero */ -extern uint16_t dc_photo_nr; -extern uint8_t dc_shoot; + DC_UP = 'u', + DC_DOWN = 'd', + DC_CENTER = 'c', + DC_LEFT = 'l', + DC_RIGHT = 'r', -#ifndef DC_PUSH -#define DC_PUSH LED_ON -#endif + DC_MENU = 'm', + DC_HOME = 'h', + DC_PLAY = 'p', -#ifndef DC_RELEASE -#define DC_RELEASE LED_OFF -#endif + DC_ON = 'O', + DC_OFF = 'o', -#define SHUTTER_DELAY 2 /* 4Hz -> 0.5s */ +} dc_command_type; -uint8_t dc_shutter( void ); +/* Send Command To Camera */ +static inline void dc_send_command(uint8_t cmd); -static inline uint8_t dc_zoom( void ) { - dc_timer = SHUTTER_DELAY; -#ifdef DC_ZOOM_LED - DC_PUSH(DC_ZOOM_LED); -#endif - return 0; -} +/* 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_type; +extern dc_autoshoot_type dc_autoshoot; -#define dc_Shutter(_) ({ dc_shutter(); 0; }) -#define dc_Zoom(_) ({ dc_zoom(); 0; }) -#define dc_Periodic(s) ({ dc_periodic_shutter = s; dc_shutter_timer = s; 0; }) +/* AutoShoot photos every X quarter_second */ +extern uint8_t dc_autoshoot_quartersec_period; -#ifndef DC_PERIODIC_SHUTTER -#define DC_PERIODIC_SHUTTER 0 -#endif - -#define dc_init() { /* initialized as leds */ dc_periodic_shutter = DC_PERIODIC_SHUTTER; DC_PUSH(DC_SHUTTER_LED);} /* Output */ - - -#ifndef DC_GPS_TRIGGER_START -#define DC_GPS_TRIGGER_START 1 -#endif -#ifndef DC_GPS_TRIGGER_STOP -#define DC_GPS_TRIGGER_STOP 3 -#endif +/* AutoShoot photos on a X meter Local Tangent Plane Grid */ +extern uint8_t dc_autoshoot_meter_grid; +/* Send Down the coordinates of where the photo was taken */ +#ifdef SENSOR_SYNC_SEND void dc_send_shot_position(void); - -static inline void dc_shoot_on_gps( void ) { - static uint8_t gps_msg_counter = 0; - - if (dc_shoot > 0) - { - - if (gps_msg_counter == 0) - { - DC_PUSH(DC_SHUTTER_LED); - - dc_send_shot_position(); - } - else if (gps_msg_counter == DC_GPS_TRIGGER_START) - { - DC_RELEASE(DC_SHUTTER_LED); - } - - gps_msg_counter++; - if (gps_msg_counter >= DC_GPS_TRIGGER_STOP) - gps_msg_counter = 0; - } -} - -/* 4Hz */ -static inline void dc_periodic( void ) { - if (dc_timer) { - dc_timer--; - } else { - DC_RELEASE(DC_SHUTTER_LED); -#ifdef DC_ZOOM_LED - DC_RELEASE(DC_ZOOM_LED); +#else +#define dc_send_shot_position() {} #endif - } - if (dc_shoot > 0) +/****************************************************************** + * FUNCTIONS + *****************************************************************/ + +/* get settings */ +static inline void dc_init(void) +{ +#ifdef DC_AUTOSHOOT_QUARTERSEC_PERIOD + dc_autoshoot_quartersec_period = DC_AUTOSHOOT_QUARTERSEC_PERIOD; +#endif +#ifdef DC_AUTOSHOOT_METER_GRID + dc_autoshoot_meter_grid = DC_AUTOSHOOT_METER_GRID; +#endif +} + +/* shoot on grid */ +static inline void dc_shot_on_utm_north_close_to_100m_grid( void ) +{ + uint32_t dist_to_100m_grid = (gps_utm_north / 100) % 100; + if (dist_to_100m_grid < dc_autoshoot_meter_grid || 100 - dist_to_100m_grid < dc_autoshoot_meter_grid) { - if (dc_periodic_shutter) { - RunOnceEvery(2, - { - if (dc_shutter_timer) { - dc_shutter_timer--; - } else { - dc_shutter(); - dc_shutter_timer = dc_periodic_shutter; - } - }); + dc_send_command(DC_SHOOT); + } +} + +/* periodic 4Hz function */ +static inline void dc_periodic_4Hz( void ) +{ + static uint8_t dc_shutter_timer = 0; + +#ifdef DC_AUTOSHOOT_QUARTERSEC_PERIOD + if (dc_autoshoot == DC_AUTOSHOOT_PERIODIC) + { + if (dc_shutter_timer) + { + dc_shutter_timer--; + } else { + dc_send_command(DC_SHOOT); + dc_shutter_timer = dc_autoshoot_quartersec_period; } } - else +#endif +#ifdef DC_AUTOSHOOT_METER_GRID + if (dc_autoshoot == DC_AUTOSHOOT_DISTANCE) { - dc_shutter_timer = 0; + // Shoot + dc_shot_on_utm_north_close_to_100m_grid(); } +#endif } -static inline void dc_shot_on_utm_north_close_to_100m_grid( void ) { - if (dc_utm_threshold && !dc_timer) { - uint32_t dist_to_100m_grid = (gps_utm_north / 100) % 100; - if (dist_to_100m_grid < dc_utm_threshold || 100 - dist_to_100m_grid < dc_utm_threshold) - dc_shutter(); - } -} + + #endif // DC_H diff --git a/sw/airborne/modules/digital_cam/led_cam_ctrl.c b/sw/airborne/modules/digital_cam/led_cam_ctrl.c new file mode 100644 index 0000000000..af9acb254a --- /dev/null +++ b/sw/airborne/modules/digital_cam/led_cam_ctrl.c @@ -0,0 +1,33 @@ +/* + * 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 "led_cam_ctrl.h" + +// Include Digital IO +#include "led.h" + +// Button Timer +uint8_t dc_timer; + + + + diff --git a/sw/airborne/modules/digital_cam/led_cam_ctrl.h b/sw/airborne/modules/digital_cam/led_cam_ctrl.h new file mode 100644 index 0000000000..fcf6a17b88 --- /dev/null +++ b/sw/airborne/modules/digital_cam/led_cam_ctrl.h @@ -0,0 +1,132 @@ +/* + * 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. + * + */ + + +/** \file led_cam_ctrl.h + * \brief Digital Camera Control + * + * Provides the control of the shutter and the zoom of a digital camera + * through standard binary IOs of the board. + * + * Configuration: + * Since the API of led.h is used, connected pins must be defined as led + * numbers (usually in the airframe file): + * + * + * + * + * Related bank and pin must also be defined: + * + * + * The required initialization (dc_init()) and periodic (4Hz) process + * + */ + +#ifndef LED_CAM_CTRL_H +#define LED_CAM_CTRL_H + +// Include Standard Camera Control Interface +#include "dc.h" + +extern uint8_t dc_timer; + +static inline void led_cam_ctrl_init(void) +{ + // Call common DC init + dc_init(); + + // Do LED specific DC init + dc_timer = 0; +} + +#ifndef DC_PUSH +#define DC_PUSH LED_ON +#endif + +#ifndef DC_RELEASE +#define DC_RELEASE LED_OFF +#endif + +#ifndef SHUTTER_DELAY +#define SHUTTER_DELAY 2 /* 4Hz -> 0.5s */ +#endif + +#ifndef DC_SHUTTER_LED +#error DC: Please specify at least a SHUTTER LED +#endif + +/* Command The Camera */ +static inline void dc_send_command(uint8_t cmd) +{ + dc_timer = SHUTTER_DELAY; + switch (cmd) + { + case DC_SHOOT: + DC_PUSH(DC_SHUTTER_LED); + dc_send_shot_position(); + break; +#ifdef DC_ZOOM_IN_LED + case DC_ZOOM_IN: + DC_PUSH(DC_ZOOM_IN_LED); + break; +#endif +#ifdef DC_ZOOM_OUT_LED + case DC_ZOOM_OUT: + DC_PUSH(DC_ZOOM_OUT_LED); + break; +#endif +#ifdef DC_POWER_LED + case DC_POWER: + DC_PUSH(DC_POWER_LED); + break; +#endif + } +} + + +/* 4Hz Periodic */ +static inline void led_cam_ctrl_periodic( void ) +{ + if (dc_timer) { + dc_timer--; + } else { + DC_RELEASE(DC_SHUTTER_LED); +#ifdef DC_ZOOM_IN_LED + DC_RELEASE(DC_ZOOM_IN_LED); +#endif +#ifdef DC_ZOOM_OUT_LED + DC_RELEASE(DC_ZOOM_OUT_LED); +#endif +#ifdef DC_POWER_LED + DC_RELEASE(DC_POWER_LED); +#endif + } + + // Common DC Periodic task + dc_periodic_4Hz(); +} + + + + + +#endif // DC_H diff --git a/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c b/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c new file mode 100644 index 0000000000..c682e4ae37 --- /dev/null +++ b/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c @@ -0,0 +1,92 @@ +/* + * 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. + * + */ + + +/** \file sim_i2c_cam_ctrl.c + * \brief Simulated Interface with digital camera + * + */ + + +#include "atmega_i2c_cam_ctrl.h" + + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif +#include "uart.h" +#include "messages.h" +#include "downlink.h" +#include "estimator.h" + + +void atmega_i2c_cam_ctrl_init(void) +{ + dc_init(); +} + +void atmega_i2c_cam_ctrl_periodic (void) +{ + dc_periodic_4Hz(); + + // Request Status + dc_send_command(DC_GET_STATUS); +} + + + +void atmega_i2c_cam_ctrl_send(uint8_t cmd) +{ + static uint8_t zoom = 0; + static uint8_t mode = 0; + unsigned char cam_ret[1]; + + if (cmd == DC_SHOOT) + { + dc_send_shot_position(); + } + else if (cmd == DC_TALLER) + { + zoom = 1; + } + else if (cmd == DC_WIDER) + { + zoom = 0; + } + else if (cmd == DC_GET_STATUS) + { + mode++; + if (mode > 15) + mode = 0; + } + + cam_ret[0] = mode + zoom * 0x20; + RunOnceEvery(6,DOWNLINK_SEND_PAYLOAD(DefaultChannel, 1, cam_ret )); + +} + +void atmega_i2c_cam_ctrl_event( void ) +{ +} + + + diff --git a/sw/airborne/arch/lpc21/max1167_hw.c b/sw/airborne/obsolete/max1167_hw.c similarity index 100% rename from sw/airborne/arch/lpc21/max1167_hw.c rename to sw/airborne/obsolete/max1167_hw.c diff --git a/sw/airborne/arch/lpc21/max1167_hw.h b/sw/airborne/obsolete/max1167_hw.h similarity index 100% rename from sw/airborne/arch/lpc21/max1167_hw.h rename to sw/airborne/obsolete/max1167_hw.h diff --git a/sw/airborne/subsystems/radio_control/spektrum_dx7se.h b/sw/airborne/subsystems/radio_control/spektrum_dx7se.h index f0016291e7..05cbd55c56 100644 --- a/sw/airborne/subsystems/radio_control/spektrum_dx7se.h +++ b/sw/airborne/subsystems/radio_control/spektrum_dx7se.h @@ -24,7 +24,8 @@ #ifndef RADIO_CONTROL_SPEKTRUM_DX7SE_H #define RADIO_CONTROL_SPEKTRUM_DX7SE_H -#define RADIO_NB_CHANNEL 7 +#define RADIO_CONTROL_NB_CHANNEL 7 + #define RADIO_ROLL 0 #define RADIO_THROTTLE 1 #define RADIO_PITCH 2 diff --git a/sw/airborne/nova_test_imu.c b/sw/airborne/test/nova_test_imu.c similarity index 100% rename from sw/airborne/nova_test_imu.c rename to sw/airborne/test/nova_test_imu.c diff --git a/sw/airborne/test_adcs.c b/sw/airborne/test/test_adcs.c similarity index 100% rename from sw/airborne/test_adcs.c rename to sw/airborne/test/test_adcs.c diff --git a/sw/ground_segment/cockpit/Makefile b/sw/ground_segment/cockpit/Makefile index 453c6cf0f4..76cd97c91c 100644 --- a/sw/ground_segment/cockpit/Makefile +++ b/sw/ground_segment/cockpit/Makefile @@ -102,6 +102,9 @@ LDFLAGS=`pkg-config gtk+-2.0 --libs` -s `pcre-config --libs` -lglibivy ant_track : ant_track.c $(CC) $(CFLAGS) -g -o $@ $^ $(LDFLAGS) +ant_track_pmm : ant_track_pmm.c + $(CC) $(CFLAGS) -g -o $@ $^ $(LDFLAGS) + test_enose : test_enose.c sliding_plot.c $(CC) $(CFLAGS) -g -o $@ $^ $(LDFLAGS) -lgtkdatabox diff --git a/sw/ground_segment/cockpit/ant_track_pmm.c b/sw/ground_segment/cockpit/ant_track_pmm.c new file mode 100644 index 0000000000..9d7a70528d --- /dev/null +++ b/sw/ground_segment/cockpit/ant_track_pmm.c @@ -0,0 +1,721 @@ +/* + * Paparazzi $Id: ant_track_pmm.c 2010-11-27 18:14:20Z griffin $ + * + * Copyright (C) 2010 + * + * Modified by: Mark Griffin and Todd Sandercock + * Modified by: Chris Efstathiou for the Pololu Micro Mestro usb servo controller Jun/2010 + * Added command line options, a 360 pan option and "MANUAL" control. + * + * 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. + * + * The antenna tracker zero azimuth is to the NORTH (NORTH = 0, EAST = 90 WEST = -90, SOUTH = 180/0 degrees). + * The elevation zero is totally horizontal, 90 is up and 180 is to the back. + * The servo used must be able to do 180 degrees in order to get full 360 degree coverage from the tracker. + */ +#include +#include +#include +#include +#include + +#include +#include + +#include +#include /* UNIX standard function definitions */ +#include /* File control definitions */ +#include /* Error number definitions */ + +#define POLOLU_PROTOCOL_START 0xAA +#define POLOLU_BOARD_ID 12 +#define SET_SERVO_POSITION_COMMAND 0x04 +#define SET_SERVO_SPEED_COMMAND 0x07 +#define SET_SERVO_ACCELERATION_COMMAND 0x09 +#define SET_SERVO_CENTER_COMMAND 0x22 + +#define MANUAL 0 +#define AUTO 1 + +static double gps_pos_x; +static double gps_pos_y; +static double gps_alt; +static double home_alt; +static double ant_azim = 180.; +static double ant_elev = 90.; +static int mode; +static int home_found; +static int ant_tracker_pan_mode = 180; +static double theta_servo_pw_span = 1000.; +static double psi_servo_pw_span = 1000.; +static double theta_servo_center_pw = 1500; +static double psi_servo_center_pw = 1500; +static char pololu_board_id = 12; +static char servo_acceleration = 3; +static char psi_servo_address = 1; +static char theta_servo_address = 0; + +int fd; /* File descriptor for the port */ +volatile int serial_error = 0; + +double hfov = 180., vfov = 180.; +double hnp = 0., vnp = 0.; + +unsigned char speed = 0x00; + +void set_servos(void); + +GtkWidget *azim_scale; +GtkWidget *elev_scale; + +void on_mode_changed(GtkRadioButton *radiobutton, gpointer user_data) { + + + mode = gtk_toggle_button_get_active(GTK_TOGGLE_BUTTON(radiobutton)) ? MANUAL : AUTO; + + + //IvySendMsg("1ME RAW_DATALINK 80 SETTING;0;0;%d", mode); + //g_message("Mode changed to %d" , mode); +} + +void on_azimuth_changed(GtkAdjustment *hscale, gpointer user_data) { + +if (mode == MANUAL) { + ant_azim = gtk_range_get_value(GTK_RANGE (azim_scale)); + ant_elev = gtk_range_get_value(GTK_RANGE (elev_scale)); + set_servos(); + } + //IvySendMsg("1ME RAW_DATALINK 80 SETTING;0;0;%d", mode); + //g_message("Mode changed to %d" , mode); +} + +//void on_elevation_changed(GtkRange *elev_scale, gpointer user_data) { +void on_elevation_changed(GtkAdjustment *hscale, gpointer user_data) { + +if (mode == MANUAL) { + ant_azim = gtk_range_get_value(GTK_RANGE (azim_scale)); + ant_elev = gtk_range_get_value(GTK_RANGE (elev_scale)); + set_servos(); + } + + + //IvySendMsg("1ME RAW_DATALINK 80 SETTING;0;0;%d", mode); + //g_message("Mode changed to %d" , mode); +} + + +#define GLADE_HOOKUP_OBJECT(component,widget,name) \ + g_object_set_data_full (G_OBJECT (component), name, \ + gtk_widget_ref (widget), (GDestroyNotify) gtk_widget_unref) + +#define GLADE_HOOKUP_OBJECT_NO_REF(component,widget,name) \ + g_object_set_data (G_OBJECT (component), name, widget) + +GtkWidget* build_gui(void) { + GtkWidget *window1; + GtkWidget *vbox1; + GtkWidget *vbox2; + GtkWidget *table1; + GtkWidget *label1; + GtkWidget *label2; + GtkWidget *label3; + GtkWidget *label4; + GtkWidget *radiobutton1; + GSList *radiobutton1_group = NULL; + GtkWidget *radiobutton2; + GtkWidget *entry1; + + window1 = gtk_window_new(GTK_WINDOW_TOPLEVEL); + gtk_window_set_title(GTK_WINDOW (window1), "tracking antenna"); + + vbox1 = gtk_vbox_new(FALSE, 0); + gtk_widget_show(vbox1); + gtk_container_add(GTK_CONTAINER (window1), vbox1); + + vbox2 = gtk_vbox_new(FALSE, 0); + gtk_widget_show(vbox2); + gtk_box_pack_start(GTK_BOX (vbox1), vbox2, TRUE, TRUE, 0); + + table1 = gtk_table_new(4, 3, FALSE); + gtk_widget_show(table1); + gtk_box_pack_start(GTK_BOX (vbox2), table1, TRUE, TRUE, 0); + gtk_table_set_col_spacings(GTK_TABLE (table1), 5); + + label1 = gtk_label_new("Azimuth"); + gtk_widget_show(label1); + gtk_table_attach(GTK_TABLE (table1), label1, 0, 1, 1, 2, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); + gtk_misc_set_alignment(GTK_MISC (label1), 0, 0.5); + + label2 = gtk_label_new("Elevation"); + gtk_widget_show(label2); + gtk_table_attach(GTK_TABLE (table1), label2, 0, 1, 2, 3, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); + gtk_misc_set_alignment(GTK_MISC (label2), 0, 0.5); + + label3 = gtk_label_new("Id"); + gtk_widget_show(label3); + gtk_table_attach(GTK_TABLE (table1), label3, 0, 1, 3, 4, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); + gtk_misc_set_alignment(GTK_MISC (label3), 0, 0.5); + + label4 = gtk_label_new("mode"); + gtk_widget_show(label4); + gtk_table_attach(GTK_TABLE (table1), label4, 0, 1, 0, 1, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); + gtk_misc_set_alignment(GTK_MISC (label4), 0, 0.5); + + radiobutton1 = gtk_radio_button_new_with_mnemonic(NULL, "manual"); + gtk_widget_show(radiobutton1); + gtk_table_attach(GTK_TABLE (table1), radiobutton1, 1, 2, 0, 1, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); + gtk_radio_button_set_group(GTK_RADIO_BUTTON (radiobutton1), + radiobutton1_group); + radiobutton1_group = gtk_radio_button_get_group( + GTK_RADIO_BUTTON (radiobutton1)); + + radiobutton2 = gtk_radio_button_new_with_mnemonic(NULL, "tracking"); + gtk_widget_show(radiobutton2); + gtk_table_attach(GTK_TABLE (table1), radiobutton2, 2, 3, 0, 1, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); + gtk_radio_button_set_group(GTK_RADIO_BUTTON (radiobutton2), + radiobutton1_group); + radiobutton1_group = gtk_radio_button_get_group( + GTK_RADIO_BUTTON (radiobutton2)); + + azim_scale = gtk_hscale_new( + //GTK_ADJUSTMENT (gtk_adjustment_new (180, 0, 360, 1, 1, 1))); + GTK_ADJUSTMENT (gtk_adjustment_new (0, 0, 360, 1, 1, 1))); + gtk_widget_show(azim_scale); + gtk_table_attach(GTK_TABLE (table1), azim_scale, 1, 3, 1, 2, + (GtkAttachOptions) (GTK_EXPAND | GTK_FILL), + (GtkAttachOptions) (GTK_FILL), 0, 0); +// gtk_range_set_update_policy(GTK_RANGE (azim_scale), GTK_UPDATE_DELAYED); + + elev_scale = gtk_hscale_new( + //GTK_ADJUSTMENT (gtk_adjustment_new (45, 0, 90, 1, 1, 1))); + GTK_ADJUSTMENT (gtk_adjustment_new (0, 0, 90, 1, 1, 1))); + gtk_widget_show(elev_scale); + gtk_table_attach(GTK_TABLE (table1), elev_scale, 1, 3, 2, 3, + (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (GTK_FILL), 0, 0); +// gtk_range_set_update_policy(GTK_RANGE (elev_scale), GTK_UPDATE_DELAYED); + + entry1 = gtk_entry_new(); + gtk_widget_show(entry1); + gtk_table_attach(GTK_TABLE (table1), entry1, 1, 3, 3, 4, + (GtkAttachOptions) (GTK_EXPAND | GTK_FILL), (GtkAttachOptions) (0), + 0, 0); + + g_signal_connect ((gpointer) radiobutton1, "toggled", + G_CALLBACK (on_mode_changed), + NULL); + + g_signal_connect ((gpointer) azim_scale, "value-changed", + G_CALLBACK (on_azimuth_changed), + NULL); + + g_signal_connect ((gpointer) elev_scale, "value-changed", + G_CALLBACK (on_elevation_changed), + NULL); + + /* Store pointers to all widgets, for use by lookup_widget(). */ + GLADE_HOOKUP_OBJECT_NO_REF (window1, window1, "window1"); + GLADE_HOOKUP_OBJECT (window1, vbox1, "vbox1"); + GLADE_HOOKUP_OBJECT (window1, vbox2, "vbox2"); + GLADE_HOOKUP_OBJECT (window1, table1, "table1"); + GLADE_HOOKUP_OBJECT (window1, label1, "label1"); + GLADE_HOOKUP_OBJECT (window1, label2, "label2"); + GLADE_HOOKUP_OBJECT (window1, label3, "label3"); + GLADE_HOOKUP_OBJECT (window1, label4, "label4"); + GLADE_HOOKUP_OBJECT (window1, radiobutton1, "radiobutton1"); + GLADE_HOOKUP_OBJECT (window1, radiobutton2, "radiobutton2"); + GLADE_HOOKUP_OBJECT (window1, entry1, "entry1"); + + return window1; +} + +void set_servos(void) +{ + +double hpos, vpos; +int hservo = theta_servo_center_pw, vservo = psi_servo_center_pw; + + // The magic is done here + + if (ant_tracker_pan_mode == 180){ + + // Take the vertical angle relative to the neutral point "vnp" + vpos = ant_elev - vnp; + + // keep within the field of view "vfov" + if (vpos > (vfov / 2)) { vpos = vfov / 2; } else if(-vpos > (vfov / 2)){ vpos = -vfov / 2; } + + // First take the horizontal angle relative to the neutral point "hnp" + hpos = ant_azim - hnp; + + // Keep the range between (-180,180). this is done so that it consistently swaps sides + if (hpos < -180){ hpos += 360; }else if(hpos > 180){ hpos -= 360; } + + // Swap sides to obtain 360 degrees of Azimuth coverage. + if(hpos > 90){ hpos = hpos-180; vpos = 180-vpos; }else if(hpos < -90){ hpos = hpos+180; vpos = 180-vpos; } + + // keep the range within the field of view "hfov" + if (hpos > (hfov / 2)) { hpos = hfov / 2; } else if (-hpos > (hfov / 2)) { hpos = -hfov / 2; } + + // Convert angles to servo microsecond values suitable for the Pololu micro Maestro servo controller. + vpos = (psi_servo_center_pw-(psi_servo_pw_span/2)) + (vpos*(psi_servo_pw_span/vfov)); + hpos = theta_servo_center_pw + (hpos*(theta_servo_pw_span/(hfov/2))); + + //convert the values to integer. + hservo = hpos; + vservo = vpos; + + + }else{ + vpos = ant_elev; + + // First take the horizontal angle relative to the neutral point "hnp" + hpos = ant_azim - hnp; + + // Keep the range between (-180,180). + if (hpos < -180){ hpos += 360; }else if(hpos > 180){ hpos -= 360; } + + // Keep the range between 0 to 360. + //if (hpos < 0) { hpos += 360; } else if (hpos > 360){ hpos -= 360; } + + // keep the range within the field of view "hfov" + if (hpos > (hfov / 2)) { hpos = hfov / 2; } else if (-hpos > (hfov / 2)) { hpos = -hfov / 2; } + + // Convert angles to servo microsecond values suitable for the Pololu micro Maestro servo controller. + vpos = (psi_servo_center_pw-(psi_servo_pw_span/2)) + (fabs(vpos)*(psi_servo_pw_span/vfov)); + hpos = theta_servo_center_pw + (hpos*(theta_servo_pw_span/hfov)); + + //convert the values to integer. + hservo = hpos; + vservo = vpos; + } + + // Sanity check. + if (vservo < (psi_servo_center_pw-fabs(psi_servo_pw_span/2)) ){ + vservo = (psi_servo_center_pw-fabs(psi_servo_pw_span/2)); + + }else if(vservo > (psi_servo_center_pw+fabs(psi_servo_pw_span/2))){ vservo = (psi_servo_center_pw+fabs(psi_servo_pw_span/2)); } + + if (hservo < (theta_servo_center_pw-fabs(theta_servo_pw_span/2)) ){ + hservo = (theta_servo_center_pw-fabs(theta_servo_pw_span/2)); + + }else if(hservo > (theta_servo_center_pw+fabs(theta_servo_pw_span/2))){ hservo = (theta_servo_center_pw+fabs(theta_servo_pw_span/2)); } + + hservo *= 4; //The pololu Maestro uses 0.25 microsecond increments so we need to multiply microseconds by 4. + vservo *= 4; //The pololu Maestro uses 0.25 microsecond increments so we need to multiply microseconds by 4. + //g_message("home_alt %f gps_alt %f azim %f elev %f", home_alt, gps_alt, ant_azim, ant_elev); + + // Send servo position. + char buffer1[]={ POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_POSITION_COMMAND, psi_servo_address, vservo%128, vservo/128, + POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_POSITION_COMMAND, theta_servo_address, hservo%128, hservo/128 + }; + + serial_error = write(fd, buffer1, 12); + + g_message("vservo %i hservo %i", (int)(vservo/4), (int)(hservo/4)); //Divide by 4 so we can have the servo PW with 1 microsecond resolution. + +return; +} + + + +/* jump here when a GPS message is received */ +void on_GPS_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]) { + if (home_found == 0) { + if (atof(argv[0]) == 3) { /* wait until we have a valid GPS fix */ + home_alt = atof(argv[4]) / 100.; /* get the altitude */ + home_found = 1; + } + } + gps_alt = atof(argv[4]) / 100.; +} + +/* jump here when a NAVIGATION message is received */ +void on_NAV_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]) { + + + if (mode == AUTO) { + gps_pos_x = atof(argv[2]); + gps_pos_y = atof(argv[3]); + /* calculate azimuth */ + //should be "atan2(gps_pos_y, gps_pos_x)" but it is reversed to give 0 when North. + ant_azim = atan2(gps_pos_x, gps_pos_y) * 180. / M_PI; + + if (ant_azim < 0) + ant_azim += 360.; + + /* calculate elevation */ + ant_elev = atan2((gps_alt - home_alt), sqrt(atof(argv[5]))) * 180. / M_PI; + // Sanity check + if (ant_elev < 0){ ant_elev = 0.; } + gtk_range_set_value(GTK_RANGE (azim_scale), ant_azim); + gtk_range_set_value(GTK_RANGE (elev_scale), ant_elev); + + set_servos(); + + } + + +} + +int open_port(char* port ) { + struct termios options; + + // would probably be good to set the port up as an arg. + // The Pololu micro maestro registers two ports /dev/ttyACM0 and /dev/ttyACM1, /dev/ttyACM0 is the data port. + fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY); + if (fd == -1) { + //perror("open_port: Unable to open /dev/ttyUSB1"); + printf ("open_port: Unable to open %s \n", port); + serial_error = fd; + + } else + printf("Success %s %s \n", port, "opened"); + fcntl(fd, F_SETFL, 0); + + tcgetattr(fd, &options); + + // Set the baud rates to 19200. This can be between 2,000 to 40,000 + + cfsetispeed(&options, B19200); + cfsetospeed(&options, B19200); + + options.c_cflag |= (CLOCAL | CREAD); + + tcsetattr(fd, TCSANOW, &options); + + // Send initialisation to the pololu micro maestro board. + // if "speed" is nonzero then 1 is the slowest 127 is the fastest. 0 = no speed restriction + char buffer_0[] = { POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_SPEED_COMMAND, psi_servo_address, 0x00, 0x00, + POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_SPEED_COMMAND, theta_servo_address, 0x00, 0x00 + }; + + serial_error = write(fd, buffer_0, 12); + // Set servo acceleration to 3 for protecting the servo gears. Fastest = 0, slowest = 255 + char buffer_1[] = { POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_ACCELERATION_COMMAND, psi_servo_address, (servo_acceleration%128), + (servo_acceleration/128), + POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_ACCELERATION_COMMAND, theta_servo_address, (servo_acceleration%128), + (servo_acceleration/128) + }; + + serial_error = write(fd, buffer_1, 12); + // Set the two servos to their neutral position, Azimuth = 1500us = EAST = 0 degrees & Elevation = 1000 = parallel to ground. + char buffer_2[] = { POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_POSITION_COMMAND, theta_servo_address, + (((int)theta_servo_center_pw*4) % 128), (((int)theta_servo_center_pw*4) / 128), + POLOLU_PROTOCOL_START, pololu_board_id, SET_SERVO_POSITION_COMMAND, psi_servo_address, + (((int)psi_servo_center_pw*4) % 128), (((int)psi_servo_center_pw*4) / 128) + }; + + serial_error = write(fd, buffer_2, 12); + + + return (fd); +} + +int main(int argc, char** argv) { + + gtk_init(&argc, &argv); + + + int x = 0, y = 0, z = 0; + char buffer[20]; + char serial_open = 0; + printf ("Antenna Tracker for the Paparazzi autopilot, Chris Efstathiou 2010 \n"); + + if (argc > 1){ + char arg_string1[] = "--help"; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string1, (sizeof(arg_string1)-1))) == 0 ){ + printf ("OPTIONS \n"); + printf ("-------------------------------------------------------------------------------- \n"); + printf ("'--help' displays this screen \n"); + printf ("'--port=xxx..x' opens port xxx..x, example --port=/dev/ttyACM0 (Default) \n"); + printf ("'--pan=xxx' sets pan mode to 180 or 360 degrees. Example --pan=180 (Default) \n"); + printf ("'--zero_angle=xxx' set the mechanical zero angle. Default is 0 (North)\n"); + printf ("'--id=xx' sets the Pololu board id. Example --id=12 (Default)\n"); + printf ("'--servo_acc=xxx' sets the servo acceleration. Example --servo_acc=3 (Default)\n"); + printf ("'--pan_servo=x' sets the pan (Theta) servo number. Example --pan_servo=0 (Default)\n"); + printf ("'--tilt_servo=x' sets the tilt (Psi) servo number.Example --tilt_servo=1 (Default) \n"); + printf ("'--pan_epa=xx..x' sets the Azimuth servo's max travel (Default is 1100us) \n"); + printf ("'--tilt_epa=xx..x' sets the elevation servo's max travel (Default is 1100us). \n"); + printf ("HINT a negative value EPA value reverses the servo direction \n"); + printf ("'--pan_servo_center_pw=xx..x' sets the Azimuth servo's center position (Default is 1500us) \n"); + printf ("'--tilt_servo_center_pw=xx..x' sets the elevation servo's center position (Default is 1500us) \n"); + printf ("WARNING: The pololu board limit servo travel to 1000-2000 microseconds. \n"); + printf ("WARNING: Use the pololu board setup program to change the above limits. \n"); + printf ("Example --tilt_epa=1100 sets the PW from 950 to 2050 microseconds \n"); + printf ("Example --pan_epa=-1000 sets the PW from 1000 to 2000 microseconds and reverses the servo direction \n"); + printf ("An EPA of 1100 sets the servo travel from 1500+(1100/2)=2050us to 1500-(1100/2)=950us. \n"); + printf ("Use programmable servos like the Hyperion Atlas. \n"); + printf ("You can also use the proportional 360 degree GWS S125-1T as the Theta (Azimuth) \n"); + printf ("servo or the mighty but expensive Futaba S5801 \n"); + printf (" \n"); + printf ("FOR THE 360 DEGREE PAN MODE: \n"); + printf ("Mechanical zero (0 degrees or 1500 ms) is to the NORTH, 90 = EAST, +-180 = SOUTH and -90 = WEST. \n"); + printf ("Elevation center is 45 degrees up (1500ms), 0 degrees = horizontal, 90 degrees is vertical (up) \n"); + printf ("Of course use this mode if your PAN servo can do a full 360 degrees rotation (GWS S125-1T for example) \n"); + printf (" \n"); + printf ("FOR THE 180 DEGREE PAN MODE: \n"); + printf ("Mechanical zero (0 degrees or 1500 ms) is to the NORTH, 90 = EAST, -90 = WEST. \n"); + printf ("Elevation center is 90 degrees up (1500ms), 0 degrees = horizontal, 180 degrees is horizontal to the opposite side \n"); + printf ("When the azimuth is > 90 or < -90 the azimuth and elevation servos swap sides to obtain the full 360 degree coverage. \n"); + printf ("Of course your PAN and TILT servos must be true 180 degrees servos like the Hyperion ATLAS servos for example. \n"); + printf (" \n"); + printf ("-------------------------------------------------------------------------------- \n"); + printf ("Antenna Tracker V1.2 for the Paparazzi autopilot 28/June/2010 \n"); + printf ("-------------------------------------------------------------------------------- \n"); + return 0; + } + } + printf ("Type '--help' for help \n"); + + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string2[] = "--port="; + for (x=1; x < argc; x++){ + + if ( (strncmp(argv[x], arg_string2, (sizeof(arg_string2)-1))) == 0 ){ + y=sizeof(arg_string2)-1; + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + printf ("Trying to open %s \n", buffer); + open_port(buffer); + } + } + for(z=0; z 1000){ + printf ("REMEMBER TO SET THE MIN/MAX SERVO LIMITS WITH THE POLOLU SETUP PROGRAM \n"); + printf ("OTHERWISE THE MAX SERVO MOVEMENT WILL BE RESTRAINED TO 1000 MICROSECONDS \n"); + } + } + } + + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string5[] = "--tilt_epa="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string5, (sizeof(arg_string5)-1))) == 0 ){ + y=(sizeof(arg_string5)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + psi_servo_pw_span = atoi(buffer); + printf ("PSI servo EPA set to %i \n", atoi(buffer)); + if (abs(psi_servo_pw_span) > 1000){ + printf ("REMEMBER TO SET THE MIN/MAX SERVO LIMITS WITH THE POLOLU SETUP PROGRAM \n"); + printf ("OTHERWISE THE MAX SERVO MOVEMENT WILL BE RESTRAINED TO 1000 MICROSECONDS \n"); + } + } + } + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string8[] = "--id="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string8, (sizeof(arg_string8)-1))) == 0 ){ + y=(sizeof(arg_string8)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + pololu_board_id = (char)atoi(buffer); + printf ("Pololu Board id set to %i \n", atoi(buffer)); + } + } + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string9[] = "--servo_acc="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string9, (sizeof(arg_string9)-1))) == 0 ){ + y=(sizeof(arg_string9)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + servo_acceleration = (char)atoi(buffer); + printf ("Servo acceleration set to %i \n", atoi(buffer)); + } + } + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string10[] = "--pan_servo="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string10, (sizeof(arg_string10)-1))) == 0 ){ + y=(sizeof(arg_string10)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + theta_servo_address = (char)atoi(buffer); + printf ("Pan (Theta) servo number set to %i \n", atoi(buffer)); + } + } + + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string11[] = "--tilt_servo="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string11, (sizeof(arg_string11)-1))) == 0 ){ + y=(sizeof(arg_string11)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + psi_servo_address = (char)atoi(buffer); + printf ("Tilt (Psi) servo number set to %i \n", atoi(buffer)); + } + } + + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string12[] = "--zero_angle="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string12, (sizeof(arg_string12)-1))) == 0 ){ + y=(sizeof(arg_string12)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + hnp = (double)atoi(buffer); + printf ("Zero angle is set to %i %s \n", atoi(buffer), "degrees"); + } + } + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string13[] = "--tilt_servo_center_pw="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string13, (sizeof(arg_string13)-1))) == 0 ){ + y=(sizeof(arg_string13)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + psi_servo_center_pw = atoi(buffer); + printf ("PSI servo center pulse width set to %i \n", atoi(buffer)); + } + } + for(z=0; z < sizeof(buffer); z++){ buffer[z] = '\0'; } //Reset the buffer. + char arg_string14[] = "--pan_servo_center_pw="; + for (x=1; x < argc; x++){ + if ( (strncmp(argv[x], arg_string14, (sizeof(arg_string14)-1))) == 0 ){ + y=(sizeof(arg_string14)-1); + z=0; + while (1){ + buffer[z] = argv[x][y]; + if(buffer[z] != '\0'){ y++; z++; }else{ break; } + } + theta_servo_center_pw = atoi(buffer); + printf ("THETA servo center pulse width set to %i \n", atoi(buffer)); + } + } + for(z=0; z -#include -#include -#include -#include - -#include -#include - -#include -#include /* UNIX standard function definitions */ -#include /* File control definitions */ -#include /* Error number definitions */ - -#define MANUAL 0 -#define AUTO 1 - -static double gps_pos_x; -static double gps_pos_y; -static double gps_alt; -static double home_alt; -static double ant_azim; -static double ant_elev; -static int mode; -static int home_found; - -int fd; /* File descriptor for the port */ - -double hfov = 170., vfov = 170.; -double hnp = 270., vnp = 30.; -double hlim1 = 30, hlim2 = 200; -double vlim1 = 30, vlim2 = 200; - -unsigned char startByte = 0x80, deviceId = 0x01, command = 0x03, commandinit = - 0x00, psiServo = 0x01, thetaServo = 0x02, speed = 0x00, speedCmd = 0x01; -unsigned char datainit = 0x40; -unsigned char data1 = 19, data2 = 68; - -GtkWidget *azim_scale; -GtkWidget *elev_scale; - -void on_mode_changed(GtkRadioButton *radiobutton, gpointer user_data) { - mode - = gtk_toggle_button_get_active(GTK_TOGGLE_BUTTON(radiobutton)) ? MANUAL - : AUTO; - //IvySendMsg("1ME RAW_DATALINK 80 SETTING;0;0;%d", mode); - //g_message("Mode changed to %d" , mode); -} - -#define GLADE_HOOKUP_OBJECT(component,widget,name) \ - g_object_set_data_full (G_OBJECT (component), name, \ - gtk_widget_ref (widget), (GDestroyNotify) gtk_widget_unref) - -#define GLADE_HOOKUP_OBJECT_NO_REF(component,widget,name) \ - g_object_set_data (G_OBJECT (component), name, widget) - -GtkWidget* build_gui(void) { - GtkWidget *window1; - GtkWidget *vbox1; - GtkWidget *vbox2; - GtkWidget *table1; - GtkWidget *label1; - GtkWidget *label2; - GtkWidget *label3; - GtkWidget *label4; - GtkWidget *radiobutton1; - GSList *radiobutton1_group = NULL; - GtkWidget *radiobutton2; - GtkWidget *entry1; - - window1 = gtk_window_new(GTK_WINDOW_TOPLEVEL); - gtk_window_set_title(GTK_WINDOW (window1), "tracking antenna"); - - vbox1 = gtk_vbox_new(FALSE, 0); - gtk_widget_show(vbox1); - gtk_container_add(GTK_CONTAINER (window1), vbox1); - - vbox2 = gtk_vbox_new(FALSE, 0); - gtk_widget_show(vbox2); - gtk_box_pack_start(GTK_BOX (vbox1), vbox2, TRUE, TRUE, 0); - - table1 = gtk_table_new(4, 3, FALSE); - gtk_widget_show(table1); - gtk_box_pack_start(GTK_BOX (vbox2), table1, TRUE, TRUE, 0); - gtk_table_set_col_spacings(GTK_TABLE (table1), 5); - - label1 = gtk_label_new("Azimuth"); - gtk_widget_show(label1); - gtk_table_attach(GTK_TABLE (table1), label1, 0, 1, 1, 2, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); - gtk_misc_set_alignment(GTK_MISC (label1), 0, 0.5); - - label2 = gtk_label_new("Elevation"); - gtk_widget_show(label2); - gtk_table_attach(GTK_TABLE (table1), label2, 0, 1, 2, 3, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); - gtk_misc_set_alignment(GTK_MISC (label2), 0, 0.5); - - label3 = gtk_label_new("Id"); - gtk_widget_show(label3); - gtk_table_attach(GTK_TABLE (table1), label3, 0, 1, 3, 4, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); - gtk_misc_set_alignment(GTK_MISC (label3), 0, 0.5); - - label4 = gtk_label_new("mode"); - gtk_widget_show(label4); - gtk_table_attach(GTK_TABLE (table1), label4, 0, 1, 0, 1, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); - gtk_misc_set_alignment(GTK_MISC (label4), 0, 0.5); - - radiobutton1 = gtk_radio_button_new_with_mnemonic(NULL, "manual"); - gtk_widget_show(radiobutton1); - gtk_table_attach(GTK_TABLE (table1), radiobutton1, 1, 2, 0, 1, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); - gtk_radio_button_set_group(GTK_RADIO_BUTTON (radiobutton1), - radiobutton1_group); - radiobutton1_group = gtk_radio_button_get_group( - GTK_RADIO_BUTTON (radiobutton1)); - - radiobutton2 = gtk_radio_button_new_with_mnemonic(NULL, "tracking"); - gtk_widget_show(radiobutton2); - gtk_table_attach(GTK_TABLE (table1), radiobutton2, 2, 3, 0, 1, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (0), 0, 0); - gtk_radio_button_set_group(GTK_RADIO_BUTTON (radiobutton2), - radiobutton1_group); - radiobutton1_group = gtk_radio_button_get_group( - GTK_RADIO_BUTTON (radiobutton2)); - - azim_scale = gtk_hscale_new( - GTK_ADJUSTMENT (gtk_adjustment_new (144.7, 0, 360, 1, 1, 1))); - gtk_widget_show(azim_scale); - gtk_table_attach(GTK_TABLE (table1), azim_scale, 1, 3, 1, 2, - (GtkAttachOptions) (GTK_EXPAND | GTK_FILL), - (GtkAttachOptions) (GTK_FILL), 0, 0); - gtk_range_set_update_policy(GTK_RANGE (azim_scale), GTK_UPDATE_DELAYED); - - elev_scale = gtk_hscale_new( - GTK_ADJUSTMENT (gtk_adjustment_new (32.3, 0, 90, 1, 1, 1))); - gtk_widget_show(elev_scale); - gtk_table_attach(GTK_TABLE (table1), elev_scale, 1, 3, 2, 3, - (GtkAttachOptions) (GTK_FILL), (GtkAttachOptions) (GTK_FILL), 0, 0); - - entry1 = gtk_entry_new(); - gtk_widget_show(entry1); - gtk_table_attach(GTK_TABLE (table1), entry1, 1, 3, 3, 4, - (GtkAttachOptions) (GTK_EXPAND | GTK_FILL), (GtkAttachOptions) (0), - 0, 0); - - g_signal_connect ((gpointer) radiobutton1, "toggled", - G_CALLBACK (on_mode_changed), - NULL); - - /* Store pointers to all widgets, for use by lookup_widget(). */ - GLADE_HOOKUP_OBJECT_NO_REF (window1, window1, "window1"); - GLADE_HOOKUP_OBJECT (window1, vbox1, "vbox1"); - GLADE_HOOKUP_OBJECT (window1, vbox2, "vbox2"); - GLADE_HOOKUP_OBJECT (window1, table1, "table1"); - GLADE_HOOKUP_OBJECT (window1, label1, "label1"); - GLADE_HOOKUP_OBJECT (window1, label2, "label2"); - GLADE_HOOKUP_OBJECT (window1, label3, "label3"); - GLADE_HOOKUP_OBJECT (window1, label4, "label4"); - GLADE_HOOKUP_OBJECT (window1, radiobutton1, "radiobutton1"); - GLADE_HOOKUP_OBJECT (window1, radiobutton2, "radiobutton2"); - GLADE_HOOKUP_OBJECT (window1, entry1, "entry1"); - - return window1; -} - -/* jump here when a GPS message is received */ -void on_GPS_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]) { - if (home_found == 0) { - if (atof(argv[0]) == 3) { /* wait until we have a valid GPS fix */ - home_alt = atof(argv[4]) / 100.; /* get the altitude */ - home_found = 1; - } - } - gps_alt = atof(argv[4]) / 100.; -} - -void send_pos(int vert, int hori) { - // Split the value into two 7 bit numbers - data1 = vert / 128; - data2 = vert % 128; - - // Command buffer for "Set Position, 8-bit (2 data bytes)" from Pololu servo controller data sheet - // Send vertical servo - char buffer1[] = { startByte, deviceId, command, psiServo, data1, data2 }; - - write(fd, buffer1, 6); - - // Split the value into two 7 bit numbers - data1 = hori / 128; - data2 = hori % 128; - - // Command buffer for "Set Position, 8-bit (2 data bytes)" from Pololu servo controller data sheet - // Send horizontal servo - char buffer2[] = { startByte, deviceId, command, thetaServo, data1, data2 }; - - write(fd, buffer2, 6); -} - -/* jump here when a NAVIGATION message is received */ -void on_NAV_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]) { - double hpos, vpos; - double hservo, vservo; - - if (mode == AUTO) { - gps_pos_x = atof(argv[2]); - gps_pos_y = atof(argv[3]); - /* calculate azimuth */ - ant_azim = atan2(gps_pos_x, gps_pos_y) * 180. / M_PI; - - if (ant_azim < 0) - ant_azim += 360.; - - /* calculate elevation */ - ant_elev = atan2((gps_alt - home_alt), sqrt(atof(argv[5]))) * 180. - / M_PI; - if (ant_elev < 0) - ant_elev = 0.; - - gtk_range_set_value(azim_scale, ant_azim); - gtk_range_set_value(elev_scale, ant_elev); - } - - // The magic is done here - - // First take the horizontal angle relative to the neutral point "hnp" - hpos = ant_azim - hnp; - - // Keep the range between (-180,180). this is done so that it consistently swaps sides - if (hpos < -180) { - hpos += 360; - } else if (hpos > 180) { - hpos -= 360; - } - - // keep the range within the field of view "hfov" - if (hpos > (hfov / 2)) { - hpos = hfov / 2; - } else if (-hpos > (hfov / 2)) { - hpos = -hfov / 2; - } - - // Take the vertical angle relative to the neutral point "vnp" - vpos = ant_elev - vnp; - - // keep within the field of view "vfov" - if (vpos > (vfov / 2)) { - vpos = vfov / 2; - } else if (-vpos > (vfov / 2)) { - vpos = -vfov / 2; - } - - // make outputs relative to limits for the Pololu board - - vservo = (((vpos + (vfov / 2)) / vfov) * (vlim2 - vlim1)) + vlim1; - hservo = (((hpos + (hfov / 2)) / hfov) * (hlim2 - hlim1)) + hlim1; - - /*g_message("home_alt %f gps_alt %f azim %f elev %f", home_alt, gps_alt, ant_azim, ant_elev); */ - - // Send servo position. - send_pos(vservo, hservo); - - g_message("vservo %f hservo %f", vservo, hservo); -} - -int open_port(void) { - struct termios options; - - // would probably be good to set the port up as an arg. - fd = open("/dev/ttyUSB0", O_RDWR | O_NOCTTY | O_NDELAY); - if (fd == -1) { - perror("open_port: Unable to open /dev/ttyUSB0 - "); - } else - fcntl(fd, F_SETFL, 0); - - tcgetattr(fd, &options); - - // Set the baud rates to 19200. This can be between 2,000 to 40,000 - - cfsetispeed(&options, B19200); - cfsetospeed(&options, B19200); - - options.c_cflag |= (CLOCAL | CREAD); - - tcsetattr(fd, TCSANOW, &options); - - // Send initialisation to the pololu board. By changing "speed" the speed of the servo can be changed - // if "speed" is nonzero then 1 is the slowest 127 is the fastest. 0 = no speed restriction - char buffer[] = { startByte, deviceId, speedCmd, psiServo, speed, - startByte, deviceId, speedCmd, thetaServo, speed}; - - write(fd, buffer, 10); - - return (fd); -} - -int main(int argc, char** argv) { - - gtk_init(&argc, &argv); - - GtkWidget* window = build_gui(); - gtk_widget_show_all(window); - - open_port(); - - IvyInit("AntennaTracker", "AntennaTracker READY", NULL, NULL, NULL, NULL); - IvyBindMsg( - on_GPS_STATUS, - NULL, - "^\\S* GPS (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); - IvyBindMsg(on_NAV_STATUS, NULL, - "^\\S* NAVIGATION (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); - IvyStart("127.255.255.255"); - gtk_main(); - return 0; -} - diff --git a/sw/lib/ocaml/ivy/Makefile b/sw/lib/ocaml/ivy/Makefile index e738db897c..34bb76568d 100644 --- a/sw/lib/ocaml/ivy/Makefile +++ b/sw/lib/ocaml/ivy/Makefile @@ -117,7 +117,7 @@ tkivy-ocaml.cmxa : $(TKIVYCMX) civy.o ctkivy.o $(OCAMLOPT) -o $@ unix.cmxa -I . ivy-ocaml.cmxa $< -cclib -livy clean: - \rm -fr *.cm* *.o *.a .depend *~ *.out *.opt .depend *.so *-stamp debian/changelog debian/ivy-ocaml debian/files debian/ivy-ocaml.debhelper.log debian/ivy-ocaml.substvars debian/*~ + \rm -fr *.cm* *.o *.a .depend *~ *.out *.opt .depend *.so *-stamp debian/ivy-ocaml debian/files debian/ivy-ocaml.debhelper.log debian/ivy-ocaml.substvars debian/*~ .depend: $(OCAMLDEP) $(INCLUDES) *.mli *.ml > .depend diff --git a/sw/lib/ocaml/ivy/civy.c b/sw/lib/ocaml/ivy/civy.c index aa0b881ca6..15561182d4 100644 --- a/sw/lib/ocaml/ivy/civy.c +++ b/sw/lib/ocaml/ivy/civy.c @@ -76,7 +76,7 @@ value ivy_name_of_client(value c) } value ivy_host_of_client(value c) { - return copy_string(IvyGetApplicationHost((IvyClientPtr)Long_val(c))); + return copy_string(IvyGetApplicationHost((IvyClientPtr)Long_val(c))); } void cb_delete_channel(void *delete_read) diff --git a/sw/lib/ocaml/ivy/civyloop.c b/sw/lib/ocaml/ivy/civyloop.c index d774e9923c..4ff0a9311f 100644 --- a/sw/lib/ocaml/ivy/civyloop.c +++ b/sw/lib/ocaml/ivy/civyloop.c @@ -25,7 +25,7 @@ value ivy_mainLoop(value unit) void timer_cb(TimerId id, void *data, unsigned long delta) { value closure = *(value*)data; - callback(closure, Val_long(id)); + callback(closure, Val_long(id)); } value ivy_timerRepeatafter(value nb_ticks,value delay, value closure_name) diff --git a/sw/lib/ocaml/ivy/debian/changelog.3.11.2 b/sw/lib/ocaml/ivy/debian/changelog.3.11.2 index acd087fd0d..eb649f9b77 100644 --- a/sw/lib/ocaml/ivy/debian/changelog.3.11.2 +++ b/sw/lib/ocaml/ivy/debian/changelog.3.11.2 @@ -1,3 +1,9 @@ +ivy-ocaml (1.1-11) unstable; urgency=low + + * Support of ivy-c_3.11.6, OSX and Linux 64bit + + -- Gautier Hattenberger Wed, 1 Dec 2010 10:43:29 +0100 + ivy-ocaml (1.1-10) unstable; urgency=low * Updated for ocaml 3.11.2 diff --git a/sw/lib/ocaml/ivy/debian/control b/sw/lib/ocaml/ivy/debian/control index d7684c3037..7707a3836d 100644 --- a/sw/lib/ocaml/ivy/debian/control +++ b/sw/lib/ocaml/ivy/debian/control @@ -1,7 +1,7 @@ Source: ivy-ocaml Section: net Priority: optional -Maintainer: Pascal Brisset (Hecto) +Maintainer: Gautier Hattenberger Build-Depends: debhelper (>= 4.0.0), ocaml-nox, ivy-c-dev (>=3.8), libglib2.0-dev, libpcre3-dev, ivy-c(>=3.8) Standards-Version: 3.6.1 diff --git a/sw/tools/gen_aircraft.ml b/sw/tools/gen_aircraft.ml index ca80d8b40f..c52957c47c 100644 --- a/sw/tools/gen_aircraft.ml +++ b/sw/tools/gen_aircraft.ml @@ -41,35 +41,35 @@ let check_unique_id_and_name = fun conf -> let ids = Hashtbl.create 5 and names = Hashtbl.create 5 in List.iter - (fun x -> - if String.lowercase (Xml.tag x) = "aircraft" then - let id = ExtXml.attrib x "ac_id" - and name = ExtXml.attrib x "name" in - if Hashtbl.mem ids id then begin - let other_name = Hashtbl.find ids id in - failwith (sprintf "Error: A/C Id '%s' duplicated in %s (%s and %s)" id conf_xml name other_name) - end; - if Hashtbl.mem names name then begin - let other_id = Hashtbl.find names name in - failwith (sprintf "Error: A/C name '%s' duplicated in %s (ids %s and %s)" name conf_xml id other_id) - end; - Hashtbl.add ids id name; - Hashtbl.add names name id) - (Xml.children conf) + (fun x -> + if String.lowercase (Xml.tag x) = "aircraft" then + let id = ExtXml.attrib x "ac_id" + and name = ExtXml.attrib x "name" in + if Hashtbl.mem ids id then begin + let other_name = Hashtbl.find ids id in + failwith (sprintf "Error: A/C Id '%s' duplicated in %s (%s and %s)" id conf_xml name other_name) + end; + if Hashtbl.mem names name then begin + let other_id = Hashtbl.find names name in + failwith (sprintf "Error: A/C name '%s' duplicated in %s (ids %s and %s)" name conf_xml id other_id) + end; + Hashtbl.add ids id name; + Hashtbl.add names name id) + (Xml.children conf) let pipe_regexp = Str.regexp "|" let targets_of_field = fun field -> try - Str.split pipe_regexp (ExtXml.attrib_or_default field "target" "ap|sim") + Str.split pipe_regexp (ExtXml.attrib_or_default field "target" "ap|sim") with - _ -> [] + _ -> [] (** singletonize a sorted list *) let rec singletonize = fun l -> match l with - [] | [_] -> l + [] | [_] -> l | x :: ((y :: t) as yt) -> if x = y then singletonize yt else x :: singletonize yt (** union of two lists *) @@ -87,28 +87,28 @@ let union_of_lists = fun l -> let get_modules = fun dir xml -> (* extract all "modules" sections *) let modules = List.map (fun x -> - match String.lowercase (Xml.tag x) with - "modules" -> Xml.children x - | _ -> [] - ) (Xml.children xml) in + match String.lowercase (Xml.tag x) with + "modules" -> Xml.children x + | _ -> [] + ) (Xml.children xml) in (* flatten the list (result is a list of "load" xml nodes) *) let modules = List.flatten modules in (* build a list (file name, (xml, xml list of flags)) *) let extract = List.map (fun m -> - match String.lowercase (Xml.tag m) with - "load" -> let file = dir // ExtXml.attrib m "name" in - (file, (ExtXml.parse_file file, Xml.children m)) - | tag -> failwith (sprintf "Warning: tag load is undefined; found '%s'" tag) - ) modules in + match String.lowercase (Xml.tag m) with + "load" -> let file = dir // ExtXml.attrib m "name" in + (file, (ExtXml.parse_file file, Xml.children m)) + | tag -> failwith (sprintf "Warning: tag load is undefined; found '%s'" tag) + ) modules in (* return a list of name and a list of pairs (xml, xml list) *) List.split extract (** [get_targets_of_module xml] Returns the list of targets of a module *) let get_targets_of_module = fun m -> let targets = List.map (fun x -> - match String.lowercase (Xml.tag x) with - "makefile" -> targets_of_field x - | _ -> [] + match String.lowercase (Xml.tag x) with + "makefile" -> targets_of_field x + | _ -> [] ) (Xml.children m) in (* return a singletonized list *) singletonize (List.sort compare (List.flatten targets)) @@ -120,8 +120,8 @@ let get_modules_dir = fun modules -> (** Search and dump the module section : - xml : the parsed airframe.xml - f : makefile.ac + xml : the parsed airframe.xml + f : makefile.ac **) let dump_module_section = fun xml f -> (* get modules *) @@ -142,167 +142,148 @@ let dump_module_section = fun xml f -> List.iter (fun dir -> let dir_name = (String.uppercase dir)^"_DIR" in fprintf f "%s = modules/%s\n" dir_name dir) dir_list; (* parse each module *) List.iter (fun (m, flags) -> - let name = ExtXml.attrib m "name" in - let dir = try Xml.attrib m "dir" with _ -> name in - let dir_name = (String.uppercase dir)^"_DIR" in - (* get the list of all the targes for this module *) - let module_target_list = get_targets_of_module m in - (* print global flags as compilation defines and flags *) - fprintf f "\n# makefile for module %s in modules/%s\n" name dir; - List.iter (fun flag -> + let name = ExtXml.attrib m "name" in + let dir = try Xml.attrib m "dir" with _ -> name in + let dir_name = (String.uppercase dir)^"_DIR" in + (* get the list of all the targets for this module *) + let module_target_list = get_targets_of_module m in + (* print global flags as compilation defines and flags *) + fprintf f "\n# makefile for module %s in modules/%s\n" name dir; + List.iter (fun flag -> match String.lowercase (Xml.tag flag) with "define" -> let value = Xml.attrib flag "value" and name = Xml.attrib flag "name" in fprintf f "%s = %s\n" name value | "flag" | "param" -> - List.iter (fun target -> - let name = ExtXml.attrib flag "name" - and value = try "="^(Xml.attrib flag "value") with _ -> "" in - fprintf f "%s.CFLAGS += -D%s%s\n" target name value - ) module_target_list + List.iter (fun target -> + let name = ExtXml.attrib flag "name" + and value = try "="^(Xml.attrib flag "value") with _ -> "" in + fprintf f "%s.CFLAGS += -D%s%s\n" target name value + ) module_target_list | _ -> () ) flags; - (* Look for makefile section *) - List.iter (fun l -> - if ExtXml.tag_is l "makefile" then begin - let targets = targets_of_field l in - (* Look for defines, flags, files, ... *) - List.iter (fun field -> - match String.lowercase (Xml.tag field) with - "flag" -> - List.iter (fun target -> - let value = try "="^(Xml.attrib field "value") with _ -> "" - and name = Xml.attrib field "name" in - let flag_type = match (ExtXml.attrib_or_default field "type" "define") with - "define" | "D" -> "D" - | "include" | "I" -> "I" - | _ -> "D" in - fprintf f "%s.CFLAGS += -%s%s%s\n" target flag_type name value - ) targets - | "file" -> - let name = Xml.attrib field "name" in - List.iter (fun target -> fprintf f "%s.srcs += $(%s)/%s\n" target dir_name name) targets - | "file_arch" -> - let name = Xml.attrib field "name" in - List.iter (fun target -> fprintf f "%s.srcs += arch/$(ARCH)/$(%s)/%s\n" target dir_name name) targets - | "file_hw" -> - let name = Xml.attrib field "name" in - List.iter (fun target -> fprintf f "%s.srcs += arch/$(ARCH)/$(%s)/%s\n" target dir_name name) targets - | "define" -> - let value = Xml.attrib field "value" - and name = Xml.attrib field "name" in - fprintf f "%s = %s\n" name value - | "raw" -> - begin match Xml.children field with - [Xml.PCData s] -> fprintf f "%s\n" s - | _ -> fprintf stderr "Warning: wrong makefile section in module '%s'\n" name - end - | _ -> () - ) (Xml.children l) - end) (Xml.children m) - ) modules; + (* Look for makefile section *) + List.iter (fun l -> + if ExtXml.tag_is l "makefile" then begin + let targets = targets_of_field l in + (* Look for defines, flags, files, ... *) + List.iter (fun field -> + match String.lowercase (Xml.tag field) with + "flag" -> + List.iter (fun target -> + let value = try "="^(Xml.attrib field "value") with _ -> "" + and name = Xml.attrib field "name" in + let flag_type = match (ExtXml.attrib_or_default field "type" "define") with + "define" | "D" -> "D" + | "include" | "I" -> "I" + | _ -> "D" in + fprintf f "%s.CFLAGS += -%s%s%s\n" target flag_type name value + ) targets + | "file" -> + let name = Xml.attrib field "name" in + List.iter (fun target -> fprintf f "%s.srcs += $(%s)/%s\n" target dir_name name) targets + | "file_arch" -> + let name = Xml.attrib field "name" in + List.iter (fun target -> fprintf f "%s.srcs += arch/$(ARCH)/$(%s)/%s\n" target dir_name name) targets + | "file_hw" -> + let name = Xml.attrib field "name" in + List.iter (fun target -> fprintf f "%s.srcs += arch/$(ARCH)/$(%s)/%s\n" target dir_name name) targets + | "define" -> + let value = Xml.attrib field "value" + and name = Xml.attrib field "name" in + fprintf f "%s = %s\n" name value + | "raw" -> + begin match Xml.children field with + [Xml.PCData s] -> fprintf f "%s\n" s + | _ -> fprintf stderr "Warning: wrong makefile section in module '%s'\n" name + end + | _ -> () + ) (Xml.children l) + end) (Xml.children m) + ) modules; (** returns a list of modules file name *) files (** - Search and dump the makefile sections + Search and dump the makefile sections **) -let dump_makefile_section = fun xml makefile_ac airframe_infile print_if_loc_after -> +let dump_makefile_section = fun xml makefile_ac airframe_infile location -> List.iter (fun x -> - if ExtXml.tag_is x "makefile" then begin - let located_before = ref true in - begin try - located_before := not (String.compare (Xml.attrib x "location") "after" = 0) - with _ -> () end; - if (not print_if_loc_after && !located_before) || (print_if_loc_after && not !located_before) then begin - begin try - fprintf makefile_ac "\n# makefile target '%s'\n" (Xml.attrib x "target") - with _ -> () end; - match Xml.children x with - [Xml.PCData s] -> fprintf makefile_ac "%s\n" s - | _ -> failwith (sprintf "Warning: wrong makefile section in '%s': %s\n" airframe_infile (Xml.to_string_fmt x)) - end - end) - (Xml.children xml) + if ExtXml.tag_is x "makefile" then begin + let loc = ExtXml.attrib_or_default x "location" "before" in + match (location, loc) with + ("before", "before") | ("after", "after") -> + fprintf makefile_ac "\n# raw makefile\n"; + begin match Xml.children x with + [Xml.PCData s] -> fprintf makefile_ac "%s\n" s + | _ -> failwith (sprintf "Warning: wrong makefile section in '%s': %s\n" airframe_infile (Xml.to_string_fmt x)) + end + | (_, _) -> () + end) + (Xml.children xml) -(** Firmware Children **) +(** + * Firmware Children + * **) -let parse_subsystems = fun makefile_ac tag firmware -> - match Xml.tag firmware with - "subsystem" -> - begin try - fprintf makefile_ac "# -subsystem: '%s' \n" (Xml.attrib firmware "name"); - let has_subtype = ref false in - begin try - has_subtype := not (String.compare (Xml.attrib firmware "type") "" = 0) - with _ -> () end; - let print_if_subsystem_define = (fun d -> - if ExtXml.tag_is d "param" then begin - fprintf makefile_ac "%s = %s\n" - (String.uppercase(Xml.attrib d "name")) - (Xml.attrib d "value"); - end) in - List.iter print_if_subsystem_define (Xml.children firmware); - fprintf makefile_ac "include $(CFG_%s)/%s" - (String.uppercase(Xml.attrib tag "name")) - (Xml.attrib firmware "name"); - if !has_subtype then - fprintf makefile_ac "_%s" - (Xml.attrib firmware "type"); - fprintf makefile_ac ".makefile\n" - with _ -> () end; - | _ -> () +(* print a param (firmware) *) +let print_firmware_param = fun f p -> + let name = (String.uppercase (Xml.attrib p "name")) + and value = (Xml.attrib p "value") in + fprintf f "%s = %s\n" name value -let parse_targets = fun makefile_ac tag target -> - match Xml.tag target with - | "target" -> - begin try - fprintf makefile_ac "\n###########\n# -target: '%s' \n" (Xml.attrib target "name"); - fprintf makefile_ac "ifeq ($(TARGET), %s) \n" (Xml.attrib target "name"); - let print_if_subsystem = (fun c -> - if ExtXml.tag_is c "param" then begin - fprintf makefile_ac "%s = %s\n" - (String.uppercase(Xml.attrib c "name")) - (Xml.attrib c "value") - end) in - List.iter print_if_subsystem (Xml.children target); - let has_processor = ref false in - begin try - has_processor := not (String.compare (Xml.attrib target "processor") "" = 0) - with _ -> () end; - if !has_processor then - fprintf makefile_ac "BOARD_PROCESSOR = %s\n" - (Xml.attrib target "processor"); - fprintf makefile_ac "include $(PAPARAZZI_SRC)/conf/boards/%s.makefile\n" (Xml.attrib target "board"); -(** fprintf makefile_ac "%s.ARCHDIR = $(ARCHI)\n" - (Xml.attrib target "name") (Xml.attrib target "name") - (Xml.attrib target "name") (Xml.attrib target "name") - (Xml.attrib target "name") (Xml.attrib target "name"); -**) fprintf makefile_ac "include $(PAPARAZZI_SRC)/conf/autopilot/%s.makefile\n" (Xml.attrib tag "name"); - let print_if_subsystem = (fun d -> - if ExtXml.tag_is d "define" then begin - let has_def_value = ref false in - begin try - has_def_value := not (String.compare (Xml.attrib d "value") "" = 0) - with _ -> () end; - fprintf makefile_ac "%s.CFLAGS += -D%s" - (Xml.attrib target "name") - (Xml.attrib d "name"); - if !has_def_value then - fprintf makefile_ac "=%s" (Xml.attrib d "value"); - fprintf makefile_ac "\n" - end) in - List.iter print_if_subsystem (Xml.children target); - List.iter (parse_subsystems makefile_ac tag) (Xml.children target ); (** dump target subsystems **) - List.iter (parse_subsystems makefile_ac tag) (Xml.children tag ); (** dump firware subsystems **) - fprintf makefile_ac "endif\n\n"; - with _ -> () end; - | "define" -> - let name = ExtXml.attrib target "name" - and value = try "="^(Xml.attrib target "value") with _ -> "" in - fprintf makefile_ac "$(TARGET).CFLAGS += -D%s%s\n" name value; - | _ -> () +(* print a define (firmware) *) +let print_firmware_define = fun f d -> + let name = ExtXml.attrib d "name" + and value = try "="^(Xml.attrib d "value") with _ -> "" in + fprintf f "$(TARGET).CFLAGS += -D%s%s\n" name value + +(* print a subsystem (firmware) *) +let print_firmware_subsystem = fun f firmware s -> + let name = ExtXml.attrib s "name" + and s_type = try "_"^(Xml.attrib s "type") with _ -> "" in + fprintf f "# -subsystem: '%s'\n" name; + (* print params *) + let s_params = List.filter (fun x -> ExtXml.tag_is x "param") (Xml.children s) in + List.iter (print_firmware_param f) s_params; + (* include subsystem *) (* TODO test if file exists with the generator ? *) + let s_name = name^s_type^".makefile" in + let s_dir = "CFG_"^(String.uppercase (Xml.attrib firmware "name")) in + fprintf f "ifneq ($(strip $(wildcard $(%s)/%s)),)\n" s_dir s_name; + fprintf f "\tinclude $(%s)/%s\n" s_dir s_name; + fprintf f "else\n"; + fprintf f "\tinclude $(CFG_SHARED)/%s\n" s_name; + fprintf f "endif\n" + +let parse_firmware = fun makefile_ac firmware -> + (* get the list of targets for this firmware *) + let targets = List.filter (fun x -> ExtXml.tag_is x "target") (Xml.children firmware) in + (* get the list of subsystems for this firmware *) + let subsystems = List.filter (fun x -> ExtXml.tag_is x "subsystem") (Xml.children firmware) in + (* get the list of defines for this firmware *) + let defines = List.filter (fun x -> ExtXml.tag_is x "define") (Xml.children firmware) in + (* iter on all targets *) + List.iter (fun target -> + (* get the list of params for this target *) + let t_params = List.filter (fun x -> ExtXml.tag_is x "param") (Xml.children target) in + (* get the list of defines for this target *) + let t_defines = List.filter (fun x -> ExtXml.tag_is x "define") (Xml.children target) in + (* get the list of subsystems for this target *) + let t_subsystems = List.filter (fun x -> ExtXml.tag_is x "subsystem") (Xml.children target) in + (* print makefile for this target *) + fprintf makefile_ac "\n###########\n# -target: '%s'\n" (Xml.attrib target "name"); + fprintf makefile_ac "ifeq ($(TARGET), %s)\n" (Xml.attrib target "name"); + try fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor") with _ -> (); + List.iter (print_firmware_param makefile_ac) t_params; + List.iter (print_firmware_define makefile_ac) defines; + List.iter (print_firmware_define makefile_ac) t_defines; + fprintf makefile_ac "include $(PAPARAZZI_SRC)/conf/boards/%s.makefile\n" (Xml.attrib target "board"); + fprintf makefile_ac "include $(PAPARAZZI_SRC)/conf/autopilot/%s.makefile\n" (Xml.attrib firmware "name"); + List.iter (print_firmware_subsystem makefile_ac firmware) t_subsystems; + List.iter (print_firmware_subsystem makefile_ac firmware) subsystems; + fprintf makefile_ac "endif\n\n" + ) targets (** @@ -310,15 +291,15 @@ let parse_targets = fun makefile_ac tag target -> **) let dump_firmware_sections = fun xml makefile_ac -> List.iter (fun tag -> - if ExtXml.tag_is tag "firmware" then begin - begin try - fprintf makefile_ac "\n####################################################\n"; - fprintf makefile_ac "# makefile firmware '%s' \n" (Xml.attrib tag "name"); - fprintf makefile_ac "####################################################\n"; - List.iter (parse_targets makefile_ac tag) (Xml.children tag ) - with _ -> () end; - end) - (Xml.children xml) + if ExtXml.tag_is tag "firmware" then begin + try + fprintf makefile_ac "\n####################################################\n"; + fprintf makefile_ac "# makefile firmware '%s'\n" (Xml.attrib tag "name"); + fprintf makefile_ac "####################################################\n"; + parse_firmware makefile_ac tag + with _ -> failwith "Warning: firmware name is undeclared" + end) + (Xml.children xml) @@ -330,12 +311,12 @@ let extract_makefile = fun airframe_file makefile_ac -> fprintf f "# This file has been generated from %s by %s\n" airframe_file Sys.argv.(0); fprintf f "# Please DO NOT EDIT\n"; - (** Search and dump makefile sections that don't have a "location" attribute set to "after" *) - dump_makefile_section xml f airframe_file false; + (** Search and dump makefile sections that have a "location" attribute set to "before" or no attribute *) + dump_makefile_section xml f airframe_file "before"; (** Search and dump the firmware sections *) dump_firmware_sections xml f; (** Search and dump makefile sections that have a "location" attribute set to "after" *) - dump_makefile_section xml f airframe_file true; + dump_makefile_section xml f airframe_file "after"; (** Look for modules *) let module_files = dump_module_section xml f in @@ -348,10 +329,10 @@ let is_older = fun target_file dep_files -> not (Sys.file_exists target_file) || let target_file_time = (U.stat target_file).U.st_mtime in let rec loop = function - [] -> false - | f::fs -> - target_file_time < (U.stat f).U.st_mtime || - loop fs in + [] -> false + | f::fs -> + target_file_time < (U.stat f).U.st_mtime || + loop fs in loop dep_files @@ -361,115 +342,115 @@ let make_element = fun t a c -> Xml.Element (t,a,c) (******************************* MAIN ****************************************) let () = try - if Array.length Sys.argv <> 2 then - failwith (sprintf "Usage: %s " Sys.argv.(0)); - let aircraft = Sys.argv.(1) in - let conf = Xml.parse_file conf_xml in - check_unique_id_and_name conf; - let aircraft_xml = - try - ExtXml.child conf ~select:(fun x -> Xml.attrib x "name" = aircraft) "aircraft" - with - Not_found -> failwith (sprintf "Aircraft '%s' not found in '%s'" aircraft conf_xml) - in + if Array.length Sys.argv <> 2 then + failwith (sprintf "Usage: %s " Sys.argv.(0)); + let aircraft = Sys.argv.(1) in + let conf = Xml.parse_file conf_xml in + check_unique_id_and_name conf; + let aircraft_xml = + try + ExtXml.child conf ~select:(fun x -> Xml.attrib x "name" = aircraft) "aircraft" + with + Not_found -> failwith (sprintf "Aircraft '%s' not found in '%s'" aircraft conf_xml) + in - let value = fun attrib -> ExtXml.attrib aircraft_xml attrib in + let value = fun attrib -> ExtXml.attrib aircraft_xml attrib in - let aircraft_dir = Env.paparazzi_home // "var" // aircraft in - let aircraft_conf_dir = aircraft_dir // "conf" in + let aircraft_dir = Env.paparazzi_home // "var" // aircraft in + let aircraft_conf_dir = aircraft_dir // "conf" in - mkdir (Env.paparazzi_home // "var"); - mkdir aircraft_dir; - mkdir (aircraft_dir // "fbw"); - mkdir (aircraft_dir // "autopilot"); - mkdir (aircraft_dir // "sim"); - mkdir aircraft_conf_dir; - mkdir (aircraft_conf_dir // "airframes"); - mkdir (aircraft_conf_dir // "flight_plans"); - mkdir (aircraft_conf_dir // "radios"); - mkdir (aircraft_conf_dir // "settings"); - mkdir (aircraft_conf_dir // "telemetry"); + mkdir (Env.paparazzi_home // "var"); + mkdir aircraft_dir; + mkdir (aircraft_dir // "fbw"); + mkdir (aircraft_dir // "autopilot"); + mkdir (aircraft_dir // "sim"); + mkdir aircraft_conf_dir; + mkdir (aircraft_conf_dir // "airframes"); + mkdir (aircraft_conf_dir // "flight_plans"); + mkdir (aircraft_conf_dir // "radios"); + mkdir (aircraft_conf_dir // "settings"); + mkdir (aircraft_conf_dir // "telemetry"); - let settings = - try value "settings" with - _ -> - fprintf stderr "\nWARNING: No 'settings' attribute specified for A/C '%s', using 'settings/basic.xml'\n\n%!" aircraft; - "settings/basic.xml" in + let settings = + try value "settings" with + _ -> + fprintf stderr "\nWARNING: No 'settings' attribute specified for A/C '%s', using 'settings/basic.xml'\n\n%!" aircraft; + "settings/basic.xml" in - (** Expands the configuration of the A/C into one single file *) - let conf_aircraft = Env.expand_ac_xml aircraft_xml in - let configuration = - make_element - "configuration" - [] - [make_element "conf" [] [conf_aircraft]; Pprz.messages_xml ()] in - let conf_aircraft_file = aircraft_conf_dir // "conf_aircraft.xml" in - let f = open_out conf_aircraft_file in - Printf.fprintf f "%s\n" (ExtXml.to_string_fmt configuration); - close_out f; + (** Expands the configuration of the A/C into one single file *) + let conf_aircraft = Env.expand_ac_xml aircraft_xml in + let configuration = + make_element + "configuration" + [] + [make_element "conf" [] [conf_aircraft]; Pprz.messages_xml ()] in + let conf_aircraft_file = aircraft_conf_dir // "conf_aircraft.xml" in + let f = open_out conf_aircraft_file in + Printf.fprintf f "%s\n" (ExtXml.to_string_fmt configuration); + close_out f; - (** Computes and store a signature of the configuration *) - let md5sum = Digest.to_hex (Digest.file conf_aircraft_file) in - let md5sum_file = aircraft_conf_dir // "aircraft.md5" in - (* Store only if different from previous one *) - if not (Sys.file_exists md5sum_file - && md5sum = input_line (open_in md5sum_file)) then begin - let f = open_out md5sum_file in - Printf.fprintf f "%s\n" md5sum; - close_out f; + (** Computes and store a signature of the configuration *) + let md5sum = Digest.to_hex (Digest.file conf_aircraft_file) in + let md5sum_file = aircraft_conf_dir // "aircraft.md5" in + (* Store only if different from previous one *) + if not (Sys.file_exists md5sum_file + && md5sum = input_line (open_in md5sum_file)) then begin + let f = open_out md5sum_file in + Printf.fprintf f "%s\n" md5sum; + close_out f; - (** Save the configuration for future use *) - let d = U.localtime (U.gettimeofday ()) in - let filename = sprintf "%02d_%02d_%02d__%02d_%02d_%02d_%s_%s.conf" (d.U.tm_year mod 100) (d.U.tm_mon+1) (d.U.tm_mday) (d.U.tm_hour) (d.U.tm_min) (d.U.tm_sec) md5sum aircraft in - let d = Env.paparazzi_home // "var" // "conf" in - mkdir d; - let f = open_out (d // filename) in - Printf.fprintf f "%s\n" (ExtXml.to_string_fmt configuration); - close_out f end; + (** Save the configuration for future use *) + let d = U.localtime (U.gettimeofday ()) in + let filename = sprintf "%02d_%02d_%02d__%02d_%02d_%02d_%s_%s.conf" (d.U.tm_year mod 100) (d.U.tm_mon+1) (d.U.tm_mday) (d.U.tm_hour) (d.U.tm_min) (d.U.tm_sec) md5sum aircraft in + let d = Env.paparazzi_home // "var" // "conf" in + mkdir d; + let f = open_out (d // filename) in + Printf.fprintf f "%s\n" (ExtXml.to_string_fmt configuration); + close_out f end; - let airframe_file = value "airframe" in + let airframe_file = value "airframe" in - let airframe_dir = Filename.dirname airframe_file in - let var_airframe_dir = aircraft_conf_dir // airframe_dir in - mkdir var_airframe_dir; - assert (Sys.command (sprintf "cp %s %s" (paparazzi_conf // airframe_file) var_airframe_dir) = 0); + let airframe_dir = Filename.dirname airframe_file in + let var_airframe_dir = aircraft_conf_dir // airframe_dir in + mkdir var_airframe_dir; + assert (Sys.command (sprintf "cp %s %s" (paparazzi_conf // airframe_file) var_airframe_dir) = 0); - (** Calls the Makefile with target and options *) - let make = fun target options -> - let c = sprintf "make -f Makefile.ac AIRCRAFT=%s AC_ID=%s AIRFRAME_XML=%s TELEMETRY=%s SETTINGS=\"%s\" MD5SUM=\"%s\" %s %s" aircraft (value "ac_id") airframe_file (value "telemetry") settings md5sum options target in - begin (** Quiet is speficied in the Makefile *) - try if Sys.getenv "Q" <> "@" then raise Not_found with - Not_found -> prerr_endline c - end; - let returned_code = Sys.command c in - if returned_code <> 0 then - exit returned_code in + (** Calls the Makefile with target and options *) + let make = fun target options -> + let c = sprintf "make -f Makefile.ac AIRCRAFT=%s AC_ID=%s AIRFRAME_XML=%s TELEMETRY=%s SETTINGS=\"%s\" MD5SUM=\"%s\" %s %s" aircraft (value "ac_id") airframe_file (value "telemetry") settings md5sum options target in + begin (** Quiet is speficied in the Makefile *) + try if Sys.getenv "Q" <> "@" then raise Not_found with + Not_found -> prerr_endline c + end; + let returned_code = Sys.command c in + if returned_code <> 0 then + exit returned_code in - (** Calls the makefile if the optional attribute is available *) - let make_opt = fun target var attr -> - try - let value = Xml.attrib aircraft_xml attr in - make target (sprintf "%s=%s" var value) - with - Xml.No_attribute _ -> () in + (** Calls the makefile if the optional attribute is available *) + let make_opt = fun target var attr -> + try + let value = Xml.attrib aircraft_xml attr in + make target (sprintf "%s=%s" var value) + with + Xml.No_attribute _ -> () in - let temp_makefile_ac = Filename.temp_file "Makefile.ac" "tmp" in - let abs_airframe_file = paparazzi_conf // airframe_file in + let temp_makefile_ac = Filename.temp_file "Makefile.ac" "tmp" in + let abs_airframe_file = paparazzi_conf // airframe_file in - let modules_files = extract_makefile abs_airframe_file temp_makefile_ac in + let modules_files = extract_makefile abs_airframe_file temp_makefile_ac in - (* Create Makefile.ac only if needed *) - let makefile_ac = aircraft_dir // "Makefile.ac" in - if is_older makefile_ac (abs_airframe_file :: modules_files) then begin - assert(Sys.command (sprintf "mv %s %s" temp_makefile_ac makefile_ac) = 0) - end; + (* Create Makefile.ac only if needed *) + let makefile_ac = aircraft_dir // "Makefile.ac" in + if is_older makefile_ac (abs_airframe_file :: modules_files) then begin + assert(Sys.command (sprintf "mv %s %s" temp_makefile_ac makefile_ac) = 0) + end; - (* Get TARGET env, needed to build modules.h according to the target *) - let t = Printf.sprintf "TARGET=%s" (try Sys.getenv "TARGET" with _ -> "") in - make "all_ac_h" t; - make_opt "radio_ac_h" "RADIO" "radio"; - make_opt "flight_plan_ac_h" "FLIGHT_PLAN" "flight_plan" + (* Get TARGET env, needed to build modules.h according to the target *) + let t = Printf.sprintf "TARGET=%s" (try Sys.getenv "TARGET" with _ -> "") in + make "all_ac_h" t; + make_opt "radio_ac_h" "RADIO" "radio"; + make_opt "flight_plan_ac_h" "FLIGHT_PLAN" "flight_plan" with - Failure f -> - prerr_endline f; - exit 1 + Failure f -> + prerr_endline f; + exit 1 diff --git a/sw/tools/gen_airframe.ml b/sw/tools/gen_airframe.ml index f35772e796..f438224ed0 100644 --- a/sw/tools/gen_airframe.ml +++ b/sw/tools/gen_airframe.ml @@ -2,7 +2,7 @@ * $Id$ * * XML preprocessing for airframe parameters - * + * * Copyright (C) 2003-2006 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. * *) @@ -59,7 +59,7 @@ let define_macro name n x = | 2 -> printf "x1,x2) (%s*(x1)+ %s*(x2))\n" (a "coeff1") (a "coeff2") | 3 -> printf "x1,x2,x3) (%s*(x1)+ %s*(x2)+%s*(x3))\n" (a "coeff1") (a "coeff2") (a "coeff3") | _ -> failwith "define_macro" - + let define_integer name v n = let max_val = 1 lsl n in let print = fun name num den -> @@ -84,11 +84,11 @@ let define_integer name v n = let parse_element = fun prefix s -> match Xml.tag s with "define" -> begin - try - define (prefix^ExtXml.attrib s "name") (ExtXml.display_entities (ExtXml.attrib s "value")); - define_integer (prefix^(ExtXml.attrib s "name")) (ExtXml.float_attrib s "value") (ExtXml.int_attrib s "integer"); - with _ -> (); - end + try + define (prefix^ExtXml.attrib s "name") (ExtXml.display_entities (ExtXml.attrib s "value")); + define_integer (prefix^(ExtXml.attrib s "name")) (ExtXml.float_attrib s "value") (ExtXml.int_attrib s "integer"); + with _ -> (); + end | "linear" -> let name = ExtXml.attrib s "name" and n = int_of_string (ExtXml.attrib s "arity") in @@ -107,7 +107,7 @@ let parse_servo = fun driver c -> let min = fos (ExtXml.attrib c "min" ) and neutral = fos (ExtXml.attrib c "neutral") and max = fos (ExtXml.attrib c "max" ) in - + let travel_up = (max-.neutral) /. max_pprz and travel_down = (neutral-.min) /. max_pprz in @@ -153,7 +153,7 @@ let parse_command_laws = fun command -> let var = a "var" and value = a "value" in let v = preprocess_value value "values" "COMMAND" in - printf " int16_t _var_%s = %s;\\\n" var v + printf " int16_t _var_%s = %s;\\\n" var v | "define" -> parse_element "" command | _ -> xml_error "set|let" @@ -162,7 +162,7 @@ let parse_csc_fields = fun csc_fields -> let a = fun s -> ExtXml.attrib csc_fields s in match Xml.tag csc_fields with "field_map" -> - let servo_id = a "servo_id" + let servo_id = a "servo_id" and field = a "field" in printf " temp.%s = actuators[%s]; \\\n" field servo_id; | _ -> xml_error "field_map" @@ -171,8 +171,8 @@ let parse_csc_messages = (let msg_index_ref = ref 0 in fun csc_id csc_messages - let a = fun s -> ExtXml.attrib csc_messages s in match Xml.tag csc_messages with "msg" -> - let msg_id = a "id" - and msg_type = a "type" + let msg_id = a "id" + and msg_type = a "type" and msg_index = msg_index_ref.contents in msg_index_ref.contents <- msg_index + 1; printf "{\\\n struct Csc%s temp; \\\n" msg_type; @@ -204,7 +204,7 @@ let parse_rc_commands = fun rc -> let var = a "var" and value = a "value" in let v = preprocess_value value "rc_values" "RADIO" in - printf " int16_t _var_%s = %s;\\\n" var v + printf " int16_t _var_%s = %s;\\\n" var v | "define" -> parse_element "" rc | _ -> xml_error "set|let" @@ -221,7 +221,7 @@ let parse_ap_only_commands = fun ap_only -> let parse_subsystem_defines = fun options -> match Xml.tag options with "param" -> - printf "// -param: %s\n" (ExtXml.attrib options "name") + printf "// -param: %s\n" (ExtXml.attrib options "name") | "define" -> printf "#define %s %s\n" (ExtXml.attrib options "name") (ExtXml.attrib options "value") | _ -> xml_error "define|param" @@ -230,7 +230,7 @@ let parse_subsystem_defines = fun options -> let parse_subsystems = fun subsystem -> match Xml.tag subsystem with "param" -> - printf "// subsystem parameter: %s\n" (ExtXml.attrib subsystem "name") + printf "// subsystem parameter: %s\n" (ExtXml.attrib subsystem "name") | "subsystem" -> printf "// -%s:\n" (ExtXml.attrib subsystem "name"); List.iter parse_subsystem_defines (Xml.children subsystem) @@ -307,7 +307,7 @@ let rec parse_section = fun s -> () (** Ignoring this section *) | _ -> () - + let h_name = "AIRFRAME_H" @@ -319,7 +319,7 @@ let hex_to_bin = fun s -> b.[4*i] <- '\\'; Scanf.sscanf (String.sub s (2*i) 2) "%2x" (fun x -> - String.blit (sprintf "%03o" x) 0 b (4*i+1) 3) + String.blit (sprintf "%03o" x) 0 b (4*i+1) 3) done; b diff --git a/sw/tools/gen_flight_plan.ml b/sw/tools/gen_flight_plan.ml index 35357f290d..8cee6ff50b 100644 --- a/sw/tools/gen_flight_plan.ml +++ b/sw/tools/gen_flight_plan.ml @@ -2,7 +2,7 @@ * $Id$ * * Flight plan preprocessing (from XML to C) - * + * * Copyright (C) 2004-2008 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. * *) @@ -50,9 +50,9 @@ let parse = fun s -> exit 1 in begin try - Expr_syntax.check_expression e + Expr_syntax.check_expression e with - Expr_syntax.Unknown_operator x -> unexpected "operator" x + Expr_syntax.Unknown_operator x -> unexpected "operator" x | Expr_syntax.Unknown_ident x -> unexpected "ident" x | Expr_syntax.Unknown_function x -> unexpected "function" x end @@ -78,7 +78,7 @@ let lprintf = fun f -> printf f -let float_attrib = fun xml a -> +let float_attrib = fun xml a -> try float_of_string (Xml.attrib xml a) with @@ -101,9 +101,9 @@ let localize_waypoint = fun rel_utm_of_wgs84 waypoint -> try let (x, y) = rel_utm_of_wgs84 - (Latlong.make_geo_deg - (Latlong.deg_of_string (Xml.attrib waypoint "lat")) - (Latlong.deg_of_string (Xml.attrib waypoint "lon"))) in + (Latlong.make_geo_deg + (Latlong.deg_of_string (Xml.attrib waypoint "lat")) + (Latlong.deg_of_string (Xml.attrib waypoint "lon"))) in let x = sprintf "%.2f" x and y = sprintf "%.2f" y in ExtXml.subst_attrib "y" y (ExtXml.subst_attrib "x" x waypoint) with @@ -145,7 +145,7 @@ let element = fun a b c -> Xml.Element (a, b, c) let goto l = element "goto" ["name",l] [] let exit_block = element "exit_block" [] [] let home_block = Xml.parse_string "" - + let stage = ref 0 let output_label l = lprintf "Label(%s)\n" l @@ -161,7 +161,7 @@ let pprz_throttle = fun s -> try let g = float_of_string s in if g < 0. || g > 1. then - failwith "throttle must be > 0 and < 1" + failwith "throttle must be > 0 and < 1" with Failure "float_of_string" -> () (* No possible check on expression *) end; @@ -181,20 +181,20 @@ let output_vmode = fun stage_xml wp last_wp -> begin match vmode with "climb" -> - lprintf "NavVerticalClimbMode(%s);\n" (parsed_attrib stage_xml "climb") + lprintf "NavVerticalClimbMode(%s);\n" (parsed_attrib stage_xml "climb") | "alt" -> - let alt = - try - let a = parsed_attrib stage_xml "alt" in - begin - try - check_altitude (float_of_string a) stage_xml - with - (* Impossible to check the altitude on an expression: *) - Failure "float_of_string" -> () - end; - a - with _ -> + let alt = + try + let a = parsed_attrib stage_xml "alt" in + begin + try + check_altitude (float_of_string a) stage_xml + with + (* Impossible to check the altitude on an expression: *) + Failure "float_of_string" -> () + end; + a + with _ -> try let h = parsed_attrib stage_xml "height" in begin @@ -204,19 +204,19 @@ let output_vmode = fun stage_xml wp last_wp -> (* Impossible to check the altitude on an expression: *) Failure "float_of_string" -> () end; - sprintf "Height(%s)" h + sprintf "Height(%s)" h with _ -> - if wp = "" - then failwith "alt or waypoint required in alt vmode" - else sprintf "WaypointAlt(%s)" wp in - lprintf "NavVerticalAltitudeMode(%s, 0.);\n" alt; + if wp = "" + then failwith "alt or waypoint required in alt vmode" + else sprintf "WaypointAlt(%s)" wp in + lprintf "NavVerticalAltitudeMode(%s, 0.);\n" alt; | "xyz" -> () (** Handled in Goto3D() *) | "glide" -> - lprintf "NavGlide(%s, %s);\n" last_wp wp + lprintf "NavGlide(%s, %s);\n" last_wp wp | "throttle" -> - if (pitch = "auto") then - failwith "auto pich mode not compatible with vmode=throttle"; - lprintf "NavVerticalThrottleMode(%s);\n" (pprz_throttle (parsed_attrib stage_xml "throttle")) + if (pitch = "auto") then + failwith "auto pich mode not compatible with vmode=throttle"; + lprintf "NavVerticalThrottleMode(%s);\n" (pprz_throttle (parsed_attrib stage_xml "throttle")) | x -> failwith (sprintf "Unknown vmode '%s'" x) end; vmode @@ -227,20 +227,20 @@ let output_hmode x wp last_wp = let hmode = ExtXml.attrib x "hmode" in begin match hmode with - "route" -> - if last_wp = "last_wp" then - fprintf stderr "Warning: Deprecated use of 'route' using last waypoint in %s\n"(Xml.to_string x); - lprintf "NavSegment(%s, %s);\n" last_wp wp + "route" -> + if last_wp = "last_wp" then + fprintf stderr "Warning: Deprecated use of 'route' using last waypoint in %s\n"(Xml.to_string x); + lprintf "NavSegment(%s, %s);\n" last_wp wp | "direct" -> lprintf "NavGotoWaypoint(%s);\n" wp | x -> failwith (sprintf "Unknown hmode '%s'" x) end; hmode with ExtXml.Error _ -> lprintf "NavGotoWaypoint(%s);\n" wp; "direct" (* Default behaviour *) - - + + let rec index_stage = fun x -> begin match Xml.tag x with @@ -259,13 +259,13 @@ let rec index_stage = fun x -> Xml.Element (Xml.tag x, Xml.attribs x@["no", soi n], l) | "return" | "goto" | "deroute" | "exit_block" | "follow" | "call" | "home" | "heading" | "attitude" | "go" | "stay" | "xyz" | "set" | "circle" -> - incr stage; - Xml.Element (Xml.tag x, Xml.attribs x@["no", soi !stage], Xml.children x) + incr stage; + Xml.Element (Xml.tag x, Xml.attribs x@["no", soi !stage], Xml.children x) | "survey_rectangle" | "eight" | "oval"-> - incr stage; incr stage; - Xml.Element (Xml.tag x, Xml.attribs x@["no", soi !stage], Xml.children x) + incr stage; incr stage; + Xml.Element (Xml.tag x, Xml.attribs x@["no", soi !stage], Xml.children x) | "exception" -> - x + x | s -> failwith (sprintf "Unknown stage: %s\n" s) end @@ -277,213 +277,213 @@ let rec print_stage = fun index_of_waypoints x -> begin match String.lowercase (Xml.tag x) with "return" -> - stage (); - lprintf "Return()\n"; - lprintf "break\n"; + stage (); + lprintf "Return()\n"; + lprintf "break\n"; | "goto" -> - stage (); - lprintf "Goto(%s)\n" (name_of x) + stage (); + lprintf "Goto(%s)\n" (name_of x) | "deroute" -> - stage (); - lprintf "GotoBlock(%d);\n" (get_index_block (ExtXml.attrib x "block")); - lprintf "break;\n" + stage (); + lprintf "GotoBlock(%d);\n" (get_index_block (ExtXml.attrib x "block")); + lprintf "break;\n" | "exit_block" -> - lprintf "default:\n"; - stage (); - lprintf "NextBlock();\n"; - lprintf "break;\n" + lprintf "default:\n"; + stage (); + lprintf "NextBlock();\n"; + lprintf "break;\n" | "while" -> - let w = gen_label "while" in - let e = gen_label "endwhile" in - output_label w; - stage (); - let c = try parsed_attrib x "cond" with _ -> "TRUE" in - lprintf "if (! (%s)) Goto(%s) else NextStageAndBreak();\n" c e; - List.iter (print_stage index_of_waypoints) (Xml.children x); - print_stage index_of_waypoints (goto w); - output_label e + let w = gen_label "while" in + let e = gen_label "endwhile" in + output_label w; + stage (); + let c = try parsed_attrib x "cond" with _ -> "TRUE" in + lprintf "if (! (%s)) Goto(%s) else NextStageAndBreak();\n" c e; + List.iter (print_stage index_of_waypoints) (Xml.children x); + print_stage index_of_waypoints (goto w); + output_label e | "for" -> - let f = gen_label "for" in - let e = gen_label "endfor" in - let v = Expr_syntax.c_var_of_ident (ExtXml.attrib x "var") - and from_ = parsed_attrib x "from" - and to_expr = parsed_attrib x "to" in - let to_var = v ^ "_to" in - lprintf "static int8_t %s;\n" v; - lprintf "static int8_t %s;\n" to_var; - - (* init *) - stage (); - lprintf "%s = %s - 1;\n" v from_; - lprintf "%s = %s;\n" to_var to_expr; - left (); + let f = gen_label "for" in + let e = gen_label "endfor" in + let v = Expr_syntax.c_var_of_ident (ExtXml.attrib x "var") + and from_ = parsed_attrib x "from" + and to_expr = parsed_attrib x "to" in + let to_var = v ^ "_to" in + lprintf "static int8_t %s;\n" v; + lprintf "static int8_t %s;\n" to_var; - output_label f; - stage (); - lprintf "if (++%s > %s) Goto(%s) else NextStageAndBreak();\n" v to_var e; - List.iter (print_stage index_of_waypoints) (Xml.children x); - print_stage index_of_waypoints (goto f); - output_label e + (* init *) + stage (); + lprintf "%s = %s - 1;\n" v from_; + lprintf "%s = %s;\n" to_var to_expr; + left (); + + output_label f; + stage (); + lprintf "if (++%s > %s) Goto(%s) else NextStageAndBreak();\n" v to_var e; + List.iter (print_stage index_of_waypoints) (Xml.children x); + print_stage index_of_waypoints (goto f); + output_label e | "heading" -> - stage (); - let until = parsed_attrib x "until" in - lprintf "if (%s) NextStageAndBreak() else {\n" until; - right (); - lprintf "NavHeading(RadOfDeg(%s));\n" (parsed_attrib x "course"); - ignore (output_vmode x "" ""); - left (); lprintf "}\n"; - lprintf "break;\n" + stage (); + let until = parsed_attrib x "until" in + lprintf "if (%s) NextStageAndBreak() else {\n" until; + right (); + lprintf "NavHeading(RadOfDeg(%s));\n" (parsed_attrib x "course"); + ignore (output_vmode x "" ""); + left (); lprintf "}\n"; + lprintf "break;\n" | "follow" -> - stage (); - let id = ExtXml.attrib x "ac_id" - and d = ExtXml.attrib x "distance" - and h = ExtXml.attrib x "height" in - lprintf "NavFollow(%s, %s, %s);\n" id d h; - lprintf "break;\n" + stage (); + let id = ExtXml.attrib x "ac_id" + and d = ExtXml.attrib x "distance" + and h = ExtXml.attrib x "height" in + lprintf "NavFollow(%s, %s, %s);\n" id d h; + lprintf "break;\n" | "attitude" -> - stage (); - begin - try - let until = parsed_attrib x "until" in - lprintf "if (%s) NextStageAndBreak() else {\n" until; - with ExtXml.Error _ -> - lprintf "{\n" - end; - right (); - lprintf "NavAttitude(RadOfDeg(%s));\n" (parsed_attrib x "roll"); - ignore (output_vmode x "" ""); - left (); lprintf "}\n"; - lprintf "break;\n" + stage (); + begin + try + let until = parsed_attrib x "until" in + lprintf "if (%s) NextStageAndBreak() else {\n" until; + with ExtXml.Error _ -> + lprintf "{\n" + end; + right (); + lprintf "NavAttitude(RadOfDeg(%s));\n" (parsed_attrib x "roll"); + ignore (output_vmode x "" ""); + left (); lprintf "}\n"; + lprintf "break;\n" | "go" -> - stage (); - let wp = - try - get_index_waypoint (ExtXml.attrib x "wp") index_of_waypoints - with - ExtXml.Error _ -> - lprintf "waypoints[0].x = %s;\n" (parsed_attrib x "x"); - lprintf "waypoints[0].y = %s;\n" (parsed_attrib x "y"); - "0" - in - let at = try ExtXml.attrib x "approaching_time" with _ -> "CARROT" in - let last_wp = - try - get_index_waypoint (ExtXml.attrib x "from") index_of_waypoints - with ExtXml.Error _ -> "last_wp" in - if last_wp = "last_wp" then - lprintf "if (NavApproaching(%s,%s)) NextStageAndBreakFrom(%s) else {\n" wp at wp - else - lprintf "if (NavApproachingFrom(%s,%s,%s)) NextStageAndBreakFrom(%s) else {\n" wp last_wp at wp; - right (); - let hmode = output_hmode x wp last_wp in - let vmode = output_vmode x wp last_wp in - if vmode = "glide" && hmode <> "route" then - failwith "glide vmode requires route hmode"; - left (); lprintf "}\n"; - lprintf "break;\n" + stage (); + let wp = + try + get_index_waypoint (ExtXml.attrib x "wp") index_of_waypoints + with + ExtXml.Error _ -> + lprintf "waypoints[0].x = %s;\n" (parsed_attrib x "x"); + lprintf "waypoints[0].y = %s;\n" (parsed_attrib x "y"); + "0" + in + let at = try ExtXml.attrib x "approaching_time" with _ -> "CARROT" in + let last_wp = + try + get_index_waypoint (ExtXml.attrib x "from") index_of_waypoints + with ExtXml.Error _ -> "last_wp" in + if last_wp = "last_wp" then + lprintf "if (NavApproaching(%s,%s)) NextStageAndBreakFrom(%s) else {\n" wp at wp + else + lprintf "if (NavApproachingFrom(%s,%s,%s)) NextStageAndBreakFrom(%s) else {\n" wp last_wp at wp; + right (); + let hmode = output_hmode x wp last_wp in + let vmode = output_vmode x wp last_wp in + if vmode = "glide" && hmode <> "route" then + failwith "glide vmode requires route hmode"; + left (); lprintf "}\n"; + lprintf "break;\n" | "stay" -> - stage (); - begin - try - let wp = get_index_waypoint (ExtXml.attrib x "wp") index_of_waypoints in - ignore (output_hmode x wp ""); - ignore (output_vmode x wp ""); - with - Xml2h.Error _ -> - lprintf "NavGotoXY(last_x, last_y);\n"; - ignore(output_vmode x "" "") - end; - begin - try - let c = parsed_attrib x "until" in - lprintf "if (%s) NextStageAndBreak();\n" c - with - ExtXml.Error _ -> () - end; - lprintf "break;\n" + stage (); + begin + try + let wp = get_index_waypoint (ExtXml.attrib x "wp") index_of_waypoints in + ignore (output_hmode x wp ""); + ignore (output_vmode x wp ""); + with + Xml2h.Error _ -> + lprintf "NavGotoXY(last_x, last_y);\n"; + ignore(output_vmode x "" "") + end; + begin + try + let c = parsed_attrib x "until" in + lprintf "if (%s) NextStageAndBreak();\n" c + with + ExtXml.Error _ -> () + end; + lprintf "break;\n" | "xyz" -> - stage (); - let r = try parsed_attrib x "radius" with _ -> "100" in - lprintf "Goto3D(%s)\n" r; - let x = ExtXml.subst_attrib "vmode" "xyz" x in - ignore (output_vmode x "" ""); (** To handle "pitch" *) - lprintf "break;\n" + stage (); + let r = try parsed_attrib x "radius" with _ -> "100" in + lprintf "Goto3D(%s)\n" r; + let x = ExtXml.subst_attrib "vmode" "xyz" x in + ignore (output_vmode x "" ""); (** To handle "pitch" *) + lprintf "break;\n" | "home" -> - stage (); - lprintf "nav_home();\n"; - lprintf "break;\n" + stage (); + lprintf "nav_home();\n"; + lprintf "break;\n" | "circle" -> - stage (); - let wp = get_index_waypoint (ExtXml.attrib x "wp") index_of_waypoints in - let r = parsed_attrib x "radius" in - let _vmode = output_vmode x wp "" in - lprintf "NavCircleWaypoint(%s, %s);\n" wp r; - begin - try - let c = parsed_attrib x "until" in - lprintf "if (%s) NextStageAndBreak();\n" c - with - ExtXml.Error _ -> () - end; - lprintf "break;\n" + stage (); + let wp = get_index_waypoint (ExtXml.attrib x "wp") index_of_waypoints in + let r = parsed_attrib x "radius" in + let _vmode = output_vmode x wp "" in + lprintf "NavCircleWaypoint(%s, %s);\n" wp r; + begin + try + let c = parsed_attrib x "until" in + lprintf "if (%s) NextStageAndBreak();\n" c + with + ExtXml.Error _ -> () + end; + lprintf "break;\n" | "eight" -> - stage (); - lprintf "nav_eight_init();\n"; - lprintf "NextStageAndBreak();\n"; - left (); - stage (); - let center = get_index_waypoint (ExtXml.attrib x "center") index_of_waypoints - and turn_about = get_index_waypoint (ExtXml.attrib x "turn_around") index_of_waypoints in - let r = parsed_attrib x "radius" in - let _vmode = output_vmode x center "" in - lprintf "Eight(%s, %s, %s);\n" center turn_about r; - lprintf "break;\n" + stage (); + lprintf "nav_eight_init();\n"; + lprintf "NextStageAndBreak();\n"; + left (); + stage (); + let center = get_index_waypoint (ExtXml.attrib x "center") index_of_waypoints + and turn_about = get_index_waypoint (ExtXml.attrib x "turn_around") index_of_waypoints in + let r = parsed_attrib x "radius" in + let _vmode = output_vmode x center "" in + lprintf "Eight(%s, %s, %s);\n" center turn_about r; + lprintf "break;\n" | "oval" -> - stage (); - lprintf "nav_oval_init();\n"; - lprintf "NextStageAndBreak();\n"; - left (); - stage (); - let p1 = get_index_waypoint (ExtXml.attrib x "p1") index_of_waypoints - and p2 = get_index_waypoint (ExtXml.attrib x "p2") index_of_waypoints in - let r = parsed_attrib x "radius" in - let _vmode = output_vmode x p1 "" in - lprintf "Oval(%s, %s, %s);\n" p1 p2 r; - begin - try - let c = parsed_attrib x "until" in - lprintf "if (%s) NextStageAndBreak();\n" c - with - ExtXml.Error _ -> () - end; - lprintf "break;\n" + stage (); + lprintf "nav_oval_init();\n"; + lprintf "NextStageAndBreak();\n"; + left (); + stage (); + let p1 = get_index_waypoint (ExtXml.attrib x "p1") index_of_waypoints + and p2 = get_index_waypoint (ExtXml.attrib x "p2") index_of_waypoints in + let r = parsed_attrib x "radius" in + let _vmode = output_vmode x p1 "" in + lprintf "Oval(%s, %s, %s);\n" p1 p2 r; + begin + try + let c = parsed_attrib x "until" in + lprintf "if (%s) NextStageAndBreak();\n" c + with + ExtXml.Error _ -> () + end; + lprintf "break;\n" | "set" -> - stage (); - let var = ExtXml.attrib x "var" - and value = parsed_attrib x "value" in - lprintf "%s = %s;\n" var value; - lprintf "NextStageAndBreak();\n"; - lprintf "break;\n" + stage (); + let var = ExtXml.attrib x "var" + and value = parsed_attrib x "value" in + lprintf "%s = %s;\n" var value; + lprintf "NextStageAndBreak();\n"; + lprintf "break;\n" | "call" -> - stage (); - let statement = ExtXml.attrib x "fun" in - lprintf "if (! (%s))\n" statement; - lprintf " NextStageAndBreak();\n"; - lprintf "break;\n" + stage (); + let statement = ExtXml.attrib x "fun" in + lprintf "if (! (%s))\n" statement; + lprintf " NextStageAndBreak();\n"; + lprintf "break;\n" | "survey_rectangle" -> - let grid = parsed_attrib x "grid" - and wp1 = get_index_waypoint (ExtXml.attrib x "wp1") index_of_waypoints - and wp2 = get_index_waypoint (ExtXml.attrib x "wp2") index_of_waypoints - and orientation = ExtXml.attrib_or_default x "orientation" "NS" in - stage (); - if orientation <> "NS" && orientation <> "WE" then - failwith (sprintf "Unknown survey orientation (NS or WE): %s" orientation); - lprintf "NavSurveyRectangleInit(%s, %s, %s, %s);\n" wp1 wp2 grid orientation; - lprintf "NextStageAndBreak();\n"; - left (); - stage (); - lprintf "NavSurveyRectangle(%s, %s);\n" wp1 wp2; - lprintf "break;\n" + let grid = parsed_attrib x "grid" + and wp1 = get_index_waypoint (ExtXml.attrib x "wp1") index_of_waypoints + and wp2 = get_index_waypoint (ExtXml.attrib x "wp2") index_of_waypoints + and orientation = ExtXml.attrib_or_default x "orientation" "NS" in + stage (); + if orientation <> "NS" && orientation <> "WE" then + failwith (sprintf "Unknown survey orientation (NS or WE): %s" orientation); + lprintf "NavSurveyRectangleInit(%s, %s, %s, %s);\n" wp1 wp2 grid orientation; + lprintf "NextStageAndBreak();\n"; + left (); + stage (); + lprintf "NavSurveyRectangle(%s, %s);\n" wp1 wp2; + lprintf "break;\n" | _s -> failwith "Unreachable" end; left () @@ -496,21 +496,21 @@ let indexed_stages = fun blocks -> let block_name = name_of b and block_no = ExtXml.attrib b "no" in let rec f = fun stage -> - try - let stage_no = Xml.attrib stage "no" in - lstages := - Xml.Element ("stage", [ "block", block_no; - "block_name", block_name; - "stage", stage_no], [stage]):: !lstages; - if (ExtXml.tag_is stage "for" || ExtXml.tag_is stage "while") then - List.iter f (Xml.children stage) - with Xml.No_attribute "no" -> - assert (ExtXml.tag_is stage "exception") + try + let stage_no = Xml.attrib stage "no" in + lstages := + Xml.Element ("stage", [ "block", block_no; + "block_name", block_name; + "stage", stage_no], [stage]):: !lstages; + if (ExtXml.tag_is stage "for" || ExtXml.tag_is stage "while") then + List.iter f (Xml.children stage) + with Xml.No_attribute "no" -> + assert (ExtXml.tag_is stage "exception") in List.iter f (Xml.children b)) blocks; !lstages - + @@ -519,17 +519,17 @@ let index_blocks = fun xml -> let indexed_blocks = List.map (fun b -> - incr block; - let name = name_of b in - if List.mem_assoc name !index_of_blocks then - failwith (Printf.sprintf "Error in flight plan: Block '%s' defined twice" name); - index_of_blocks := (name, !block) :: !index_of_blocks; - stage := -1; - let indexed_stages = List.map index_stage (Xml.children b) in - Xml.Element (Xml.tag b, Xml.attribs b@["no", soi !block], indexed_stages)) + incr block; + let name = name_of b in + if List.mem_assoc name !index_of_blocks then + failwith (Printf.sprintf "Error in flight plan: Block '%s' defined twice" name); + index_of_blocks := (name, !block) :: !index_of_blocks; + stage := -1; + let indexed_stages = List.map index_stage (Xml.children b) in + Xml.Element (Xml.tag b, Xml.attribs b@["no", soi !block], indexed_stages)) (Xml.children xml) in Xml.Element (Xml.tag xml, Xml.attribs xml, indexed_blocks) - + let print_block = fun index_of_waypoints (b:Xml.xml) block_num -> @@ -580,10 +580,10 @@ let home = fun waypoints -> let rec loop i = function [] -> failwith "Waypoint 'HOME' required" | w::ws -> - if name_of w = "HOME" then - (float_attrib w "x", float_attrib w "y") - else - loop (i+1) ws in + if name_of w = "HOME" then + (float_attrib w "x", float_attrib w "y") + else + loop (i+1) ws in loop 0 waypoints @@ -593,7 +593,7 @@ let check_distance = fun (hx, hy) max_d wp -> let d = sqrt ((x-.hx)**2. +. (y-.hy)**2.) in if d > max_d then fprintf stderr "\nWarning: Waypoint '%s' too far from HOME (%.0f>%.0f)\n\n" (name_of wp) d max_d - + (* Check coherence between global ref and waypoints ref *) (* Returns a patched xml with utm_x0 and utm_y0 set *) @@ -614,12 +614,12 @@ let check_geo_ref = fun wgs84 xml -> let x = ExtXml.subst_child "waypoints" wpts xml in x -let dummy_waypoint = - Xml.Element ("waypoint", - ["name", "dummy"; - "x", "42."; - "y", "42." ], - []) +let dummy_waypoint = + Xml.Element ("waypoint", + ["name", "dummy"; + "x", "42."; + "y", "42." ], + []) @@ -629,12 +629,12 @@ let print_inside_polygon = fun pts -> if i = j then let {G2D.top=yl; left_side=(xg, ag); right_side=(xd, ad)} = layers.(i) in if xg > xd then begin - lprintf "return FALSE;\n" + lprintf "return FALSE;\n" end else begin - if ad <> 0. || ag <> 0. then - lprintf "float dy = _y - %.1f;\n" yl; - let dy_times = fun f -> if f = 0. then "" else sprintf "+dy*%f" f in - lprintf "return (%.1f%s<= _x && _x <= %.1f%s);\n" xg (dy_times ag) xd (dy_times ad) + if ad <> 0. || ag <> 0. then + lprintf "float dy = _y - %.1f;\n" yl; + let dy_times = fun f -> if f = 0. then "" else sprintf "+dy*%f" f in + lprintf "return (%.1f%s<= _x && _x <= %.1f%s);\n" xg (dy_times ag) xd (dy_times ad) end else let ij2 = (i+j) / 2 in @@ -670,14 +670,14 @@ let parse_wpt_sector = fun waypoints xml -> Not_found -> failwith (sprintf "Error: corner '%s' of sector '%s' not found" name sector_name) in (sector_name, List.map p2D_of (Xml.children xml)) - + (************************** MAIN ******************************************) let () = let xml_file = ref "fligh_plan.xml" and dump = ref false in Arg.parse [ ("-check", Arg.Set check_expressions, "Enable expression checking"); - ("-dump", Arg.Set dump, "Dump compile result") ] + ("-dump", Arg.Set dump, "Dump compile result") ] (fun f -> xml_file := f) "Usage:"; if !xml_file = "" then @@ -718,25 +718,25 @@ let () = let h_name = "FLIGHT_PLAN_H" in printf "/* This file has been generated from %s */\n" !xml_file; printf "/* Please DO NOT EDIT */\n\n"; - + printf "#ifndef %s\n" h_name; Xml2h.define h_name ""; printf "\n"; - + printf "#include \"std.h\"\n"; - printf "#include \"modules.h\"\n"; + printf "#include \"generated/modules.h\"\n"; begin - try - let header = ExtXml.child (ExtXml.child xml "header") "0" in - printf "%s\n" (Xml.pcdata header) - with _ -> () + try + let header = ExtXml.child (ExtXml.child xml "header") "0" in + printf "%s\n" (Xml.pcdata header) + with _ -> () end; let name = ExtXml.attrib xml "name" in Xml2h.warning ("FLIGHT PLAN: "^name); Xml2h.define_string "FLIGHT_PLAN_NAME" name; - + let get_float = fun x -> float_attrib xml x in let qfu = try get_float "qfu" with Xml.No_attribute "qfu" -> 0. and mdfh = get_float "max_dist_from_home" @@ -753,9 +753,9 @@ let () = Xml2h.define "NAV_LON0" (sprintf "%d /* 1e7deg */" (convert_angle wgs84.posn_long)); Xml2h.define "NAV_ALT0" (sprintf "%.0f /* cm from msl */" (100. *. !ground_alt)); Xml2h.define "NAV_HMSL0" (sprintf "%.0f /* cm, msl from ellipsoid (EGM96) */" (100. *. Egm96.of_wgs84 wgs84)); - + Xml2h.define "QFU" (sprintf "%.1f" qfu); - + let waypoints = dummy_waypoint :: waypoints in let (hx, hy) = home waypoints in @@ -777,10 +777,10 @@ let () = Xml2h.define "SECURITY_HEIGHT" (sof !security_height); Xml2h.define "SECURITY_ALT" (sof (!security_height +. !ground_alt)); Xml2h.define "MAX_DIST_FROM_HOME" (sof mdfh); - + let index_of_waypoints = - let i = ref (-1) in - List.map (fun w -> incr i; (name_of w, !i)) waypoints in + let i = ref (-1) in + List.map (fun w -> incr i; (name_of w, !i)) waypoints in let sectors_element = try ExtXml.child xml "sectors" with Not_found -> Xml.Element ("", [], []) in let sectors = List.filter (fun x -> String.lowercase (Xml.tag x) = "sector") (Xml.children sectors_element) in @@ -795,7 +795,7 @@ let () = right (); print_blocks index_of_waypoints blocks; lprintf "default: break;\n"; - left (); + left (); lprintf "}\n"; left (); lprintf "}\n"; @@ -812,6 +812,5 @@ let () = Xml2h.finish h_name end with - Failure x -> + Failure x -> fprintf stderr "%s: %s\n" !xml_file x; exit 1 - diff --git a/sw/tools/gen_modules.ml b/sw/tools/gen_modules.ml index 319d6653c6..8c203f018c 100644 --- a/sw/tools/gen_modules.ml +++ b/sw/tools/gen_modules.ml @@ -2,7 +2,7 @@ * $Id$ * * XML preprocessing for modules - * + * * Copyright (C) 2009 Gautier Hattenberger * * 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. * *) @@ -102,7 +102,7 @@ let remove_dup = fun l -> match l with [] | [_] -> l | x::((x'::_) as xs) -> - if x = x' then loop xs else x::loop xs in + if x = x' then loop xs else x::loop xs in loop (List.sort compare l) let print_periodic_functions = fun modules -> @@ -117,7 +117,7 @@ let print_periodic_functions = fun modules -> let functions_modulo = List.flatten (List.map (fun m -> let periodic = List.filter (fun i -> (String.compare (Xml.tag i) "periodic") == 0) (Xml.children m) in let module_name = ExtXml.attrib m "name" in - List.map (fun x -> + List.map (fun x -> try let p = float_of_string (Xml.attrib x "period") in let _ = try let _ = Xml.attrib x "freq" in fprintf stderr "Warning: both period and freq are defined but only period is used for function %s\n" (ExtXml.attrib x "fun") with _ -> () in @@ -178,7 +178,7 @@ let print_periodic_functions = fun modules -> lprintf out_h "}\n"; end end - else + else begin if (test_delay func) then begin (** Delay is set by user *) @@ -229,7 +229,7 @@ let print_event_functions = fun modules -> let print_datalink_functions = fun modules -> lprintf out_h "\n#include \"messages.h\"\n"; - lprintf out_h "#include \"airframe.h\"\n"; + lprintf out_h "#include \"generated/airframe.h\"\n"; lprintf out_h "static inline void modules_parse_datalink(uint8_t msg_id __attribute__ ((unused))) {\n"; right (); let else_ = ref "" in @@ -267,16 +267,16 @@ let get_modules = fun dir m -> let name = ExtXml.attrib m "name" in let xml = Xml.parse_file (dir^name) in xml - end + end | _ -> xml_error "load" let test_section_modules = fun xml -> - List.fold_right (fun x r -> ExtXml.tag_is x "modules" || r) (Xml.children xml) false + List.fold_right (fun x r -> ExtXml.tag_is x "modules" || r) (Xml.children xml) false (** Check dependencies *) let pipe_regexp = Str.regexp "|" let dep_of_field = fun field att -> - try + try Str.split pipe_regexp (Xml.attrib field att) with _ -> [] @@ -310,7 +310,7 @@ let write_settings = fun xml_file out_set modules -> match Xml.tag i with "periodic" -> if not (is_status_lock i) then begin - if (not !setting_exist) then begin + if (not !setting_exist) then begin fprintf out_set " \n"; setting_exist := true; end; @@ -326,7 +326,7 @@ let write_settings = fun xml_file out_set modules -> let get_targets_of_module = fun m -> let pipe_regexp = Str.regexp "|" in - let targets_of_field = fun field -> try + let targets_of_field = fun field -> try Str.split pipe_regexp (ExtXml.attrib_or_default field "target" "ap|sim") with _ -> [] in let rec singletonize = fun l -> match l with @@ -380,7 +380,7 @@ let () = freq := main_freq; let modules_list = List.map (get_modules modules_dir) (Xml.children modules) in let modules_list = unload_unused_modules modules_list in - let modules_name = + let modules_name = (List.map (fun l -> try Xml.attrib l "name" with _ -> "") (Xml.children modules)) @ (List.map (fun m -> try Xml.attrib m "name" with _ -> "") modules_list) in check_dependencies modules_list modules_name; diff --git a/sw/tools/gen_settings.ml b/sw/tools/gen_settings.ml index e663f06f8e..7bc25f6424 100644 --- a/sw/tools/gen_settings.ml +++ b/sw/tools/gen_settings.ml @@ -2,7 +2,7 @@ * $Id$ * * XML preprocessing for dynamic tuning - * + * * Copyright (C) 2006 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. * *) @@ -44,50 +44,50 @@ let rec flatten = fun xml r -> match Xml.children xml with [] -> r | x::xs -> - List.iter (fun y -> assert(ExtXml.tag_is y (Xml.tag x))) xs; - List.fold_right flatten (x::xs) r + List.iter (fun y -> assert(ExtXml.tag_is y (Xml.tag x))) xs; + List.fold_right flatten (x::xs) r module StringSet = Set.Make(struct type t = string let compare = compare end) - + let print_dl_settings = fun settings -> let settings = flatten settings [] in (** include headers **) let modules = ref StringSet.empty in - List.iter + List.iter (fun s -> try - modules := StringSet.add (ExtXml.attrib s "module") !modules + modules := StringSet.add (ExtXml.attrib s "module") !modules with ExtXml.Error e -> () - ) + ) settings; lprintf "\n"; StringSet.iter (fun m -> lprintf "#include \"%s.h\"\n" m) !modules; - lprintf "#include \"modules.h\"\n"; + lprintf "#include \"generated/modules.h\"\n"; lprintf "\n"; - + (** Macro to call to set one variable *) lprintf "#define DlSetting(_idx, _value) { \\\n"; right (); lprintf "switch (_idx) { \\\n"; right (); let idx = ref 0 in - List.iter + List.iter (fun s -> let v = ExtXml.attrib s "var" in - begin - try - let h = ExtXml.attrib s "handler" and - m = ExtXml.attrib s "module" in - lprintf "case %d: %s_%s( _value ); _value = %s; break;\\\n" !idx (Filename.basename m) h v - with - ExtXml.Error e -> lprintf "case %d: %s = _value; break;\\\n" !idx v - end; - incr idx - ) + begin + try + let h = ExtXml.attrib s "handler" and + m = ExtXml.attrib s "module" in + lprintf "case %d: %s_%s( _value ); _value = %s; break;\\\n" !idx (Filename.basename m) h v + with + ExtXml.Error e -> lprintf "case %d: %s = _value; break;\\\n" !idx v + end; + incr idx + ) settings; lprintf "default: break;\\\n"; left (); @@ -106,10 +106,10 @@ let print_dl_settings = fun settings -> let idx = ref 0 in lprintf "switch (i) { \\\n"; right (); - List.iter + List.iter (fun s -> - let v = ExtXml.attrib s "var" in - lprintf "case %d: var = %s; break;\\\n" !idx v; incr idx) + let v = ExtXml.attrib s "var" in + lprintf "case %d: var = %s; break;\\\n" !idx v; incr idx) settings; lprintf "default: var = 0.; break;\\\n"; left (); @@ -126,16 +126,16 @@ let print_dl_settings = fun settings -> let idx = ref 0 in lprintf "switch (i) { \\\n"; right (); - List.iter + List.iter (fun s -> let v = ExtXml.attrib s "var" in - lprintf "case %d: return %s;\n" !idx v; incr idx) + lprintf "case %d: return %s;\n" !idx v; incr idx) settings; lprintf "default: return 0.;\n"; lprintf "}\n"; left (); lprintf "}\n" - + @@ -190,12 +190,12 @@ let join_xml_files = fun xml_files -> and rc_settings = ref [] in List.iter (fun xml_file -> let xml = Xml.parse_file xml_file in - let these_rc_settings = + let these_rc_settings = try Xml.children (ExtXml.child xml "rc_settings") with - Not_found -> [] in - let these_dl_settings = - try Xml.children (ExtXml.child xml "dl_settings") with - Not_found -> [] in + Not_found -> [] in + let these_dl_settings = + try Xml.children (ExtXml.child xml "dl_settings") with + Not_found -> [] in rc_settings := these_rc_settings @ !rc_settings; dl_settings := these_dl_settings @ !dl_settings) xml_files; @@ -211,11 +211,11 @@ let _ = for i = 2 to Array.length Sys.argv - 1 do xml_files := Sys.argv.(i) :: !xml_files; done; - + try printf "/* This file has been generated from %s */\n" (String.concat " " !xml_files); printf "/* Please DO NOT EDIT */\n\n"; - + printf "#ifndef %s\n" h_name; define h_name ""; nl ();