diff --git a/conf/airframes/mm/extra/press_t.xml b/conf/airframes/mm/extra/press_t.xml
old mode 100755
new mode 100644
diff --git a/conf/airframes/mm/extra/probe_t.xml b/conf/airframes/mm/extra/probe_t.xml
old mode 100755
new mode 100644
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi8.xml b/conf/airframes/mm/fixed-wing/funjetgfi8.xml
index cb284e816e..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 @@
-
-
-
-
-
-
-
-
+
-
-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 += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c
-
-ap.srcs += subsystems/navigation/nav_line.c
-ap.srcs += subsystems/navigation/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 += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c
-
-sim.srcs += joystick.c
-sim.CFLAGS += -DUSE_JOYSTICK
-
-
-
diff --git a/conf/airframes/mm/fixed-wing/funjetlisa.xml b/conf/airframes/mm/fixed-wing/funjetlisa.xml
new file mode 100644
index 0000000000..d6e6556d1c
--- /dev/null
+++ b/conf/airframes/mm/fixed-wing/funjetlisa.xml
@@ -0,0 +1,173 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/conf/airframes/mm/fixed-wing/funjetmm.xml b/conf/airframes/mm/fixed-wing/funjetmm.xml
old mode 100755
new mode 100644
diff --git a/conf/airframes/mm/rotor/qmk1.xml b/conf/airframes/mm/rotor/qmk1.xml
old mode 100755
new mode 100644
index 2c010bd134..8935328ed0
--- a/conf/airframes/mm/rotor/qmk1.xml
+++ b/conf/airframes/mm/rotor/qmk1.xml
@@ -189,8 +189,9 @@
+
-
+
diff --git a/conf/autopilot/csc_baro.makefile b/conf/autopilot/csc_baro.makefile
index cb2444b04d..c233cdc6f0 100644
--- a/conf/autopilot/csc_baro.makefile
+++ b/conf/autopilot/csc_baro.makefile
@@ -1,4 +1,4 @@
# baro scp bits
ap.CFLAGS += -DUSE_BARO_SCP -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0
-ap.srcs += $(SRC_CSC)/csc_baro.c spi.c $(SRC_ARCH)/spi_hw.c
+ap.srcs += $(SRC_CSC)/csc_baro.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c
diff --git a/conf/autopilot/lisa_l_test_progs.makefile b/conf/autopilot/lisa_l_test_progs.makefile
index d7e3afa0b7..ab9527b999 100644
--- a/conf/autopilot/lisa_l_test_progs.makefile
+++ b/conf/autopilot/lisa_l_test_progs.makefile
@@ -280,7 +280,7 @@ test_adc.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=$(MODEM_PORT)
test_adc.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT)
test_adc.srcs += downlink.c pprz_transport.c
-test_adc.srcs += $(SRC_ARCH)/adc_hw.c
+test_adc.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c
test_adc.CFLAGS += -DUSE_AD1 -DUSE_AD1_1
# -DUSE_AD1_2 -DUSE_AD1_3 -DUSE_AD1_4
test_adc.CFLAGS += -DUSE_ADC1_2_IRQ_HANDLER
@@ -681,4 +681,4 @@ tunnel.CFLAGS += -DUSE_LED
tunnel.srcs += $(SRC_ARCH)/led_hw.c
tunnel.CFLAGS += -DUSE_SYS_TIME -DSYS_TIME_LED=$(SYS_TIME_LED)
tunnel.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)'
-tunnel.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
\ No newline at end of file
+tunnel.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
diff --git a/conf/autopilot/lisa_passthrough.makefile b/conf/autopilot/lisa_passthrough.makefile
index 5798922428..2241a70455 100644
--- a/conf/autopilot/lisa_passthrough.makefile
+++ b/conf/autopilot/lisa_passthrough.makefile
@@ -103,12 +103,12 @@ stm_passthrough.CFLAGS += -DUSE_CAN1 \
-DCAN_BS1_TQ=CAN_BS1_3tq \
-DCAN_BS2_TQ=CAN_BS2_4tq \
-DCAN_ERR_RESUME=DISABLE
-stm_passthrough.srcs += can.c $(SRC_ARCH)/can_hw.c
+stm_passthrough.srcs += mcu_periph/can.c $(SRC_ARCH)/mcu_periph/can_arch.c
stm_passthrough.srcs += $(SRC_CSC)/csc_protocol.c
# ADC
-stm_passthrough.srcs += $(SRC_ARCH)/adc_hw.c
+stm_passthrough.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c
stm_passthrough.CFLAGS += -DUSE_AD1 \
-DUSE_AD1_1 \
-DUSE_AD1_2 \
diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile
index d29a13b1fc..07274c0b94 100644
--- a/conf/autopilot/rotorcraft.makefile
+++ b/conf/autopilot/rotorcraft.makefile
@@ -55,6 +55,8 @@ ap.ARCHDIR = $(ARCH)
ap.CFLAGS += $(ROTORCRAFT_INC)
ap.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) -DPERIPHERALS_AUTO_INIT
ap.srcs = $(SRC_FIRMWARE)/main.c
+ap.srcs += mcu.c
+ap.srcs += $(SRC_ARCH)/mcu_arch.c
ifeq ($(ARCH), stm32)
ap.srcs += lisa/plug_sys.c
@@ -90,7 +92,7 @@ endif
#
# Telemetry/Datalink
#
-ap.srcs += $(SRC_ARCH)/uart_hw.c
+ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
ap.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport
ap.CFLAGS += -DDOWNLINK_DEVICE=$(MODEM_PORT)
ap.srcs += $(SRC_FIRMWARE)/telemetry.c \
diff --git a/conf/autopilot/sitl.makefile b/conf/autopilot/sitl.makefile
index d0d1f39582..f3971eb938 100644
--- a/conf/autopilot/sitl.makefile
+++ b/conf/autopilot/sitl.makefile
@@ -6,7 +6,7 @@ sim.srcs += latlong.c\
commands.c\
gps.c\
inter_mcu.c\
- infrared.c\
+ subsystems/sensors/infrared.c\
$(SRC_FIRMWARE)/stabilization/stabilization_attitude.c\
$(SRC_FIRMWARE)/guidance/guidance_v.c \
subsystems/nav.c\
diff --git a/conf/autopilot/sitl_jsbsim.makefile b/conf/autopilot/sitl_jsbsim.makefile
index ea7153f87b..06f62f724e 100644
--- a/conf/autopilot/sitl_jsbsim.makefile
+++ b/conf/autopilot/sitl_jsbsim.makefile
@@ -26,7 +26,7 @@ endif
jsbsim.CFLAGS += -DSITL -DAP -DFBW -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport -DUSE_INFRARED -DNAV -DLED -DWIND_INFO -Ifirmwares/fixedwing
jsbsim.srcs = $(SRC_ARCH)/jsbsim_hw.c $(SRC_ARCH)/jsbsim_gps.c $(SRC_ARCH)/jsbsim_ir.c $(SRC_ARCH)/jsbsim_transport.c $(SRC_ARCH)/ivy_transport.c
-jsbsim.srcs += latlong.c downlink.c commands.c gps.c inter_mcu.c infrared.c \
+jsbsim.srcs += latlong.c downlink.c commands.c gps.c inter_mcu.c subsystems/sensors/infrared.c \
$(SRC_FIXEDWING)/stabilization/stabilization_attitude.c \
$(SRC_FIXEDWING)/guidance/guidance_v.c\
subsystems/nav.c estimator.c sys_time.c $(SRC_FIRMWARE)/main_fbw.c $(SRC_FIRMWARE)/main_ap.c datalink.c
diff --git a/conf/autopilot/sitl_link_pprz.makefile b/conf/autopilot/sitl_link_pprz.makefile
index 41ba561388..2fcd2b8d91 100644
--- a/conf/autopilot/sitl_link_pprz.makefile
+++ b/conf/autopilot/sitl_link_pprz.makefile
@@ -1,3 +1,3 @@
sim.ARCHDIR = $(ARCH)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DUSE_INFRARED -DRADIO_CONTROL_SETTINGS -DSIM_UART -DDOWNLINK_AP_DEVICE=SimUart -DDOWNLINK_FBW_DEVICE=SimUart -DDATALINK=PPRZ
-sim.srcs = radio_control.c downlink.c pprz_transport.c commands.c gps.c inter_mcu.c infrared.c $(SRC_FIRMWARE)/stabilization/stabilization_attitude.c $(SRC_FIRMWARE)/guidance/guidance_v.c subsystems/nav.c estimator.c cam.c sys_time.c $(SRC_FIRMWARE)/main_fbw.c $(SRC_FIRMWARE)/main_ap.c rc_settings.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/sim_uart.c datalink.c
+sim.srcs = radio_control.c downlink.c pprz_transport.c commands.c gps.c inter_mcu.c subsystems/sensors/infrared.c $(SRC_FIRMWARE)/stabilization/stabilization_attitude.c $(SRC_FIRMWARE)/guidance/guidance_v.c nav.c estimator.c cam.c sys_time.c $(SRC_FIRMWARE)/main_fbw.c $(SRC_FIRMWARE)/main_ap.c rc_settings.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/sim_uart.c datalink.c
diff --git a/conf/autopilot/sitl_link_xbee.makefile b/conf/autopilot/sitl_link_xbee.makefile
index ee5d37a179..6928643999 100644
--- a/conf/autopilot/sitl_link_xbee.makefile
+++ b/conf/autopilot/sitl_link_xbee.makefile
@@ -1,3 +1,3 @@
sim.ARCHDIR = $(ARCH)
sim.CFLAGS += -DSITL -DAP -DFBW -DRADIO_CONTROL -DINTER_MCU -DDOWNLINK -DDOWNLINK_TRANSPORT=XBeeTransport -DUSE_INFRARED -DRADIO_CONTROL_SETTINGS -DSIM_UART -DSIM_XBEE -DXBEE_UART=SimUart
-sim.srcs = radio_control.c downlink.c xbee.c commands.c gps.c inter_mcu.c infrared.c $(SRC_FIXEDWING)/stabilization/stabilization_attitude.c $(SRC_FIXEDWING)/guidance/guidance_v.c subsystems/nav.c estimator.c cam.c sys_time.c $(SRC_FIRMWARE)/main_fbw.c $(SRC_FIRMWARE)/main_ap.c rc_settings.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/sim_uart.c
+sim.srcs = radio_control.c downlink.c xbee.c commands.c gps.c inter_mcu.c subsystems/sensors/infrared.c $(SRC_FIXEDWING)/stabilization/stabilization_attitude.c $(SRC_FIXEDWING)/guidance/guidance_v.c nav.c estimator.c cam.c sys_time.c $(SRC_FIRMWARE)/main_fbw.c $(SRC_FIRMWARE)/main_ap.c rc_settings.c $(SRC_ARCH)/ppm_hw.c $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_ir.c $(SRC_ARCH)/sim_ap.c $(SRC_ARCH)/sim_uart.c
diff --git a/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile b/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile
index cf762bf1ff..aa4509a479 100644
--- a/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile
+++ b/conf/autopilot/subsystems/fixedwing/attitude_infrared.makefile
@@ -32,7 +32,7 @@ endif
ap.CFLAGS += -DADC_CHANNEL_IR_NB_SAMPLES=$(ADC_IR_NB_SAMPLES)
$(TARGET).CFLAGS += -DUSE_INFRARED
-$(TARGET).srcs += $(SRC_FIXEDWING)/infrared.c
+$(TARGET).srcs += subsystems/sensors/infrared.c
sim.srcs += $(SRC_ARCH)/sim_ir.c
jsbsim.srcs += $(SRC_ARCH)/jsbsim_ir.c
diff --git a/conf/autopilot/subsystems/fixedwing/autopilot.makefile b/conf/autopilot/subsystems/fixedwing/autopilot.makefile
index 7a334a7338..075eae6ae9 100644
--- a/conf/autopilot/subsystems/fixedwing/autopilot.makefile
+++ b/conf/autopilot/subsystems/fixedwing/autopilot.makefile
@@ -29,7 +29,7 @@
# temporary hack for ADCs
ifeq ($(ARCH), stm32)
-$(TARGET).CFLAGS += -DSTM32
+# FIXME : this is for the battery
$(TARGET).CFLAGS += -DUSE_AD1_3
endif
#
@@ -37,8 +37,12 @@ endif
#
$(TARGET).CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG)
+$(TARGET).CFLAGS += -DPERIPHERALS_AUTO_INIT
$(TARGET).CFLAGS += $(FIXEDWING_INC)
+$(TARGET).srcs += mcu.c
+$(TARGET).srcs += $(SRC_ARCH)/mcu_arch.c
+
#
# Common Options
#
@@ -54,7 +58,7 @@ $(TARGET).CFLAGS += -DTRAFFIC_INFO
# LEDs
#
-$(TARGET).CFLAGS += -DLED
+$(TARGET).CFLAGS += -DUSE_LED
ifneq ($(ARCH), lpc21)
ifneq ($(ARCH), jsbsim)
$(TARGET).srcs += $(SRC_ARCH)/led_hw.c
@@ -126,7 +130,7 @@ ns_srcs += $(SRC_ARCH)/sys_time_hw.c
# UARTS
#
-ns_srcs += $(SRC_ARCH)/uart_hw.c
+ns_srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
#
# ANALOG
@@ -134,10 +138,7 @@ ns_srcs += $(SRC_ARCH)/uart_hw.c
ns_CFLAGS += -DADC
#ifeq ($(ARCH), lpc21)
- ns_srcs += $(SRC_ARCH)/adc_hw.c
-#else ifeq ($(ARCH), stm32)
-# ns_srcs += lisa/lisa_analog_plug.c
-#endif
+ ns_srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c
ifeq ($(ARCH), stm32)
ns_CFLAGS += -DUSE_ADC1_2_IRQ_HANDLER
endif
@@ -207,9 +208,9 @@ jsbsim.srcs += downlink.c datalink.c $(SRC_ARCH)/jsbsim_hw.c $(SRC_ARCH)/jsbsi
ifeq ($(BOARD),classix)
fbw.CFLAGS += -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE
- fbw.srcs += $(SRC_FIXEDWING)/link_mcu.c $(SRC_FIXEDWING)/spi.c $(SRC_ARCH)/spi_hw.c
+ fbw.srcs += $(SRC_FIXEDWING)/link_mcu.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c
ap.CFLAGS += -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0
- ap.srcs += $(SRC_FIXEDWING)/link_mcu.c $(SRC_FIXEDWING)/spi.c $(SRC_ARCH)/spi_hw.c
+ ap.srcs += $(SRC_FIXEDWING)/link_mcu.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c
else
# Single MCU's run both
ap.CFLAGS += $(fbw_CFLAGS)
diff --git a/conf/autopilot/subsystems/fixedwing/i2c.makefile b/conf/autopilot/subsystems/fixedwing/i2c.makefile
index 7a16bd4ebe..0f8769cf04 100644
--- a/conf/autopilot/subsystems/fixedwing/i2c.makefile
+++ b/conf/autopilot/subsystems/fixedwing/i2c.makefile
@@ -1,3 +1,5 @@
#generic i2c driver
-ap.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
-sim.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+ap.srcs += mcu_periph/i2c.c
+ap.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
+sim.srcs += mcu_periph/i2c.c
+sim.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
diff --git a/conf/autopilot/subsystems/fixedwing/spi.makefile b/conf/autopilot/subsystems/fixedwing/spi.makefile
index 42106f69f5..d6ff15a24a 100644
--- a/conf/autopilot/subsystems/fixedwing/spi.makefile
+++ b/conf/autopilot/subsystems/fixedwing/spi.makefile
@@ -1,5 +1,5 @@
#generic spi driver
$(TARGET).CFLAGS += -DUSE_SPI
-ap.srcs += spi.c $(SRC_ARCH)/spi_hw.c
-sim.srcs += spi.c $(SRC_ARCH)/spi_hw.c
+ap.srcs += mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c
+sim.srcs += mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c
diff --git a/conf/autopilot/subsystems/fixedwing/testing.makefile b/conf/autopilot/subsystems/fixedwing/testing.makefile
index 909daa7715..527e9de60f 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/test_adcs.c
+test_adcs.srcs += sys_time.c $(SRC_ARCH)/mcu_periph/adc_arch.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/actuators_asctec.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile
index 9e092b0c83..cfc69bc2cb 100644
--- a/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile
+++ b/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile
@@ -1,6 +1,7 @@
# asctec controllers
ap.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
-ap.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+ap.srcs += mcu_periph/i2c.c
+ap.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
ifeq ($(ARCH), lpc21)
ap.CFLAGS += -DACTUATORS_ASCTEC_DEVICE=i2c0
@@ -16,5 +17,6 @@ endif
# Simulator
sim.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
sim.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 -DI2C0_VIC_SLOT=10
-sim.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+sim.srcs += mcu_periph/i2c.c
+sim.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_asctec_v2.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_asctec_v2.makefile
index e59570a96c..c1cfc48f37 100644
--- a/conf/autopilot/subsystems/rotorcraft/actuators_asctec_v2.makefile
+++ b/conf/autopilot/subsystems/rotorcraft/actuators_asctec_v2.makefile
@@ -19,7 +19,8 @@
ap.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
ap.CFLAGS += -DACTUATORS_ASCTEC_V2_PROTOCOL
ap.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
-ap.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+ap.srcs += mcu_periph/i2c.c
+ap.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
ifeq ($(ARCH), lpc21)
ap.CFLAGS += -DACTUATORS_ASCTEC_DEVICE=i2c0
diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_heli.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_heli.makefile
index c64e676752..95e3591951 100644
--- a/conf/autopilot/subsystems/rotorcraft/actuators_heli.makefile
+++ b/conf/autopilot/subsystems/rotorcraft/actuators_heli.makefile
@@ -7,4 +7,4 @@ ap.srcs += $(SRC_FIRMWARE)/actuators/actuators_heli.c
ap.srcs += $(SRC_FIRMWARE)/actuators/arch/$(ARCH)/actuators_pwm_arch.c
# fixme : this is needed by baro and usualy added by actuators_mkk or actuators_asctec
-ap.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+ap.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c
diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile
index 031567385e..f70c299815 100644
--- a/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile
+++ b/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile
@@ -28,7 +28,8 @@
#
ap.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
ap.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
-ap.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+ap.srcs += mcu_periph/i2c.c
+ap.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
ifeq ($(ARCH), lpc21)
ap.CFLAGS += -DACTUATORS_MKK_DEVICE=i2c0
@@ -42,4 +43,5 @@ endif
sim.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
sim.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
sim.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 -DI2C0_VIC_SLOT=10 -DACTUATORS_MKK_DEVICE=i2c1
-sim.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c
+sim.srcs += mcu_periph/i2c.c
+sim.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
diff --git a/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile b/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile
index 5f288cdc7f..ae53bd7a26 100644
--- a/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile
+++ b/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile
@@ -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/boards/lisa_l_1.0.makefile b/conf/boards/lisa_l_1.0.makefile
index d98f433b5e..24fc846132 100644
--- a/conf/boards/lisa_l_1.0.makefile
+++ b/conf/boards/lisa_l_1.0.makefile
@@ -78,8 +78,8 @@ ADC_IR2 = 2
ADC_IR2_CHAN = 1
endif
ifndef ADC_IR3
-ADC_IR_TOP = 3
-ADC_IR_TOP_CHAN = 2
+ADC_IR_TOP = 4
+ADC_IR_TOP_CHAN = 3
endif
ifndef ADC_IR_NB_SAMPLES
ADC_IR_NB_SAMPLES = 16
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/settings/basic.xml b/conf/settings/basic.xml
index a69afe1978..d982774302 100644
--- a/conf/settings/basic.xml
+++ b/conf/settings/basic.xml
@@ -29,8 +29,8 @@
-
-
+
+
diff --git a/conf/settings/tuning.xml b/conf/settings/tuning.xml
index 170cea7188..c7d1c10dd4 100644
--- a/conf/settings/tuning.xml
+++ b/conf/settings/tuning.xml
@@ -34,7 +34,7 @@
-
+
diff --git a/conf/settings/tuningJH.xml b/conf/settings/tuningJH.xml
index c70089189a..f981b3a7c3 100644
--- a/conf/settings/tuningJH.xml
+++ b/conf/settings/tuningJH.xml
@@ -26,7 +26,7 @@
-
+
diff --git a/conf/settings/tuning_ctl_new.xml b/conf/settings/tuning_ctl_new.xml
index 373fcf1c06..f61ce9a3c2 100644
--- a/conf/settings/tuning_ctl_new.xml
+++ b/conf/settings/tuning_ctl_new.xml
@@ -34,7 +34,7 @@
-
+
diff --git a/conf/settings/tuning_loiter.xml b/conf/settings/tuning_loiter.xml
index 87521b9950..61f378a4d2 100644
--- a/conf/settings/tuning_loiter.xml
+++ b/conf/settings/tuning_loiter.xml
@@ -34,7 +34,7 @@
-
+
diff --git a/sw/airborne/6dof.h b/sw/airborne/6dof.h
deleted file mode 100644
index 029585afc0..0000000000
--- a/sw/airborne/6dof.h
+++ /dev/null
@@ -1,31 +0,0 @@
-#ifndef _6DOF_H
-#define _6DOF_H
-
-#define AXIS_X 0
-#define AXIS_Y 1
-#define AXIS_Z 2
-#define AXIS_NB 3
-
-#define AXIS_P 0
-#define AXIS_Q 1
-#define AXIS_R 2
-
-#define AXIS_U 0
-#define AXIS_V 1
-#define AXIS_W 2
-
-#define EULER_PHI 0
-#define EULER_THETA 1
-#define EULER_PSI 2
-#define EULER_NB 3
-
-#define QUAT_QI 0
-#define QUAT_QX 1
-#define QUAT_QY 2
-#define QUAT_QZ 3
-#define QUAT_NB 4
-
-
-
-
-#endif /* _6DOF_H */
diff --git a/sw/airborne/agl_vfilter.h b/sw/airborne/agl_vfilter.h
index 91ce89532f..f7fd036e86 100644
--- a/sw/airborne/agl_vfilter.h
+++ b/sw/airborne/agl_vfilter.h
@@ -1,7 +1,7 @@
#ifndef AGL_VFILTER_H
#define AGL_VFILTER_H
-#include "adc.h"
+#include "mcu_periph/adc.h"
#define STATE_SIZE 3
diff --git a/sw/airborne/arch/avr/adc_hw.c b/sw/airborne/arch/avr/mcu_periph/adc_arch.c
similarity index 99%
rename from sw/airborne/arch/avr/adc_hw.c
rename to sw/airborne/arch/avr/mcu_periph/adc_arch.c
index ae37327e7f..6799d7317f 100644
--- a/sw/airborne/arch/avr/adc_hw.c
+++ b/sw/airborne/arch/avr/mcu_periph/adc_arch.c
@@ -31,7 +31,7 @@
#endif
#include
#include
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include "std.h"
diff --git a/sw/airborne/arch/avr/adc_hw.h b/sw/airborne/arch/avr/mcu_periph/adc_arch.h
similarity index 100%
rename from sw/airborne/arch/avr/adc_hw.h
rename to sw/airborne/arch/avr/mcu_periph/adc_arch.h
diff --git a/sw/airborne/arch/avr/i2c_ap.c b/sw/airborne/arch/avr/mcu_periph/i2c_arch.c
similarity index 100%
rename from sw/airborne/arch/avr/i2c_ap.c
rename to sw/airborne/arch/avr/mcu_periph/i2c_arch.c
diff --git a/sw/airborne/arch/avr/i2c_ap.h b/sw/airborne/arch/avr/mcu_periph/i2c_arch.h
similarity index 100%
rename from sw/airborne/arch/avr/i2c_ap.h
rename to sw/airborne/arch/avr/mcu_periph/i2c_arch.h
diff --git a/sw/airborne/arch/avr/spi_hw.c b/sw/airborne/arch/avr/mcu_periph/spi_arch.c
similarity index 99%
rename from sw/airborne/arch/avr/spi_hw.c
rename to sw/airborne/arch/avr/mcu_periph/spi_arch.c
index eb30bcc7af..558b06a7e2 100644
--- a/sw/airborne/arch/avr/spi_hw.c
+++ b/sw/airborne/arch/avr/mcu_periph/spi_arch.c
@@ -27,7 +27,7 @@
*/
#include CONFIG
-#include "spi.h"
+#include "mcu_periph/spi.h"
#include
#include
diff --git a/sw/airborne/arch/avr/spi_hw.h b/sw/airborne/arch/avr/mcu_periph/spi_arch.h
similarity index 100%
rename from sw/airborne/arch/avr/spi_hw.h
rename to sw/airborne/arch/avr/mcu_periph/spi_arch.h
diff --git a/sw/airborne/arch/avr/uart_hw.c b/sw/airborne/arch/avr/mcu_periph/uart_arch.c
similarity index 99%
rename from sw/airborne/arch/avr/uart_hw.c
rename to sw/airborne/arch/avr/mcu_periph/uart_arch.c
index b1c8aac337..29ec68e656 100644
--- a/sw/airborne/arch/avr/uart_hw.c
+++ b/sw/airborne/arch/avr/mcu_periph/uart_arch.c
@@ -26,7 +26,7 @@
* \brief avr uart low level functions
*
*/
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "sys_time.h"
#define B2400 2400UL
diff --git a/sw/airborne/arch/avr/uart_hw.h b/sw/airborne/arch/avr/mcu_periph/uart_arch.h
similarity index 100%
rename from sw/airborne/arch/avr/uart_hw.h
rename to sw/airborne/arch/avr/mcu_periph/uart_arch.h
diff --git a/sw/airborne/arch/lpc21/ADS8344.c b/sw/airborne/arch/lpc21/ADS8344.c
index dd72abcac8..49ce4dd027 100644
--- a/sw/airborne/arch/lpc21/ADS8344.c
+++ b/sw/airborne/arch/lpc21/ADS8344.c
@@ -27,7 +27,7 @@
#include "armVIC.h"
#include BOARD_CONFIG
#include "led.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi.h"
#define ADS8344_SS_IODIR IO0DIR
#define ADS8344_SS_IOSET IO0SET
diff --git a/sw/airborne/arch/lpc21/init_hw.h b/sw/airborne/arch/lpc21/mcu_arch.c
similarity index 51%
rename from sw/airborne/arch/lpc21/init_hw.h
rename to sw/airborne/arch/lpc21/mcu_arch.c
index 470f38e6e5..a99d484ba4 100644
--- a/sw/airborne/arch/lpc21/init_hw.h
+++ b/sw/airborne/arch/lpc21/mcu_arch.c
@@ -1,64 +1,40 @@
/*
- * Paparazzi $Id$
+ * Paparazzi lpc21 arch dependant microcontroller initialisation function
*
- * Copyright (C) 2005 Pascal Brisset, Antoine Drouin
+ * Copyright (C) 2010 The Paparazzi team
*
- * This file is part of paparazzi.
+ * This file is part of Paparazzi.
*
- * paparazzi is free software; you can redistribute it and/or modify
+ * 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,
+ * 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
+ * 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.
*
*/
-/*
- *\brief ARM7 low level hardware initialisation
- * PLL, MAM, VIC
- *
- */
+#include "mcu.h"
-#ifndef INIT_HW_H
-#define INIT_HW_H
#include
#include BOARD_CONFIG
#include "LPC21xx.h"
-#ifdef PERIPHERALS_AUTO_INIT
-#if defined LED || defined USE_LED
-#include "led.h"
-#endif
-#if defined USE_UART0 || defined USE_UART1
-#include "uart.h"
-#endif
-#ifdef USE_USB_SERIAL
-#include "usb_serial.h"
-#endif
-#if defined USE_I2C0 || defined USE_I2C1
-#include "i2c.h"
-#endif
-#endif /* PERIPHERALS_AUTO_INIT */
-
-
/* declare functions and values from crt0.S & the linker control file */
extern void reset(void);
-/* extern void exit(void); */
-extern void abort(void);
+void mcu_arch_init(void) {
-static inline void hw_init(void) {
/* set PLL multiplier & divisor. */
/* values computed from config.h */
PLLCFG = PLLCFG_MSEL | PLLCFG_PSEL;
@@ -82,25 +58,13 @@ static inline void hw_init(void) {
MAMTIM = MAMTIM_CYCLES;
MAMCR = MAMCR_FULL;
- /* setup & enable the MAM */
- MAMTIM = MAMTIM_CYCLES;
- MAMCR = MAMCR_FULL;
-
/* set the peripheral bus speed */
/* value computed from config.h */
VPBDIV = VPBDIV_VALUE;
- /* set the interrupt controller defaults */
- //#if defined(RAM_RUN)
- /* map interrupt vectors space into SRAM */
- // MEMMAP = MEMMAP_SRAM;
- //#elif defined(ROM_RUN)
- /* map interrupt vectors space into FLASH */
+ /* set the interrupt controller to flash */
MEMMAP = MEMMAP_FLASH;
- //#else
- //#error RUN_MODE not defined!
- //#endif
-
+
/* clear all interrupts */
VICIntEnClear = 0xFFFFFFFF;
/* clear all FIQ selections */
@@ -108,29 +72,4 @@ static inline void hw_init(void) {
/* point unvectored IRQs to reset() */
VICDefVectAddr = (uint32_t)reset;
-
-#ifdef PERIPHERALS_AUTO_INIT
-#if defined LED || defined USE_LED
- led_init();
-#endif
-#ifdef USE_UART0
- uart0_init();
-#endif
-#ifdef USE_UART1
- uart1_init();
-#endif
-#ifdef USE_USB_SERIAL
- VCOM_init();
-#endif
-#ifdef USE_I2C0
- i2c0_init();
-#endif
-#ifdef USE_I2C1
- i2c1_init();
-#endif
-#endif /* PERIPHERALS_AUTO_INIT */
-
-
}
-
-#endif /* INIT_HW_H */
diff --git a/sw/airborne/arch/lpc21/mcu_arch.h b/sw/airborne/arch/lpc21/mcu_arch.h
new file mode 100644
index 0000000000..a677d396c2
--- /dev/null
+++ b/sw/airborne/arch/lpc21/mcu_arch.h
@@ -0,0 +1,35 @@
+/*
+ * Paparazzi lpc21 arch dependant microcontroller initialisation functions
+ *
+ * Copyright (C) 2010 The Paparazzi team
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+#ifndef LPC21_MCU_ARCH_H
+#define LPC21_MCU_ARCH_H
+
+extern void mcu_arch_init(void);
+
+#include "armVIC.h"
+
+#define mcu_int_enable() enableIRQ()
+#define mcu_int_disable() disableIRQ()
+
+#endif /* LPC21_MCU_ARCH_H */
diff --git a/sw/airborne/arch/lpc21/adc_hw.c b/sw/airborne/arch/lpc21/mcu_periph/adc_arch.c
similarity index 99%
rename from sw/airborne/arch/lpc21/adc_hw.c
rename to sw/airborne/arch/lpc21/mcu_periph/adc_arch.c
index 6fe1f8654d..3c1c298373 100644
--- a/sw/airborne/arch/lpc21/adc_hw.c
+++ b/sw/airborne/arch/lpc21/mcu_periph/adc_arch.c
@@ -22,7 +22,7 @@
*
*/
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include "LPC21xx.h"
#include "armVIC.h"
diff --git a/sw/airborne/arch/lpc21/adc_hw.h b/sw/airborne/arch/lpc21/mcu_periph/adc_arch.h
similarity index 100%
rename from sw/airborne/arch/lpc21/adc_hw.h
rename to sw/airborne/arch/lpc21/mcu_periph/adc_arch.h
diff --git a/sw/airborne/arch/lpc21/i2c_hw.c b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c
similarity index 99%
rename from sw/airborne/arch/lpc21/i2c_hw.c
rename to sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c
index d91352db4b..7d8541121d 100644
--- a/sw/airborne/arch/lpc21/i2c_hw.c
+++ b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c
@@ -22,7 +22,7 @@
*
*/
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "std.h"
#include "interrupt_hw.h"
diff --git a/sw/airborne/arch/lpc21/i2c_hw.h b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.h
similarity index 100%
rename from sw/airborne/arch/lpc21/i2c_hw.h
rename to sw/airborne/arch/lpc21/mcu_periph/i2c_arch.h
diff --git a/sw/airborne/arch/lpc21/spi_hw.c b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c
similarity index 99%
rename from sw/airborne/arch/lpc21/spi_hw.c
rename to sw/airborne/arch/lpc21/mcu_periph/spi_arch.c
index 5c29360fe6..614704b944 100644
--- a/sw/airborne/arch/lpc21/spi_hw.c
+++ b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c
@@ -25,7 +25,7 @@
* for now only SPI1 ( aka SSP )
*/
-#include "spi.h"
+#include "mcu_periph/spi.h"
#include "std.h"
#include "LPC21xx.h"
diff --git a/sw/airborne/arch/lpc21/spi_hw.h b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.h
similarity index 100%
rename from sw/airborne/arch/lpc21/spi_hw.h
rename to sw/airborne/arch/lpc21/mcu_periph/spi_arch.h
diff --git a/sw/airborne/arch/lpc21/uart_hw.c b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c
similarity index 99%
rename from sw/airborne/arch/lpc21/uart_hw.c
rename to sw/airborne/arch/lpc21/mcu_periph/uart_arch.c
index 722dbf411e..55d8df8c52 100644
--- a/sw/airborne/arch/lpc21/uart_hw.c
+++ b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c
@@ -1,7 +1,7 @@
/*
* $Id$
*
- * Copyright (C) 2008 Pascal Brisset, Antoine Drouin
+ * Copyright (C) 2008-2010 The Paparazzi Team
*
* This file is part of paparazzi.
*
@@ -26,7 +26,7 @@
* Brief LPC21 uart code
*/
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "armVIC.h"
#ifdef USE_UART0
diff --git a/sw/airborne/arch/lpc21/uart_hw.h b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h
similarity index 97%
rename from sw/airborne/arch/lpc21/uart_hw.h
rename to sw/airborne/arch/lpc21/mcu_periph/uart_arch.h
index 06ac5ff7f0..fbc1c6c991 100644
--- a/sw/airborne/arch/lpc21/uart_hw.h
+++ b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h
@@ -22,8 +22,8 @@
*
*/
-#ifndef UART_HW_H
-#define UART_HW_H
+#ifndef LPC21_UART_ARCH_H
+#define LPC21_UART_ARCH_H
#include "types.h"
#include "LPC21xx.h"
@@ -93,4 +93,4 @@ extern void uart0_init_param( uint16_t baud, uint8_t mode, uint8_t fmode);
extern uint8_t uart0_tx_running;
extern uint8_t uart1_tx_running;
-#endif /* UART_HW_H */
+#endif /* LPC21_UART_ARCH_H */
diff --git a/sw/airborne/arch/lpc21/modules/display/lcd_dogm_hw.h b/sw/airborne/arch/lpc21/modules/display/lcd_dogm_hw.h
index 3897cf2a0d..14f6640e49 100644
--- a/sw/airborne/arch/lpc21/modules/display/lcd_dogm_hw.h
+++ b/sw/airborne/arch/lpc21/modules/display/lcd_dogm_hw.h
@@ -3,7 +3,7 @@
#include
#include "std.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi.h"
#include "led.h"
diff --git a/sw/airborne/arch/lpc21/modules/sensors/mag_micromag_fw_hw.h b/sw/airborne/arch/lpc21/modules/sensors/mag_micromag_fw_hw.h
index 9f9b38e6ae..2ea2218424 100644
--- a/sw/airborne/arch/lpc21/modules/sensors/mag_micromag_fw_hw.h
+++ b/sw/airborne/arch/lpc21/modules/sensors/mag_micromag_fw_hw.h
@@ -5,9 +5,9 @@
#include "std.h"
#include "LPC21xx.h"
-#include "interrupt_hw.h"
+#include "mcu.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi.h"
#include BOARD_CONFIG
#include "generated/airframe.h"
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..616354e976 100644
--- a/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h
+++ b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h
@@ -26,7 +26,7 @@
#define RADIO_CONTROL_SPEKTRUM_ARCH_H
#include "std.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include RADIO_CONTROL_SPEKTRUM_MODEL_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/arch/lpc21/usb_tunnel.c b/sw/airborne/arch/lpc21/usb_tunnel.c
index 869caeabd3..d5140ddc0f 100644
--- a/sw/airborne/arch/lpc21/usb_tunnel.c
+++ b/sw/airborne/arch/lpc21/usb_tunnel.c
@@ -31,12 +31,10 @@
*/
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "usb_serial.h"
/* minimum LED blink on time 10Hz = 100ms */
@@ -46,21 +44,11 @@ int main( void ) {
unsigned char inc;
unsigned int rx_time=0, tx_time=0;
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
VCOM_allow_linecoding(1);
-#ifdef USE_UART0
- Uart0Init();
-#else
-#ifdef USE_UART1
- Uart1Init();
-#else
-#error no serial port defined
-#endif
-#endif
-
#ifdef USE_USB_SERIAL
VCOM_init();
#endif
diff --git a/sw/airborne/arch/sim/gps_hw.c b/sw/airborne/arch/sim/gps_hw.c
index 75dfc0ac47..4511247803 100644
--- a/sw/airborne/arch/sim/gps_hw.c
+++ b/sw/airborne/arch/sim/gps_hw.c
@@ -1,7 +1,5 @@
#include "gps.h"
-#include "6dof.h"
-
/* in gps_ubx.c */
volatile uint8_t gps_msg_received;
bool_t gps_pos_available;
diff --git a/sw/airborne/arch/sim/init_hw.h b/sw/airborne/arch/sim/init_hw.h
deleted file mode 100644
index 32a393b484..0000000000
--- a/sw/airborne/arch/sim/init_hw.h
+++ /dev/null
@@ -1,6 +0,0 @@
-#ifndef INIT_HW_H
-#define INIT_HW_H
-
-static inline void hw_init(void) {}
-
-#endif /* INIT_HW_H */
diff --git a/sw/airborne/arch/sim/interrupt_hw.h b/sw/airborne/arch/sim/interrupt_hw.h
deleted file mode 100644
index 12561a990c..0000000000
--- a/sw/airborne/arch/sim/interrupt_hw.h
+++ /dev/null
@@ -1,6 +0,0 @@
-#ifndef INTERRUPT_HW_H
-#define INTERRUPT_HW_H
-
-#define int_enable() {}
-
-#endif /* INTERRUPT_HW_H */
diff --git a/sw/airborne/arch/sim/jsbsim_hw.h b/sw/airborne/arch/sim/jsbsim_hw.h
index 96cd553b47..88ed9404a7 100644
--- a/sw/airborne/arch/sim/jsbsim_hw.h
+++ b/sw/airborne/arch/sim/jsbsim_hw.h
@@ -40,7 +40,7 @@
#include "subsystems/nav.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
#include "firmwares/fixedwing/guidance/guidance_v.h"
-#include "infrared.h"
+#include "subsystems/sensors/infrared.h"
#include "commands.h"
#include "firmwares/fixedwing/main_ap.h"
#include "ap_downlink.h"
diff --git a/sw/airborne/arch/sim/mcu_arch.c b/sw/airborne/arch/sim/mcu_arch.c
new file mode 100644
index 0000000000..1820c41208
--- /dev/null
+++ b/sw/airborne/arch/sim/mcu_arch.c
@@ -0,0 +1,3 @@
+
+
+void mcu_arch_init(void) {}
diff --git a/sw/airborne/arch/avr/init_hw.h b/sw/airborne/arch/sim/mcu_arch.h
similarity index 68%
rename from sw/airborne/arch/avr/init_hw.h
rename to sw/airborne/arch/sim/mcu_arch.h
index f517fdbc7d..9500d80520 100644
--- a/sw/airborne/arch/avr/init_hw.h
+++ b/sw/airborne/arch/sim/mcu_arch.h
@@ -1,7 +1,7 @@
/*
- * Paparazzi $Id$
+ * $Id$
*
- * Copyright (C) 2005 Pascal Brisset, Antoine Drouin
+ * Copyright (C) 2010 The Paparazzi Team
*
* This file is part of paparazzi.
*
@@ -22,23 +22,12 @@
*
*/
-/*
- *\brief AVR low level hardware initialisation
- *
- */
+#ifndef SIM_MCU_ARCH_H
+#define SIM_MCU_ARCH_H
-#ifndef INIT_HW_H
-#define INIT_HW_H
+extern void mcu_arch_init(void);
-#include
+#define mcu_int_enable() {}
-static inline void hw_init(void) {
- /** Pause */
- uint8_t foo1 = 25;
- while (foo1--) {
- uint16_t foo2 = 1;
- while (foo2++);
- }
-}
+#endif /* SIM_MCU_ARCH_H */
-#endif /* INIT_HW_H */
diff --git a/sw/airborne/arch/sim/adc_hw.c b/sw/airborne/arch/sim/mcu_periph/adc_arch.c
similarity index 88%
rename from sw/airborne/arch/sim/adc_hw.c
rename to sw/airborne/arch/sim/mcu_periph/adc_arch.c
index 05d7287f27..0a21926066 100644
--- a/sw/airborne/arch/sim/adc_hw.c
+++ b/sw/airborne/arch/sim/mcu_periph/adc_arch.c
@@ -1,4 +1,4 @@
-#include "adc.h"
+#include "mcu_periph/adc.h"
void adc_buf_channel(uint8_t adc_channel __attribute__ ((unused)),
struct adc_buf* s __attribute__ ((unused)),
diff --git a/sw/airborne/arch/sim/adc_hw.h b/sw/airborne/arch/sim/mcu_periph/adc_arch.h
similarity index 100%
rename from sw/airborne/arch/sim/adc_hw.h
rename to sw/airborne/arch/sim/mcu_periph/adc_arch.h
diff --git a/sw/airborne/arch/sim/i2c_hw.c b/sw/airborne/arch/sim/mcu_periph/i2c_arch.c
similarity index 85%
rename from sw/airborne/arch/sim/i2c_hw.c
rename to sw/airborne/arch/sim/mcu_periph/i2c_arch.c
index 37d9c6df38..cd16065446 100644
--- a/sw/airborne/arch/sim/i2c_hw.c
+++ b/sw/airborne/arch/sim/mcu_periph/i2c_arch.c
@@ -1,4 +1,4 @@
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
void i2c_hw_init ( void ) {}
diff --git a/sw/airborne/arch/sim/i2c_hw.h b/sw/airborne/arch/sim/mcu_periph/i2c_arch.h
similarity index 61%
rename from sw/airborne/arch/sim/i2c_hw.h
rename to sw/airborne/arch/sim/mcu_periph/i2c_arch.h
index 24b31c0b8f..3f5e6921c1 100644
--- a/sw/airborne/arch/sim/i2c_hw.h
+++ b/sw/airborne/arch/sim/mcu_periph/i2c_arch.h
@@ -1,5 +1,5 @@
-#ifndef I2C_HW_H
-#define I2C_HW_H
+#ifndef SIM_MCU_PERIPH_I2C_ARCH_H
+#define SIM_MCU_PERIPH_I2C_ARCH_H
#define I2cSendStart() {}
@@ -10,4 +10,4 @@
#define I2c0SendStart() {}
#define I2c1SendStart() {}
-#endif /* I2C_HW_H */
+#endif /* SIM_MCU_PERIPH_I2C_ARCH_H */
diff --git a/sw/airborne/arch/sim/mcu_periph/spi_arch.c b/sw/airborne/arch/sim/mcu_periph/spi_arch.c
new file mode 100644
index 0000000000..43ec2e48d4
--- /dev/null
+++ b/sw/airborne/arch/sim/mcu_periph/spi_arch.c
@@ -0,0 +1,3 @@
+#include "mcu_periph/spi.h"
+
+void spi_init( void ) {}
diff --git a/sw/airborne/arch/sim/spi_hw.h b/sw/airborne/arch/sim/mcu_periph/spi_arch.h
similarity index 100%
rename from sw/airborne/arch/sim/spi_hw.h
rename to sw/airborne/arch/sim/mcu_periph/spi_arch.h
diff --git a/sw/airborne/arch/sim/uart_hw.h b/sw/airborne/arch/sim/mcu_periph/uart_arch.h
similarity index 100%
rename from sw/airborne/arch/sim/uart_hw.h
rename to sw/airborne/arch/sim/mcu_periph/uart_arch.h
diff --git a/sw/airborne/arch/sim/micromag_hw.c b/sw/airborne/arch/sim/micromag_hw.c
index bb867b7156..3dd9c24c01 100644
--- a/sw/airborne/arch/sim/micromag_hw.c
+++ b/sw/airborne/arch/sim/micromag_hw.c
@@ -28,16 +28,15 @@
#include "micromag.h"
-#include "6dof.h"
void micromag_hw_init( void ) {}
void micromag_read( void ) {}
void micromag_hw_feed_value(VEC* mag) {
- micromag_values[0] = mag->ve[AXIS_X];
- micromag_values[1] = mag->ve[AXIS_Y];
- micromag_values[2] = mag->ve[AXIS_Z];
+ micromag_values[0] = mag->ve[0];
+ micromag_values[1] = mag->ve[1];
+ micromag_values[2] = mag->ve[2];
micromag_status = MM_DATA_AVAILABLE;
}
diff --git a/sw/airborne/arch/sim/sim_ap.c b/sw/airborne/arch/sim/sim_ap.c
index d1beea54bf..1990c33a84 100644
--- a/sw/airborne/arch/sim/sim_ap.c
+++ b/sw/airborne/arch/sim/sim_ap.c
@@ -18,7 +18,7 @@
#include "subsystems/nav.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
#include "firmwares/fixedwing/guidance/guidance_v.h"
-#include "infrared.h"
+#include "subsystems/sensors/infrared.h"
#include "commands.h"
#include "firmwares/fixedwing/main_ap.h"
#include "ap_downlink.h"
diff --git a/sw/airborne/arch/sim/sim_ir.c b/sw/airborne/arch/sim/sim_ir.c
index ffc1cac2e5..59dd9edb88 100644
--- a/sw/airborne/arch/sim/sim_ir.c
+++ b/sw/airborne/arch/sim/sim_ir.c
@@ -6,7 +6,7 @@
#include
-#include "infrared.h"
+#include "subsystems/sensors/infrared.h"
#include "generated/airframe.h"
#include
diff --git a/sw/airborne/arch/sim/sim_jsbsim.c b/sw/airborne/arch/sim/sim_jsbsim.c
index 963f750d0c..f81a5bcb41 100644
--- a/sw/airborne/arch/sim/sim_jsbsim.c
+++ b/sw/airborne/arch/sim/sim_jsbsim.c
@@ -18,7 +18,7 @@
#include "subsystems/nav.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
#include "ffirmwares/fixedwing/guidance/guidance_v.h"
-#include "infrared.h"
+#include "subsystems/sensors/infrared.h"
#include "commands.h"
#include "firmwares/fixedwing/main_ap.h"
#include "ap_downlink.h"
diff --git a/sw/airborne/arch/sim/spi_hw.c b/sw/airborne/arch/sim/spi_hw.c
deleted file mode 100644
index cd0b3ece6e..0000000000
--- a/sw/airborne/arch/sim/spi_hw.c
+++ /dev/null
@@ -1,3 +0,0 @@
-#include "spi.h"
-
-void spi_init( void ) {}
diff --git a/sw/airborne/arch/stm32/init_hw.h b/sw/airborne/arch/stm32/mcu_arch.c
similarity index 54%
rename from sw/airborne/arch/stm32/init_hw.h
rename to sw/airborne/arch/stm32/mcu_arch.c
index 5f601a4673..eb6760b1c6 100644
--- a/sw/airborne/arch/stm32/init_hw.h
+++ b/sw/airborne/arch/stm32/mcu_arch.c
@@ -1,34 +1,29 @@
/*
- * Paparazzi $Id$
+ * Paparazzi stm32 arch dependant microcontroller initialisation function
*
- * Copyright (C) 2009-2010 The Paparazzi Team
+ * Copyright (C) 2010 The Paparazzi team
*
- * This file is part of paparazzi.
+ * This file is part of Paparazzi.
*
- * paparazzi is free software; you can redistribute it and/or modify
+ * 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,
+ * 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
+ * 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.
- */
-
-/*
- *\brief STM low level hardware initialisation
- * PLL, MAM, VIC
*
*/
-#ifndef INIT_HW_H
-#define INIT_HW_H
+#include "mcu.h"
+
#include
#include
@@ -38,43 +33,7 @@
#include BOARD_CONFIG
-/* should probably not be here
- * a couple of macros to use the rev instruction
- */
-#define MyByteSwap16(in, out) { \
- asm volatile ( \
- "rev16 %0, %1\n\t" \
- : "=r" (out) \
- : "r"(in) \
- ); \
- }
-
-
-#ifdef PERIPHERALS_AUTO_INIT
-#ifdef USE_LED
-#include "led.h"
-#endif
-#if defined RADIO_CONTROL
-#if defined RADIO_CONTROL_LINK || defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT
-#include "subsystems/radio_control.h"
-#endif
-#endif
-#if defined USE_UART1 || defined USE_UART2 || defined USE_UART3
-#include "uart.h"
-#endif
-#if defined USE_I2C1 || defined USE_I2C2
-#include "i2c.h"
-#endif
-#endif /* PERIPHERALS_AUTO_INIT */
-
-
-/* declare functions and values from crt0.S & the linker control file */
-extern void reset(void);
-/* extern void exit(void); */
-extern void abort(void);
-
-
-static inline void hw_init(void) {
+void mcu_arch_init(void) {
#ifdef HSE_TYPE_EXT_CLK
/* Setup the microcontroller system.
@@ -119,33 +78,5 @@ static inline void hw_init(void) {
/* Set the Vector Table base location at 0x08000000 */
NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
-
-#ifdef PERIPHERALS_AUTO_INIT
-#ifdef USE_LED
- led_init();
-#endif
- /* for now this means using spektrum */
-#if defined RADIO_CONTROL & defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT & defined RADIO_CONTROL_BIND_IMPL_FUNC
- RADIO_CONTROL_BIND_IMPL_FUNC();
-#endif
-#ifdef USE_UART1
- uart1_init();
-#endif
-#ifdef USE_UART2
- uart2_init();
-#endif
-#ifdef USE_UART3
- uart3_init();
-#endif
-#ifdef USE_I2C1
- i2c1_init();
-#endif
-#ifdef USE_I2C2
- i2c2_init();
-#endif
-#endif /* PERIPHERALS_AUTO_INIT */
-
-
}
-#endif /* INIT_HW_H */
diff --git a/sw/airborne/arch/stm32/mcu_arch.h b/sw/airborne/arch/stm32/mcu_arch.h
new file mode 100644
index 0000000000..b8110a16cc
--- /dev/null
+++ b/sw/airborne/arch/stm32/mcu_arch.h
@@ -0,0 +1,45 @@
+/*
+ * Paparazzi stm32 arch dependant microcontroller initialisation function
+ *
+ * Copyright (C) 2010 The Paparazzi team
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+#ifndef STM32_MCU_ARCH_H
+#define STM32_MCU_ARCH_H
+
+extern void mcu_arch_init(void);
+
+
+/* should probably not be here
+ * a couple of macros to use the rev instruction
+ */
+#define MyByteSwap16(in, out) { \
+ asm volatile ( \
+ "rev16 %0, %1\n\t" \
+ : "=r" (out) \
+ : "r"(in) \
+ ); \
+ }
+
+#define mcu_int_enable() {}
+#define mcu_int_disable() {}
+
+#endif /* STM32_MCU_ARCH_H */
diff --git a/sw/airborne/arch/stm32/adc_hw.c b/sw/airborne/arch/stm32/mcu_periph/adc_arch.c
similarity index 97%
rename from sw/airborne/arch/stm32/adc_hw.c
rename to sw/airborne/arch/stm32/mcu_periph/adc_arch.c
index bbea45a95c..8ff6734e31 100644
--- a/sw/airborne/arch/stm32/adc_hw.c
+++ b/sw/airborne/arch/stm32/mcu_periph/adc_arch.c
@@ -83,8 +83,7 @@
*/
-#include "adc.h"
-#include "adc_hw.h"
+#include "mcu_periph/adc.h"
#include
#include
#include
@@ -125,16 +124,16 @@ static inline void adc_init_irq( void );
// {{{
/*
- GPIO mapping for ADC1 pins (PA.B, PB.1, PC.3, PC.5).
+ GPIO mapping for ADC1 pins (PB.1, PB.0, PC.5, PC.3).
Can be changed by predefining ADC1_GPIO_INIT.
*/
#ifdef USE_AD1
#ifndef ADC1_GPIO_INIT
#define ADC1_GPIO_INIT(gpio) { \
- (gpio).GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1; \
+ (gpio).GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_0; \
(gpio).GPIO_Mode = GPIO_Mode_AIN; \
GPIO_Init(GPIOB, (&gpio)); \
- (gpio).GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_5; \
+ (gpio).GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_3; \
GPIO_Init(GPIOC, (&gpio)); \
}
#endif // ADC1_GPIO_INIT
@@ -387,7 +386,9 @@ void adc_init( void ) {
// using defines.
adc_channel_map[0] = ADC_Channel_8;
adc_channel_map[1] = ADC_Channel_9;
- adc_channel_map[2] = ADC_Channel_13;
+ // adc_channel_map[2] = ADC_Channel_13;
+ // FIXME for now we get battery voltage this way
+ adc_channel_map[2] = ADC_Channel_0;
adc_channel_map[3] = ADC_Channel_15;
adc_init_rcc();
diff --git a/sw/airborne/arch/stm32/adc_hw.h b/sw/airborne/arch/stm32/mcu_periph/adc_arch.h
similarity index 100%
rename from sw/airborne/arch/stm32/adc_hw.h
rename to sw/airborne/arch/stm32/mcu_periph/adc_arch.h
diff --git a/sw/airborne/arch/stm32/can_hw.c b/sw/airborne/arch/stm32/mcu_periph/can_arch.c
similarity index 99%
rename from sw/airborne/arch/stm32/can_hw.c
rename to sw/airborne/arch/stm32/mcu_periph/can_arch.c
index 5d0991e3ea..2af91534c1 100644
--- a/sw/airborne/arch/stm32/can_hw.c
+++ b/sw/airborne/arch/stm32/mcu_periph/can_arch.c
@@ -25,7 +25,7 @@
#include
#include
-#include "can_hw.h"
+#include "mcu_periph/can.h"
#include
#include
diff --git a/sw/airborne/arch/stm32/can_hw.h b/sw/airborne/arch/stm32/mcu_periph/can_arch.h
similarity index 89%
rename from sw/airborne/arch/stm32/can_hw.h
rename to sw/airborne/arch/stm32/mcu_periph/can_arch.h
index e6f6228a71..b2fa04798a 100644
--- a/sw/airborne/arch/stm32/can_hw.h
+++ b/sw/airborne/arch/stm32/mcu_periph/can_arch.h
@@ -22,11 +22,11 @@
*
*/
-#ifndef CAN_HW_H
-#define CAN_HW_H
+#ifndef MCU_PERIPH_STM32_CAN_ARCH_H
+#define MCU_PERIPH_STM32_CAN_ARCH_H
void can_hw_init(void);
void usb_lp_can1_rx0_irq_handler(void);
int can_hw_transmit(uint32_t id, const uint8_t *buf, uint8_t len);
-#endif /* CAN_HW_H */
+#endif /* MCU_PERIPH_STM32_CAN_ARCH_H */
diff --git a/sw/airborne/arch/stm32/i2c_hw.c b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c
similarity index 99%
rename from sw/airborne/arch/stm32/i2c_hw.c
rename to sw/airborne/arch/stm32/mcu_periph/i2c_arch.c
index fb9325d7a4..2099326c6c 100644
--- a/sw/airborne/arch/stm32/i2c_hw.c
+++ b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c
@@ -1,4 +1,4 @@
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include
#include
diff --git a/sw/airborne/arch/stm32/i2c_hw.h b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.h
similarity index 97%
rename from sw/airborne/arch/stm32/i2c_hw.h
rename to sw/airborne/arch/stm32/mcu_periph/i2c_arch.h
index 2d41241471..0274829fc1 100644
--- a/sw/airborne/arch/stm32/i2c_hw.h
+++ b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.h
@@ -28,7 +28,7 @@
#ifndef I2C_HW_H
#define I2C_HW_H
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include
diff --git a/sw/airborne/arch/stm32/uart_hw.c b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c
similarity index 99%
rename from sw/airborne/arch/stm32/uart_hw.c
rename to sw/airborne/arch/stm32/mcu_periph/uart_arch.c
index f1c1fd4743..3edce0c1d1 100644
--- a/sw/airborne/arch/stm32/uart_hw.c
+++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c
@@ -21,7 +21,7 @@
* Boston, MA 02111-1307, USA.
*/
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include
#include
@@ -282,9 +282,6 @@ volatile uint16_t uart3_tx_insert_idx, uart3_tx_extract_idx;
volatile bool_t uart3_tx_running;
uint8_t uart3_tx_buffer[UART3_TX_BUFFER_SIZE];
-#include "led.h"
-
-
void uart3_init( void ) {
/* init RCC */
diff --git a/sw/airborne/arch/stm32/uart_hw.h b/sw/airborne/arch/stm32/mcu_periph/uart_arch.h
similarity index 97%
rename from sw/airborne/arch/stm32/uart_hw.h
rename to sw/airborne/arch/stm32/mcu_periph/uart_arch.h
index 8679622711..e281700dba 100644
--- a/sw/airborne/arch/stm32/uart_hw.h
+++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.h
@@ -1,7 +1,7 @@
/*
* $Id$
*
- * Copyright (C) 2009 Antoine Drouin
+ * Copyright (C) 2009-2010 The Paparazzi Team
*
* This file is part of paparazzi.
*
@@ -26,8 +26,8 @@
*
*/
-#ifndef UART_HW_H
-#define UART_HW_H
+#ifndef STM32_UART_ARCH_H
+#define STM32_UART_ARCH_H
#include "std.h"
@@ -183,4 +183,4 @@ extern uint8_t uart3_tx_buffer[UART3_TX_BUFFER_SIZE];
void uart_init( void );
-#endif /* UART_HW_H */
+#endif /* STM32_UART_ARCH_H */
diff --git a/sw/airborne/arch/stm32/peripherals/hmc8543_arch.c b/sw/airborne/arch/stm32/peripherals/hmc8543_arch.c
index e85724e199..f50c285037 100644
--- a/sw/airborne/arch/stm32/peripherals/hmc8543_arch.c
+++ b/sw/airborne/arch/stm32/peripherals/hmc8543_arch.c
@@ -27,7 +27,7 @@
#include
#include
#include
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
void exti9_5_irq_handler(void);
diff --git a/sw/airborne/arch/stm32/stm32_vector_table.c b/sw/airborne/arch/stm32/stm32_vector_table.c
index 40b187d87f..a2cd4e7348 100644
--- a/sw/airborne/arch/stm32/stm32_vector_table.c
+++ b/sw/airborne/arch/stm32/stm32_vector_table.c
@@ -1,7 +1,7 @@
/*
* $Id$
*
- * Copyright (C) 2010 Antoine Drouin
+ * Copyright (C) 2010 The Paparazzi Team
*
* This file is part of Paparazzi.
*
@@ -35,28 +35,28 @@
#endif
#if defined USE_UART1 || OVERRIDE_UART1_IRQ_HANDLER
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define USART1_IRQ_HANDLER usart1_irq_handler
#else
#define USART1_IRQ_HANDLER null_handler
#endif
#if defined USE_UART2 || OVERRIDE_UART2_IRQ_HANDLER
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define USART2_IRQ_HANDLER usart2_irq_handler
#else
#define USART2_IRQ_HANDLER null_handler
#endif
#if defined USE_UART3 || OVERRIDE_UART3_IRQ_HANDLER
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define USART3_IRQ_HANDLER usart3_irq_handler
#else
#define USART3_IRQ_HANDLER null_handler
#endif
#if defined USE_UART5 || OVERRIDE_UART5_IRQ_HANDLER
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define USART5_IRQ_HANDLER usart5_irq_handler
#else
#define USART5_IRQ_HANDLER null_handler
@@ -64,7 +64,7 @@
#ifdef USE_I2C1
-#include "i2c_hw.h"
+#include "mcu_periph/i2c_arch.h"
#define I2C1_EV_IRQ_HANDLER i2c1_ev_irq_handler
#define I2C1_ER_IRQ_HANDLER i2c1_er_irq_handler
#else
@@ -73,7 +73,7 @@
#endif
#ifdef USE_I2C2
-#include "i2c_hw.h"
+#include "mcu_periph/i2c_arch.h"
#define I2C2_EV_IRQ_HANDLER i2c2_ev_irq_handler
#define I2C2_ER_IRQ_HANDLER i2c2_er_irq_handler
#else
diff --git a/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c b/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c
index 6cd584f842..ca50b9c639 100644
--- a/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c
+++ b/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c
@@ -7,7 +7,7 @@
#include
#include
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
/* gyro int handler */
void exti15_10_irq_handler(void);
diff --git a/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c b/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c
index 316122ebe4..91b609b63d 100644
--- a/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c
+++ b/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c
@@ -27,10 +27,9 @@
#include
#include
#include
-#include "uart.h"
#include "subsystems/radio_control.h"
#include "subsystems/radio_control/spektrum_arch.h"
-#include "firmwares/rotorcraft/autopilot.h"
+#include "mcu_periph/uart.h"
#define SPEKTRUM_CHANNELS_PER_FRAME 7
diff --git a/sw/airborne/boards/booz/baro_board.c b/sw/airborne/boards/booz/baro_board.c
index cc92db4224..aa43c684a5 100644
--- a/sw/airborne/boards/booz/baro_board.c
+++ b/sw/airborne/boards/booz/baro_board.c
@@ -21,7 +21,7 @@
*/
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
#include "generated/airframe.h"
#include "led.h"
diff --git a/sw/airborne/boards/booz/baro_board.h b/sw/airborne/boards/booz/baro_board.h
index 135bebbdac..f1fae16a48 100644
--- a/sw/airborne/boards/booz/baro_board.h
+++ b/sw/airborne/boards/booz/baro_board.h
@@ -3,7 +3,7 @@
#include "std.h"
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
#include "booz/booz2_analog.h"
/* we don't need that on this board */
diff --git a/sw/airborne/boards/booz/test_baro.c b/sw/airborne/boards/booz/test_baro.c
index 05b81ae065..f00cbe54e9 100644
--- a/sw/airborne/boards/booz/test_baro.c
+++ b/sw/airborne/boards/booz/test_baro.c
@@ -29,12 +29,11 @@
#include BOARD_CONFIG
-#include "init_hw.h"
-#include "interrupt_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "downlink.h"
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
static inline void main_init( void );
static inline void main_periodic_task( void );
@@ -57,11 +56,11 @@ int main(void) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
booz2_analog_init();
baro_init();
- int_enable();
+ mcu_int_enable();
}
diff --git a/sw/airborne/boards/booz_1.0.h b/sw/airborne/boards/booz_1.0.h
index 51e461a3c9..7634648333 100644
--- a/sw/airborne/boards/booz_1.0.h
+++ b/sw/airborne/boards/booz_1.0.h
@@ -93,6 +93,8 @@
#define PWM1_PINSEL_BIT 14
+#define BOARD_HAS_BARO
+
/*
* Modem
*/
diff --git a/sw/airborne/boards/lisa_l/baro_board.c b/sw/airborne/boards/lisa_l/baro_board.c
index 0f30dbd2e9..3bf8cc2a20 100644
--- a/sw/airborne/boards/lisa_l/baro_board.c
+++ b/sw/airborne/boards/lisa_l/baro_board.c
@@ -1,5 +1,5 @@
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
struct Baro baro;
struct BaroBoard baro_board;
diff --git a/sw/airborne/boards/lisa_l/baro_board.h b/sw/airborne/boards/lisa_l/baro_board.h
index 017d41a99b..f6c59fd3c7 100644
--- a/sw/airborne/boards/lisa_l/baro_board.h
+++ b/sw/airborne/boards/lisa_l/baro_board.h
@@ -8,7 +8,7 @@
#define BOARDS_LISA_L_BARO_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
enum LisaBaroStatus {
LBS_UNINITIALIZED,
diff --git a/sw/airborne/boards/lisa_l/test_baro.c b/sw/airborne/boards/lisa_l/test_baro.c
index dcd8122dd6..20e9dbef66 100644
--- a/sw/airborne/boards/lisa_l/test_baro.c
+++ b/sw/airborne/boards/lisa_l/test_baro.c
@@ -34,7 +34,7 @@
#include "downlink.h"
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
//#include "my_debug_servo.h"
static inline void main_init( void );
diff --git a/sw/airborne/boards/lisa_l_1.0.h b/sw/airborne/boards/lisa_l_1.0.h
index 417fd309f0..8724588595 100644
--- a/sw/airborne/boards/lisa_l_1.0.h
+++ b/sw/airborne/boards/lisa_l_1.0.h
@@ -20,8 +20,9 @@
#define IMU_ACC_DRDY_GPIO_PORTSOURCE GPIO_PortSourceGPIOD
-#define ADC_CHANNEL_VSUPPLY 4
-#define DefaultVoltageOfAdc(adc) (0.01787109375*adc)
+#define ADC_CHANNEL_VSUPPLY 2
+#define DefaultVoltageOfAdc(adc) (0.0059*adc)
+#define BOARD_HAS_BARO
#endif /* CONFIG_LISA_V1_0_H */
diff --git a/sw/airborne/boards/pc/baro_board.c b/sw/airborne/boards/pc/baro_board.c
index dd87d54ffa..52f3cb19fe 100644
--- a/sw/airborne/boards/pc/baro_board.c
+++ b/sw/airborne/boards/pc/baro_board.c
@@ -1,6 +1,6 @@
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
struct Baro baro;
diff --git a/sw/airborne/booz/arch/lpc21/booz2_analog_hw.c b/sw/airborne/booz/arch/lpc21/booz2_analog_hw.c
index 8c1f2a68c7..a991d3e3ed 100644
--- a/sw/airborne/booz/arch/lpc21/booz2_analog_hw.c
+++ b/sw/airborne/booz/arch/lpc21/booz2_analog_hw.c
@@ -24,7 +24,7 @@
#include "booz2_analog.h"
/* analog_arch includes baro ??? naaaa we don't want double references */
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
#include "firmwares/rotorcraft/battery.h"
#ifndef USE_EXTRA_ADC
diff --git a/sw/airborne/booz/arch/sim/booz2_unsimulated_peripherals.c b/sw/airborne/booz/arch/sim/booz2_unsimulated_peripherals.c
index 93912efe1d..5a86889e63 100644
--- a/sw/airborne/booz/arch/sim/booz2_unsimulated_peripherals.c
+++ b/sw/airborne/booz/arch/sim/booz2_unsimulated_peripherals.c
@@ -21,8 +21,8 @@
* Boston, MA 02111-1307, USA.
*/
-#include "uart.h"
-#include "i2c.h"
+#include "mcu_periph/uart.h"
+//#include "mcu_periph/i2c.h"
void uart0_init( void ) {}
void uart1_init( void ) {}
diff --git a/sw/airborne/booz/booz2_datalink.c b/sw/airborne/booz/booz2_datalink.c
index 2fae20a594..adb77a1825 100644
--- a/sw/airborne/booz/booz2_datalink.c
+++ b/sw/airborne/booz/booz2_datalink.c
@@ -32,7 +32,7 @@
#include "downlink.h"
#include "messages.h"
#include "dl_protocol.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#ifdef BOOZ_FMS_TYPE
#include "booz_fms.h"
diff --git a/sw/airborne/booz/booz_gps.h b/sw/airborne/booz/booz_gps.h
index addeb62043..7d30611baf 100644
--- a/sw/airborne/booz/booz_gps.h
+++ b/sw/airborne/booz/booz_gps.h
@@ -26,7 +26,7 @@
#include "std.h"
#include "math/pprz_geodetic_int.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
struct Booz_gps_state {
struct EcefCoor_i ecef_pos; /* pos ECEF in cm */
diff --git a/sw/airborne/booz/test/booz2_test_mc.c b/sw/airborne/booz/test/booz2_test_mc.c
index 51cd5ebcdc..ba755f46ce 100644
--- a/sw/airborne/booz/test/booz2_test_mc.c
+++ b/sw/airborne/booz/test/booz2_test_mc.c
@@ -23,17 +23,16 @@
#include
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "commands.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "firmwares/rotorcraft/actuators.h"
static inline void main_init( void );
@@ -53,7 +52,7 @@ int main( void ) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
uart1_init_tx();
@@ -61,7 +60,7 @@ static inline void main_init( void ) {
i2c_init();
actuators_init();
- int_enable();
+ mcu_int_enable();
}
static inline void main_periodic_task( void ) {
diff --git a/sw/airborne/csc/csc_adc.c b/sw/airborne/csc/csc_adc.c
index be8f0197cf..d81fa19d8a 100644
--- a/sw/airborne/csc/csc_adc.c
+++ b/sw/airborne/csc/csc_adc.c
@@ -1,12 +1,12 @@
#include "csc_adc.h"
#include "csc_ap_link.h"
#include
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "print.h"
#include "LPC21xx.h"
#include "led.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include ACTUATORS
#include "csc_servos.h"
#include "sys_time.h"
diff --git a/sw/airborne/csc/csc_main.c b/sw/airborne/csc/csc_main.c
index 1bae760ee7..90474cd2fc 100644
--- a/sw/airborne/csc/csc_main.c
+++ b/sw/airborne/csc/csc_main.c
@@ -28,11 +28,11 @@
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
#include "interrupt_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "csc_telemetry.h"
#include "generated/periodic.h"
#include "downlink.h"
@@ -66,7 +66,7 @@ struct NedCoor_i booz_ins_gps_speed_cm_s_ned;
static void csc_main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
@@ -100,7 +100,7 @@ static void csc_main_init( void ) {
#ifdef USE_CSC_THROTTLE
csc_throttle_init();
#endif
- int_enable();
+ mcu_int_enable();
}
diff --git a/sw/airborne/csc/csc_protocol.c b/sw/airborne/csc/csc_protocol.c
index 2ff5b7ee21..f3167c7c20 100644
--- a/sw/airborne/csc/csc_protocol.c
+++ b/sw/airborne/csc/csc_protocol.c
@@ -26,7 +26,7 @@
#include
#include "csc_protocol.h"
-#include "can.h"
+#include "mcu_periph/can.h"
#include "csc_msg_def.h"
// #include "init_hw.h"
diff --git a/sw/airborne/csc/csc_throttle.c b/sw/airborne/csc/csc_throttle.c
index 20cbfcb3cf..008a269fe4 100644
--- a/sw/airborne/csc/csc_throttle.c
+++ b/sw/airborne/csc/csc_throttle.c
@@ -31,7 +31,7 @@
//#include "downlink.h"
//#include "messages.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "csc_ap_link.h"
//#include "print.h"
//#include "com_stats.h"
diff --git a/sw/airborne/datalink.c b/sw/airborne/datalink.c
index ef990bfc77..907b45b0a7 100644
--- a/sw/airborne/datalink.c
+++ b/sw/airborne/datalink.c
@@ -39,6 +39,10 @@
#include "subsystems/navigation/traffic_info.h"
#endif // TRAFFIC_INFO
+#if defined NAV || defined WIND_INFO
+#include "estimator.h"
+#endif
+
#ifdef USE_JOYSTICK
#include "joystick.h"
#endif
@@ -60,7 +64,7 @@
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "downlink.h"
#include "ap_downlink.h"
diff --git a/sw/airborne/estimator.c b/sw/airborne/estimator.c
index 05f335a97f..85b369f2ca 100644
--- a/sw/airborne/estimator.c
+++ b/sw/airborne/estimator.c
@@ -30,7 +30,7 @@
#include
#include "estimator.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "ap_downlink.h"
#include "gps.h"
#include "subsystems/nav.h"
@@ -233,3 +233,26 @@ void estimator_update_state_gps( void ) {
DOWNLINK_SEND_ATTITUDE(ExtraPprzTransport,&estimator_phi,&estimator_psi,&estimator_theta);
#endif
}
+
+#include "subsystems/sensors/infrared.h"
+void estimator_update_state_infrared( void ) {
+ estimator_phi = atan2(ir_roll, ir_top) - ir_roll_neutral;
+
+ estimator_theta = atan2(ir_pitch, ir_top) - ir_pitch_neutral;
+
+ if (estimator_theta < -M_PI_2)
+ estimator_theta += M_PI;
+ else if (estimator_theta > M_PI_2)
+ estimator_theta -= M_PI;
+
+ if (estimator_phi >= 0)
+ estimator_phi *= ir_correction_right;
+ else
+ estimator_phi *= ir_correction_left;
+
+ if (estimator_theta >= 0)
+ estimator_theta *= ir_correction_up;
+ else
+ estimator_theta *= ir_correction_down;
+
+}
diff --git a/sw/airborne/estimator.h b/sw/airborne/estimator.h
index c221d6a463..a26e5cdc89 100644
--- a/sw/airborne/estimator.h
+++ b/sw/airborne/estimator.h
@@ -127,4 +127,6 @@ extern void alt_kalman( float );
#define EstimatorSetRate(p, q) { estimator_p = p; estimator_q = q; }
+extern void estimator_update_state_infrared( void );
+
#endif /* ESTIMATOR_H */
diff --git a/sw/airborne/fbw_downlink.h b/sw/airborne/fbw_downlink.h
index d4280f8e4d..aeca720421 100644
--- a/sw/airborne/fbw_downlink.h
+++ b/sw/airborne/fbw_downlink.h
@@ -42,7 +42,7 @@
#include "commands.h"
#include "actuators.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "firmwares/fixedwing/main_fbw.h"
#include "subsystems/radio_control.h"
#include "inter_mcu.h"
diff --git a/sw/airborne/firmwares/beth/bench_sensors.h b/sw/airborne/firmwares/beth/bench_sensors.h
index de655ad046..9d3df4a776 100644
--- a/sw/airborne/firmwares/beth/bench_sensors.h
+++ b/sw/airborne/firmwares/beth/bench_sensors.h
@@ -8,9 +8,7 @@
#endif
#ifdef USE_CAN1
-#include "can.h"
-#include "can_hw.h"
-#include
+#include "mcu_periph/can.h"
extern uint16_t can_err_flags;
#endif
diff --git a/sw/airborne/firmwares/beth/bench_sensors_can.c b/sw/airborne/firmwares/beth/bench_sensors_can.c
index 597f798151..ada5ccfca7 100644
--- a/sw/airborne/firmwares/beth/bench_sensors_can.c
+++ b/sw/airborne/firmwares/beth/bench_sensors_can.c
@@ -1,5 +1,5 @@
#include "bench_sensors.h"
-#include "can.h"
+#include "mcu_periph/can.h"
#include "led.h"
//uint16_t halfw1,halfw2,halfw3,halfw4;
diff --git a/sw/airborne/firmwares/beth/main_coders.c b/sw/airborne/firmwares/beth/main_coders.c
index 2e927c02ab..31e873270d 100644
--- a/sw/airborne/firmwares/beth/main_coders.c
+++ b/sw/airborne/firmwares/beth/main_coders.c
@@ -1,6 +1,6 @@
#include BOARD_CONFIG
#include "init_hw.h"
-#include "can.h"
+#include "mcu_periph/can.h"
#include "sys_time.h"
#include "downlink.h"
diff --git a/sw/airborne/firmwares/beth/main_stm32.c b/sw/airborne/firmwares/beth/main_stm32.c
index e34bf8518e..bec7f05419 100644
--- a/sw/airborne/firmwares/beth/main_stm32.c
+++ b/sw/airborne/firmwares/beth/main_stm32.c
@@ -24,8 +24,8 @@
#include BOARD_CONFIG
#include "std.h"
-#include "init_hw.h"
-#include "can.h"
+#include "mcu.h"
+#include "mcu_periph/can.h"
#include "sys_time.h"
#include "downlink.h"
#include "booz/booz2_commands.h"
@@ -61,7 +61,7 @@ int main(void) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
actuators_init();
//radio_control_init();
diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c
index b0954cc92d..acc198898d 100644
--- a/sw/airborne/firmwares/fixedwing/main_ap.c
+++ b/sw/airborne/firmwares/fixedwing/main_ap.c
@@ -34,14 +34,13 @@
#include
#include "firmwares/fixedwing/main_ap.h"
+#include "mcu.h"
-#include "interrupt_hw.h"
-#include "init_hw.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
#include "firmwares/fixedwing/guidance/guidance_v.h"
#include "gps.h"
-#include "infrared.h"
+#include "subsystems/sensors/infrared.h"
#include "gyro.h"
#include "ap_downlink.h"
#include "subsystems/nav.h"
@@ -60,16 +59,9 @@
#include "rc_settings.h"
#endif
-#ifdef LED
-#include "led.h"
-#endif
-
-#if defined USE_I2C0 || USE_I2C1
-#include "i2c.h"
-#endif
#ifdef USE_SPI
-#include "spi.h"
+#include "mcu_periph/spi.h"
#endif
#ifdef TRAFFIC_INFO
@@ -480,12 +472,9 @@ void periodic_task_ap( void ) {
void init_ap( void ) {
#ifndef SINGLE_MCU /** init done in main_fbw in single MCU */
- hw_init();
+ mcu_init();
sys_time_init();
-#ifdef LED
- led_init();
-#endif
#ifdef ADC
adc_init();
@@ -502,35 +491,11 @@ void init_ap( void ) {
#ifdef USE_GPS
gps_init();
#endif
-#ifdef USE_UART0
- Uart0Init();
-#endif
-#ifdef USE_UART1
- Uart1Init();
-#endif
-#ifdef USE_UART2
- Uart2Init();
-#endif
-#ifdef USE_UART3
- Uart3Init();
-#endif
-#ifdef USE_USB_SERIAL
- VCOM_init();
-#endif
#ifdef USE_GPIO
GpioInit();
#endif
-#ifdef USE_I2C0
- i2c0_init();
-#endif
-#ifdef USE_I2C1
- i2c1_init();
-#endif
-#ifdef USE_I2C2
- i2c2_init();
-#endif
/************* Links initialization ***************/
#if defined USE_SPI
@@ -555,7 +520,7 @@ void init_ap( void ) {
modules_init();
/** - start interrupt task */
- int_enable();
+ mcu_int_enable();
/** wait 0.5s (historical :-) */
sys_time_usleep(500000);
diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c
index ed29dab3e6..f4bba8c24f 100644
--- a/sw/airborne/firmwares/fixedwing/main_fbw.c
+++ b/sw/airborne/firmwares/fixedwing/main_fbw.c
@@ -1,22 +1,22 @@
/*
* Paparazzi $Id$
*
- * Copyright (C) 2003-2006 Pascal Brisset, Antoine Drouin
+ * Copyright (C) 2003-2010 The Paparazzi Team
*
- * This file is part of paparazzi.
+ * This file is part of Paparazzi.
*
- * paparazzi is free software; you can redistribute it and/or modify
+ * 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,
+ * 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
+ * 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.
*
@@ -31,15 +31,14 @@
* ( for parameters like the supply )
*/
-#include "firmwares/fixedwing/main_fbw.h"
#include "generated/airframe.h"
-#include "init_hw.h"
-#include "interrupt_hw.h"
+#include "firmwares/fixedwing/main_fbw.h"
+#include "mcu.h"
+
#include "led.h"
-#include "uart.h"
-#include "spi.h"
-#include "adc.h"
+#include "mcu_periph/spi.h"
+#include "mcu_periph/adc.h"
#ifdef USE_USB_SERIAL
#include "usb_serial.h"
@@ -84,33 +83,17 @@ uint8_t fbw_mode;
/********** INIT *************************************************************/
void init_fbw( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
-#ifdef LED
- led_init();
-#endif
-#ifdef USE_UART0
- uart0_init();
-#endif
-#ifdef USE_UART1
- uart1_init();
-#endif
-#ifdef USE_UART2
- uart2_init();
-#endif
-#ifdef USE_UART3
- uart3_init();
-#endif
- // FIXME: remove STM32 flag
#ifdef ADC
adc_init();
-#ifndef STM32
+#ifdef ADC_CHANNEL_VSUPPLY
adc_buf_channel(ADC_CHANNEL_VSUPPLY, &vsupply_adc_buf, DEFAULT_AV_NB_SAMPLE);
-# ifdef ADC_CHANNEL_CURRENT
+#endif
+#ifdef ADC_CHANNEL_CURRENT
adc_buf_channel(ADC_CHANNEL_CURRENT, ¤t_adc_buf, DEFAULT_AV_NB_SAMPLE);
-# endif
-#endif /* ! STM32 */
+#endif
#endif /* ADC */
#ifdef ACTUATORS
@@ -229,10 +212,12 @@ void periodic_task_fbw( void ) {
if (!_10Hz)
{
#ifdef ADC
+#ifdef ADC_CHANNEL_VSUPPLY
fbw_vsupply_decivolt = VoltageOfAdc((10*(vsupply_adc_buf.sum/vsupply_adc_buf.av_nb_sample)));
-# ifdef ADC_CHANNEL_CURRENT
+#endif
+#ifdef ADC_CHANNEL_CURRENT
fbw_current_milliamp = MilliAmpereOfAdc((current_adc_buf.sum/current_adc_buf.av_nb_sample));
-# endif
+#endif
#endif
#if ((! defined ADC_CHANNEL_CURRENT) && defined MILLIAMP_AT_FULL_THROTTLE)
diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.h b/sw/airborne/firmwares/fixedwing/main_fbw.h
index d21aa0e451..efc5b7d505 100644
--- a/sw/airborne/firmwares/fixedwing/main_fbw.h
+++ b/sw/airborne/firmwares/fixedwing/main_fbw.h
@@ -31,7 +31,7 @@
#define FBW_H
#include "std.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
/** Fly by wire modes */
#define FBW_MODE_MANUAL 0
diff --git a/sw/airborne/firmwares/logger/main_logger.c b/sw/airborne/firmwares/logger/main_logger.c
index 8f5adf2df1..69a104dde1 100644
--- a/sw/airborne/firmwares/logger/main_logger.c
+++ b/sw/airborne/firmwares/logger/main_logger.c
@@ -78,12 +78,10 @@
*/
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
+#include "mcu_periph/uart.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart_hw.h"
-#include "uart.h"
#include "usb_msc_hw.h"
@@ -513,17 +511,10 @@ int main(void)
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
-#ifdef USE_UART0
- Uart0Init();
-#endif
-#ifdef USE_UART1
- Uart1Init();
-#endif
-
#ifdef USE_MAX11040
max11040_init_ssp();
max11040_init();
diff --git a/sw/airborne/firmwares/motor_bench/main_motor_bench.c b/sw/airborne/firmwares/motor_bench/main_motor_bench.c
index 152fc6f1d3..8c45c24e10 100644
--- a/sw/airborne/firmwares/motor_bench/main_motor_bench.c
+++ b/sw/airborne/firmwares/motor_bench/main_motor_bench.c
@@ -1,9 +1,8 @@
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
#include "mb_tacho.h"
#include "mb_servo.h"
#include "i2c.h"
@@ -13,7 +12,7 @@
#include "mb_scale.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
@@ -42,7 +41,7 @@ int main( void ) {
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
led_init();
sys_time_init();
mb_tacho_init();
@@ -62,7 +61,7 @@ static inline void main_init( void ) {
uart0_init();
mb_mode_init();
- int_enable();
+ mcu_int_enable();
}
static inline void main_periodic_task( void ) {
diff --git a/sw/airborne/firmwares/motor_bench/mb_current.c b/sw/airborne/firmwares/motor_bench/mb_current.c
index 5e3046cde4..2089e9f814 100644
--- a/sw/airborne/firmwares/motor_bench/mb_current.c
+++ b/sw/airborne/firmwares/motor_bench/mb_current.c
@@ -1,6 +1,6 @@
#include "mb_current.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
static struct adc_buf mb_current_buf;
diff --git a/sw/airborne/firmwares/motor_bench/mb_modes.c b/sw/airborne/firmwares/motor_bench/mb_modes.c
index 920f07c763..650736de0e 100644
--- a/sw/airborne/firmwares/motor_bench/mb_modes.c
+++ b/sw/airborne/firmwares/motor_bench/mb_modes.c
@@ -2,7 +2,7 @@
//#include "mb_static.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include "sys_time.h"
diff --git a/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.c b/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.c
index be043b9669..ae69747ecc 100644
--- a/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.c
+++ b/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.c
@@ -1,12 +1,12 @@
#include "firmwares/rotorcraft/actuators.h"
-#include "actuators_asctec.h"
+#include "firmwares/rotorcraft/actuators/actuators_asctec.h"
#ifdef ACTUATORS_ASCTEC_V2_PROTOCOL
#include "firmwares/rotorcraft/actuators/supervision.h"
#endif
#include "booz/booz2_commands.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "sys_time.h"
diff --git a/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.h b/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.h
index a82e4ef968..9b9dc58916 100644
--- a/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.h
+++ b/sw/airborne/firmwares/rotorcraft/actuators/actuators_asctec.h
@@ -24,7 +24,7 @@
#ifndef ACTUATORS_ASCTEC_H
#define ACTUATORS_ASCTEC_H
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
enum actuators_astec_cmd { NONE,
TEST,
diff --git a/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.c b/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.c
index e86651621e..90bb98f8f9 100644
--- a/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.c
+++ b/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.c
@@ -22,10 +22,10 @@
*/
#include "firmwares/rotorcraft/actuators.h"
-#include "actuators_mkk.h"
+#include "firmwares/rotorcraft/actuators/actuators_mkk.h"
#include "booz/booz2_commands.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "sys_time.h"
diff --git a/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.h b/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.h
index 8b6d821098..77b36eb980 100644
--- a/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.h
+++ b/sw/airborne/firmwares/rotorcraft/actuators/actuators_mkk.h
@@ -25,7 +25,7 @@
#define ACTUATORS_MKK_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "generated/airframe.h"
diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c
index 5f6cd5485d..4d72a022e3 100644
--- a/sw/airborne/firmwares/rotorcraft/main.c
+++ b/sw/airborne/firmwares/rotorcraft/main.c
@@ -25,10 +25,9 @@
#define MODULES_C
#include
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
#include "downlink.h"
#include "firmwares/rotorcraft/telemetry.h"
@@ -42,7 +41,7 @@
#include "booz_gps.h"
#include "booz/booz2_analog.h"
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
#include "firmwares/rotorcraft/battery.h"
@@ -95,7 +94,7 @@ STATIC_INLINE void main_init( void ) {
}
#endif
- hw_init();
+ mcu_init();
sys_time_init();
@@ -130,7 +129,7 @@ STATIC_INLINE void main_init( void ) {
modules_init();
- int_enable();
+ mcu_int_enable();
}
diff --git a/sw/airborne/firmwares/rotorcraft/main.h b/sw/airborne/firmwares/rotorcraft/main.h
index 7bf6d26716..9e9a651b53 100644
--- a/sw/airborne/firmwares/rotorcraft/main.h
+++ b/sw/airborne/firmwares/rotorcraft/main.h
@@ -1,7 +1,7 @@
/*
* $Id$
*
- * Copyright (C) 2008-2009 Antoine Drouin
+ * Copyright (C) 2008-2010 The Paparazzi Team
*
* This file is part of paparazzi.
*
diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c
index b742b5da7a..463927fe1e 100644
--- a/sw/airborne/firmwares/rotorcraft/navigation.c
+++ b/sw/airborne/firmwares/rotorcraft/navigation.c
@@ -306,7 +306,7 @@ void nav_periodic_task() {
#include "downlink.h"
#include "messages.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
void nav_move_waypoint(uint8_t wp_id, struct EnuCoor_i * new_pos) {
if (wp_id < nb_waypoint) {
INT32_VECT3_COPY(waypoints[wp_id],(*new_pos));
diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h
index fddcc79b98..1cf5801b80 100644
--- a/sw/airborne/firmwares/rotorcraft/telemetry.h
+++ b/sw/airborne/firmwares/rotorcraft/telemetry.h
@@ -26,7 +26,7 @@
#include "std.h"
#include "messages.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "downlink.h"
@@ -50,8 +50,8 @@
#include "booz_gps.h"
#include "subsystems/ins.h"
#include "subsystems/ahrs.h"
-
-#include "i2c_hw.h"
+//FIXME: wtf ??!!
+#include "mcu_periph/i2c_arch.h"
extern uint8_t telemetry_mode_Main_DefaultChannel;
diff --git a/sw/airborne/firmwares/setup/setup_actuators.c b/sw/airborne/firmwares/setup/setup_actuators.c
index 9c8afa4f32..7404d02b18 100644
--- a/sw/airborne/firmwares/setup/setup_actuators.c
+++ b/sw/airborne/firmwares/setup/setup_actuators.c
@@ -1,6 +1,5 @@
#include "std.h"
-#include "init_hw.h"
-#include "interrupt_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
#include "firmwares/fixedwing/actuators.h"
@@ -8,7 +7,7 @@
#include "generated/airframe.h"
#define DATALINK_C
#include "datalink.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "pprz_transport.h"
#include "firmwares/fixedwing/main_fbw.h"
#include "downlink.h"
@@ -48,7 +47,7 @@ void dl_parse_msg( void ) {
#define PprzUartInit() Link(Init())
void init_fbw( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
@@ -63,7 +62,7 @@ void init_fbw( void ) {
// SetServo(SERVO_GAZ, SERVO_GAZ_MIN);
- int_enable();
+ mcu_int_enable();
}
void periodic_task_fbw(void) {
diff --git a/sw/airborne/firmwares/tutorial/main_demo3.c b/sw/airborne/firmwares/tutorial/main_demo3.c
index e1b2689e34..29ae419e12 100644
--- a/sw/airborne/firmwares/tutorial/main_demo3.c
+++ b/sw/airborne/firmwares/tutorial/main_demo3.c
@@ -1,10 +1,9 @@
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "print.h"
static inline void main_init( void );
diff --git a/sw/airborne/firmwares/tutorial/main_demo4.c b/sw/airborne/firmwares/tutorial/main_demo4.c
index 1eb1e97e85..83352b5faf 100644
--- a/sw/airborne/firmwares/tutorial/main_demo4.c
+++ b/sw/airborne/firmwares/tutorial/main_demo4.c
@@ -1,9 +1,8 @@
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
@@ -21,11 +20,11 @@ int main( void ) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
uart0_init_tx();
- int_enable();
+ mcu_int_enable();
}
static inline void main_periodic_task( void ) {
diff --git a/sw/airborne/firmwares/tutorial/main_demo5.c b/sw/airborne/firmwares/tutorial/main_demo5.c
index 138fe63b0d..5cb2b2c430 100644
--- a/sw/airborne/firmwares/tutorial/main_demo5.c
+++ b/sw/airborne/firmwares/tutorial/main_demo5.c
@@ -1,9 +1,8 @@
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
@@ -25,11 +24,11 @@ int main( void ) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
uart0_init_tx();
- int_enable();
+ mcu_int_enable();
}
static inline void main_periodic_task( void ) {
diff --git a/sw/airborne/gps.h b/sw/airborne/gps.h
index 06ffadced9..b6c28317b8 100644
--- a/sw/airborne/gps.h
+++ b/sw/airborne/gps.h
@@ -106,7 +106,7 @@ struct svinfo {
extern struct svinfo gps_svinfos[GPS_NB_CHANNELS];
#ifndef SITL
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define __GpsLink(dev, _x) dev##_x
#define _GpsLink(dev, _x) __GpsLink(dev, _x)
@@ -128,7 +128,7 @@ extern struct svinfo gps_svinfos[GPS_NB_CHANNELS];
#define GpsToggleLed() {}
#endif
-#if defined(GPS) || defined(USE_GPS_XSENS) || defined(SITL)
+#if defined(USE_GPS) || defined(USE_GPS_XSENS) || defined(SITL)
# define GpsTimeoutError (cpu_time_sec - last_gps_msg_t > FAILSAFE_DELAY_WITHOUT_GPS)
#else
# define GpsTimeoutError 1
diff --git a/sw/airborne/gps_nmea.c b/sw/airborne/gps_nmea.c
index a110425dcf..6d843b92b6 100644
--- a/sw/airborne/gps_nmea.c
+++ b/sw/airborne/gps_nmea.c
@@ -43,9 +43,8 @@
#include "generated/flight_plan.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "gps.h"
-//include "gps_ubx.h"
#include "subsystems/nav.h"
#include "latlong.h"
@@ -98,8 +97,6 @@ void ubxsend_cfg_rst(uint16_t bbr , uint8_t reset_mode) {
#ifdef GPS_CONFIGURE
/* GPS dynamic configuration */
-#include "uart.h"
-
void gps_configure_uart ( void ) {
//UbxSend_CFG_PRT(0x01, 0x0, 0x0, 0x000008D0, GPS_BAUD, UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
//while (GpsUartRunning) ; /* FIXME */
diff --git a/sw/airborne/gps_ubx.c b/sw/airborne/gps_ubx.c
index 15777dece9..581a3cb4ce 100644
--- a/sw/airborne/gps_ubx.c
+++ b/sw/airborne/gps_ubx.c
@@ -35,10 +35,10 @@
#include
//for baudrate
#include "fms_serial_port.h"
-#endif
+#endif /* FMS_PERIODIC_FREQ */
#include "generated/flight_plan.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "gps.h"
#include "gps_ubx.h"
#include "subsystems/nav.h"
@@ -152,7 +152,6 @@ void gps_init( void ) {
#ifdef GPS_CONFIGURE
/* GPS dynamic configuration */
-#include "uart.h"
#ifndef GPS_PORT_ID
#define GPS_PORT_ID GPS_PORT_UART1
diff --git a/sw/airborne/gps_xsens.c b/sw/airborne/gps_xsens.c
index 3aae822ad6..077d2353af 100644
--- a/sw/airborne/gps_xsens.c
+++ b/sw/airborne/gps_xsens.c
@@ -33,7 +33,7 @@
#include "sys_time.h"
#include "generated/airframe.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/gyro.c b/sw/airborne/gyro.c
index 4982ef69cc..b8f6bfa77c 100644
--- a/sw/airborne/gyro.c
+++ b/sw/airborne/gyro.c
@@ -30,7 +30,7 @@
#include BOARD_CONFIG
#include "gyro.h"
#include "std.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include "generated/airframe.h"
#include "estimator.h"
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/link_mcu.c b/sw/airborne/link_mcu.c
index 1bb27affce..f7cbcc9322 100644
--- a/sw/airborne/link_mcu.c
+++ b/sw/airborne/link_mcu.c
@@ -23,7 +23,7 @@
*/
#include "link_mcu.h"
-#include "spi.h"
+#include "mcu_periph/spi.h"
struct link_mcu_msg link_mcu_from_ap_msg;
struct link_mcu_msg link_mcu_from_fbw_msg;
diff --git a/sw/airborne/lisa/lisa_stm_gps_passthrough_main.c b/sw/airborne/lisa/lisa_stm_gps_passthrough_main.c
index a8fc59c643..5a115a0c74 100644
--- a/sw/airborne/lisa/lisa_stm_gps_passthrough_main.c
+++ b/sw/airborne/lisa/lisa_stm_gps_passthrough_main.c
@@ -27,7 +27,7 @@
#include "lisa/lisa_overo_link.h"
#include "lisa/lisa_spistream.h"
#include "generated/airframe.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
static inline void main_init(void);
static inline void main_periodic(void);
diff --git a/sw/airborne/lisa/lisa_stm_passthrough_main.c b/sw/airborne/lisa/lisa_stm_passthrough_main.c
index bc468456df..2a79c50762 100644
--- a/sw/airborne/lisa/lisa_stm_passthrough_main.c
+++ b/sw/airborne/lisa/lisa_stm_passthrough_main.c
@@ -22,7 +22,7 @@
*
*/
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "downlink.h"
#include "booz/booz2_commands.h"
@@ -45,9 +45,9 @@
#include "csc_msg_def.h"
#include "csc_protocol.h"
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
static inline void main_init(void);
static inline void main_periodic(void);
@@ -103,7 +103,7 @@ int main(void) {
static inline void main_init(void) {
- hw_init();
+ mcu_init();
sys_time_init();
imu_init();
baro_init();
diff --git a/sw/airborne/lisa/test/hs_gyro.c b/sw/airborne/lisa/test/hs_gyro.c
index c95e033358..e82e1dd4be 100644
--- a/sw/airborne/lisa/test/hs_gyro.c
+++ b/sw/airborne/lisa/test/hs_gyro.c
@@ -24,16 +24,15 @@
#include
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "subsystems/imu.h"
-#include "interrupt_hw.h"
#ifndef MEASURED_SENSOR
#define MEASURED_SENSOR gyro_unscaled.p
@@ -60,11 +59,11 @@ int main( void ) {
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
imu_init();
- int_enable();
+ mcu_int_enable();
}
static inline void main_periodic_task( void ) {
diff --git a/sw/airborne/lisa/test/lisa_tunnel.c b/sw/airborne/lisa/test/lisa_tunnel.c
index e35a86630d..1a7bec287a 100644
--- a/sw/airborne/lisa/test/lisa_tunnel.c
+++ b/sw/airborne/lisa/test/lisa_tunnel.c
@@ -24,10 +24,10 @@
#include
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
+#include "mcu_periph/uart.h"
#include "sys_time.h"
#include "led.h"
-#include "uart.h"
static inline void main_init( void );
static inline void main_periodic_task( void );
diff --git a/sw/airborne/lisa/test/test_board.c b/sw/airborne/lisa/test/test_board.c
index efb4088ff1..292fb22bca 100644
--- a/sw/airborne/lisa/test/test_board.c
+++ b/sw/airborne/lisa/test/test_board.c
@@ -29,11 +29,11 @@
#include "test_board.h"
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
+#include "mcu_periph/uart.h"
#include "sys_time.h"
#include "downlink.h"
#include "led.h"
-#include "uart.h"
#include "datalink.h"
#include "generated/settings.h"
diff --git a/sw/airborne/lisa/test_adc.c b/sw/airborne/lisa/test_adc.c
index 3f8e00e99a..7132bc90e3 100644
--- a/sw/airborne/lisa/test_adc.c
+++ b/sw/airborne/lisa/test_adc.c
@@ -26,11 +26,10 @@
#include
#include BOARD_CONFIG
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "adc.h"
-#include "adc_hw.h"
+#include "mcu_periph/adc.h"
#include "downlink.h"
int main_periodic(void);
@@ -46,7 +45,7 @@ static struct adc_buf adc3_buf;
extern uint8_t adc_new_data_trigger;
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
adc_init();
adc_buf_channel(0, &adc0_buf, 8);
diff --git a/sw/airborne/lisa/test_servos.c b/sw/airborne/lisa/test_servos.c
index d095c00319..4bf9235b67 100644
--- a/sw/airborne/lisa/test_servos.c
+++ b/sw/airborne/lisa/test_servos.c
@@ -50,6 +50,8 @@ static inline void main_periodic( void ) {
static float foo = 0.;
foo += 0.0025;
int32_t bar = 1500 + 500. * sin(foo);
+ // int32_t bar = 1450;
+ // int32_t bar = 1950;
actuators_pwm_values[0] = bar;
actuators_pwm_values[1] = bar;
actuators_pwm_values[2] = bar;
diff --git a/sw/airborne/mcu.c b/sw/airborne/mcu.c
new file mode 100644
index 0000000000..6929d50d9e
--- /dev/null
+++ b/sw/airborne/mcu.c
@@ -0,0 +1,88 @@
+/*
+ * Paparazzi microcontroller initialisation function
+ *
+ * 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 "mcu.h"
+
+#ifdef PERIPHERALS_AUTO_INIT
+#ifdef USE_LED
+#include "led.h"
+#endif
+#if defined RADIO_CONTROL
+#if defined RADIO_CONTROL_LINK || defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT
+#include "subsystems/radio_control.h"
+#endif
+#endif
+#if defined USE_UART0 || defined USE_UART1 || defined USE_UART2 || defined USE_UART3 || defined USE_UART4 || defined USE_UART5
+#include "mcu_periph/uart.h"
+#endif
+#if defined USE_I2C1 || defined USE_I2C2
+#include "mcu_periph/i2c.h"
+#endif
+#endif /* PERIPHERALS_AUTO_INIT */
+
+void mcu_init(void) {
+
+ mcu_arch_init();
+
+#ifdef PERIPHERALS_AUTO_INIT
+#ifdef USE_LED
+ led_init();
+#endif
+ /* for now this means using spektrum */
+#if defined RADIO_CONTROL & defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT & defined RADIO_CONTROL_BIND_IMPL_FUNC
+ RADIO_CONTROL_BIND_IMPL_FUNC();
+#endif
+#ifdef USE_UART0
+ uart0_init();
+#endif
+#ifdef USE_UART1
+ uart1_init();
+#endif
+#ifdef USE_UART2
+ uart2_init();
+#endif
+#ifdef USE_UART3
+ uart3_init();
+#endif
+#ifdef USE_UART4
+ uart4_init();
+#endif
+#ifdef USE_UART5
+ uart5_init();
+#endif
+#ifdef USE_I2C0
+ i2c0_init();
+#endif
+#ifdef USE_I2C1
+ i2c1_init();
+#endif
+#ifdef USE_I2C2
+ i2c2_init();
+#endif
+#ifdef USE_USB_SERIAL
+ VCOM_init();
+#endif
+#endif /* PERIPHERALS_AUTO_INIT */
+
+}
diff --git a/sw/airborne/mcu.h b/sw/airborne/mcu.h
new file mode 100644
index 0000000000..0372433374
--- /dev/null
+++ b/sw/airborne/mcu.h
@@ -0,0 +1,45 @@
+/*
+ * Paparazzi microcontroller functions
+ *
+ * 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 mcu.h
+ * \brief arch independant mcu ( Micro Controller Unit ) utilities
+ */
+
+#ifndef MCU_H
+#define MCU_H
+
+
+#include
+
+/*
+ * Microcontroller initialisation
+ * This function is responisble for setting up the microcontroller
+ * after Reset.
+ */
+extern void mcu_init(void);
+
+
+#endif /* MCU_H */
+
+
diff --git a/sw/airborne/adc.h b/sw/airborne/mcu_periph/adc.h
similarity index 96%
rename from sw/airborne/adc.h
rename to sw/airborne/mcu_periph/adc.h
index 803b9c5100..bb2f9362c2 100644
--- a/sw/airborne/adc.h
+++ b/sw/airborne/mcu_periph/adc.h
@@ -35,7 +35,7 @@
#define _ADC_H_
#include
-#include "adc_hw.h"
+#include "mcu_periph/adc_arch.h"
/* Allow driver implementation to define
* number of available ADCs implicitly
@@ -58,7 +58,7 @@
See @ref adc_buf_channel.
*/
struct adc_buf {
- uint16_t sum; /* Sum of samples in buffer (avg = sum / av_nb_sample) */
+ uint32_t sum; /* Sum of samples in buffer (avg = sum / av_nb_sample) */
uint16_t values[MAX_AV_NB_SAMPLE]; /* Buffer for sample values from ADC */
uint8_t head; /* Position index of write head in buffer */
uint8_t av_nb_sample; /* Number of samples to use in buffer (used for avg) */
diff --git a/sw/airborne/can.c b/sw/airborne/mcu_periph/can.c
similarity index 95%
rename from sw/airborne/can.c
rename to sw/airborne/mcu_periph/can.c
index a40c2e54f9..2087eceb77 100644
--- a/sw/airborne/can.c
+++ b/sw/airborne/mcu_periph/can.c
@@ -24,8 +24,8 @@
#include
-#include "can.h"
-#include "can_hw.h"
+#include "mcu_periph/can.h"
+#include "mcu_periph/can_arch.h"
can_rx_callback_t can_rx_callback;
diff --git a/sw/airborne/can.h b/sw/airborne/mcu_periph/can.h
similarity index 100%
rename from sw/airborne/can.h
rename to sw/airborne/mcu_periph/can.h
diff --git a/sw/airborne/i2c.c b/sw/airborne/mcu_periph/i2c.c
similarity index 94%
rename from sw/airborne/i2c.c
rename to sw/airborne/mcu_periph/i2c.c
index 9036dc8004..0249105d36 100644
--- a/sw/airborne/i2c.c
+++ b/sw/airborne/mcu_periph/i2c.c
@@ -1,4 +1,4 @@
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#ifdef USE_I2C0
diff --git a/sw/airborne/i2c.h b/sw/airborne/mcu_periph/i2c.h
similarity index 97%
rename from sw/airborne/i2c.h
rename to sw/airborne/mcu_periph/i2c.h
index 52150b097e..6c6b400682 100644
--- a/sw/airborne/i2c.h
+++ b/sw/airborne/mcu_periph/i2c.h
@@ -1,9 +1,9 @@
-#ifndef I2C_H
-#define I2C_H
+#ifndef MCU_PERIPH_I2C_H
+#define MCU_PERIPH_I2C_H
#include "std.h"
-#include "i2c_hw.h"
+#include "mcu_periph/i2c_arch.h"
enum I2CTransactionType {
I2CTransTx,
diff --git a/sw/airborne/spi.c b/sw/airborne/mcu_periph/spi.c
similarity index 97%
rename from sw/airborne/spi.c
rename to sw/airborne/mcu_periph/spi.c
index 5ca6193333..2451ed7e79 100644
--- a/sw/airborne/spi.c
+++ b/sw/airborne/mcu_periph/spi.c
@@ -23,7 +23,7 @@
*/
#include "std.h"
-#include "spi.h"
+#include "mcu_periph/spi.h"
uint8_t* spi_buffer_input;
uint8_t* spi_buffer_output;
diff --git a/sw/airborne/spi.h b/sw/airborne/mcu_periph/spi.h
similarity index 96%
rename from sw/airborne/spi.h
rename to sw/airborne/mcu_periph/spi.h
index dd6b0fe8f9..9cdd614a4b 100644
--- a/sw/airborne/spi.h
+++ b/sw/airborne/mcu_periph/spi.h
@@ -22,7 +22,7 @@
*
*/
-/** \file spi.h
+/** \file mcu_periph/spi.h
* \brief arch independant SPI (Serial Peripheral Interface) API */
@@ -32,7 +32,7 @@
#ifdef USE_SPI
#include "std.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi_arch.h"
extern uint8_t* spi_buffer_input;
extern uint8_t* spi_buffer_output;
diff --git a/sw/airborne/uart.h b/sw/airborne/mcu_periph/uart.h
similarity index 94%
rename from sw/airborne/uart.h
rename to sw/airborne/mcu_periph/uart.h
index 03e043ae5f..32bc3588d2 100644
--- a/sw/airborne/uart.h
+++ b/sw/airborne/mcu_periph/uart.h
@@ -1,7 +1,7 @@
/*
* Paparazzi $Id$
*
- * Copyright (C) 2006 Pascal Brisset, Antoine Drouin
+ * Copyright (C) 2010 The Paparazzi Team
*
* This file is part of paparazzi.
*
@@ -22,15 +22,15 @@
*
*/
-/** \file uart.h
+/** \file mcu_periph/uart.h
* \brief arch independant UART (Universal Asynchronous Receiver/Transmitter) API
*
*/
-#ifndef UART_H
-#define UART_H
+#ifndef MCU_PERIPH_UART_H
+#define MCU_PERIPH_UART_H
-#include "uart_hw.h"
+#include "mcu_periph/uart_arch.h"
#include "std.h"
@@ -121,4 +121,4 @@ extern bool_t uart3_check_free_space( uint8_t len);
#endif /* USE_UART3 */
-#endif /* UART_H */
+#endif /* MCU_PERIPH_UART_H */
diff --git a/sw/airborne/modules/MPPT/MPPT.c b/sw/airborne/modules/MPPT/MPPT.c
index 389f997e9f..2df9df684f 100644
--- a/sw/airborne/modules/MPPT/MPPT.c
+++ b/sw/airborne/modules/MPPT/MPPT.c
@@ -26,7 +26,7 @@
#include
#include "MPPT.h"
#include "firmwares/fixedwing/main_fbw.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#define MPPT_SLAVE_ADDR 0x40
@@ -53,7 +53,7 @@ struct i2c_transaction mppt_trans;
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/adcs/adc_generic.c b/sw/airborne/modules/adcs/adc_generic.c
index d7e8f26f52..95e747a556 100644
--- a/sw/airborne/modules/adcs/adc_generic.c
+++ b/sw/airborne/modules/adcs/adc_generic.c
@@ -1,6 +1,6 @@
#include "adc_generic.h"
-#include "adc.h"
-#include "uart.h"
+#include "mcu_periph/adc.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include BOARD_CONFIG
diff --git a/sw/airborne/modules/adcs/max11040.c b/sw/airborne/modules/adcs/max11040.c
index 6ef76fd7e2..0cafe4993e 100644
--- a/sw/airborne/modules/adcs/max11040.c
+++ b/sw/airborne/modules/adcs/max11040.c
@@ -28,7 +28,7 @@
*/
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "max11040.h"
diff --git a/sw/airborne/modules/cam_control/cam_track.h b/sw/airborne/modules/cam_control/cam_track.h
index 873e0324bf..0cfc6e6644 100644
--- a/sw/airborne/modules/cam_control/cam_track.h
+++ b/sw/airborne/modules/cam_control/cam_track.h
@@ -45,7 +45,7 @@ extern volatile uint8_t cam_msg_received;
extern void parse_cam_msg( void );
extern void parse_cam_buffer( uint8_t );
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define __CamLink(dev, _x) dev##_x
#define _CamLink(dev, _x) __CamLink(dev, _x)
diff --git a/sw/airborne/modules/core/extra_pprz_dl.c b/sw/airborne/modules/core/extra_pprz_dl.c
index 231287f7d3..3e36b305e1 100644
--- a/sw/airborne/modules/core/extra_pprz_dl.c
+++ b/sw/airborne/modules/core/extra_pprz_dl.c
@@ -25,7 +25,7 @@
#include
#include "extra_pprz_dl.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
volatile bool_t extra_pprz_msg_received = FALSE;
uint8_t extra_pprz_ovrn, extra_pprz_error;
diff --git a/sw/airborne/modules/core/sys_mon.c b/sw/airborne/modules/core/sys_mon.c
index 6999c6f6a1..35517029d9 100644
--- a/sw/airborne/modules/core/sys_mon.c
+++ b/sw/airborne/modules/core/sys_mon.c
@@ -57,7 +57,7 @@ void init_sysmon(void) {
sum_n_event = 0;
}
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
diff --git a/sw/airborne/modules/digital_cam/atmega_i2c_cam_ctrl.c b/sw/airborne/modules/digital_cam/atmega_i2c_cam_ctrl.c
index 645cbe1294..c1c2e3a184 100644
--- a/sw/airborne/modules/digital_cam/atmega_i2c_cam_ctrl.c
+++ b/sw/airborne/modules/digital_cam/atmega_i2c_cam_ctrl.c
@@ -30,13 +30,13 @@
#include "atmega_i2c_cam_ctrl.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "estimator.h"
diff --git a/sw/airborne/modules/digital_cam/dc.c b/sw/airborne/modules/digital_cam/dc.c
index 29543af74a..99543a6f56 100644
--- a/sw/airborne/modules/digital_cam/dc.c
+++ b/sw/airborne/modules/digital_cam/dc.c
@@ -38,7 +38,7 @@ uint16_t dc_photo_nr = 0;
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "estimator.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
index c682e4ae37..12c3eeb5e4 100644
--- a/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c
+++ b/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c
@@ -33,7 +33,7 @@
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "estimator.h"
diff --git a/sw/airborne/modules/display/lcd_dogm.h b/sw/airborne/modules/display/lcd_dogm.h
index 8dfa74d1fb..17f68f753d 100644
--- a/sw/airborne/modules/display/lcd_dogm.h
+++ b/sw/airborne/modules/display/lcd_dogm.h
@@ -3,7 +3,7 @@
#include
#include "std.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi.h"
#include "led.h"
/* EA DOGM163, 3 line LCD at 3.3V */
diff --git a/sw/airborne/modules/enose/enose.c b/sw/airborne/modules/enose/enose.c
index c3e816bb92..7d8b333b28 100644
--- a/sw/airborne/modules/enose/enose.c
+++ b/sw/airborne/modules/enose/enose.c
@@ -1,9 +1,9 @@
#include
-#include "enose/enose.h"
+#include "modules/enose/enose.h"
-#include "i2c.h"
-#include "adc.h"
+#include "mcu_periph/i2c.h"
+#include "mcu_periph/adc.h"
#include BOARD_CONFIG
@@ -47,7 +47,7 @@ void enose_set_heat(uint8_t no_sensor, uint8_t value) {
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/gps_i2c/gps_i2c.c b/sw/airborne/modules/gps_i2c/gps_i2c.c
index 9d4548c26c..6717e3cea0 100644
--- a/sw/airborne/modules/gps_i2c/gps_i2c.c
+++ b/sw/airborne/modules/gps_i2c/gps_i2c.c
@@ -20,8 +20,8 @@
*
*/
-#include "gps_i2c.h"
-#include "i2c.h"
+#include "modules/gps_i2c.h"
+#include "mcu_periph/i2c.h"
#include "gps.h"
uint8_t gps_i2c_rx_buf[GPS_I2C_BUF_SIZE];
diff --git a/sw/airborne/modules/gsm/gsm.c b/sw/airborne/modules/gsm/gsm.c
index 44acfd941a..58814c97bd 100644
--- a/sw/airborne/modules/gsm/gsm.c
+++ b/sw/airborne/modules/gsm/gsm.c
@@ -58,7 +58,7 @@ Receiving:
#include
#include "gsm.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "std.h"
#ifdef USE_USB_SERIAL
#include "usb_serial.h"
@@ -66,7 +66,7 @@ Receiving:
#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "downlink.h"
#include "ap_downlink.h"
#include "gps.h"
diff --git a/sw/airborne/modules/ins/fw_ins_vn100.c b/sw/airborne/modules/ins/fw_ins_vn100.c
index 06002880c2..1b08545606 100644
--- a/sw/airborne/modules/ins/fw_ins_vn100.c
+++ b/sw/airborne/modules/ins/fw_ins_vn100.c
@@ -26,8 +26,8 @@
* \brief driver for the VectorNav VN100 (Fixed-Wing part)
*/
-#include "ins_vn100.h"
-#include "spi.h"
+#include "modules/ins/ins_vn100.h"
+#include "mcu_periph/spi.h"
void ins_init( void ) {
@@ -92,7 +92,7 @@ void ins_periodic_task( void ) {
}
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/ins/ins_arduimu.c b/sw/airborne/modules/ins/ins_arduimu.c
index 68db855b0d..c4e14dd7cd 100644
--- a/sw/airborne/modules/ins/ins_arduimu.c
+++ b/sw/airborne/modules/ins/ins_arduimu.c
@@ -6,9 +6,9 @@ Autoren@ZHAW: schmiemi
#include
-#include "ins_arduimu.h"
+#include "modules/ins/ins_arduimu.h"
#include "firmwares/fixedwing/main_fbw.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
// test
#include "estimator.h"
@@ -30,7 +30,7 @@ int32_t GPS_Data[14];
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/ins/ins_module.h b/sw/airborne/modules/ins/ins_module.h
index 0f2575d241..7c707d011e 100644
--- a/sw/airborne/modules/ins/ins_module.h
+++ b/sw/airborne/modules/ins/ins_module.h
@@ -71,7 +71,7 @@ void parse_ins_msg( void );
void parse_ins_buffer( uint8_t );
#ifndef SITL
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define __InsLink(dev, _x) dev##_x
#define _InsLink(dev, _x) __InsLink(dev, _x)
diff --git a/sw/airborne/modules/ins/ins_vn100.c b/sw/airborne/modules/ins/ins_vn100.c
index ba36debbdd..d0670ca565 100644
--- a/sw/airborne/modules/ins/ins_vn100.c
+++ b/sw/airborne/modules/ins/ins_vn100.c
@@ -176,7 +176,7 @@ void parse_ins_msg( void ) {
}
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/max3100/max3100_hw.c b/sw/airborne/modules/max3100/max3100_hw.c
index 00158e6f1a..af85b690cb 100644
--- a/sw/airborne/modules/max3100/max3100_hw.c
+++ b/sw/airborne/modules/max3100/max3100_hw.c
@@ -27,7 +27,7 @@
#include "max3100_hw.h"
#include "ap_downlink.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
uint8_t volatile max3100_status;
diff --git a/sw/airborne/modules/max3100/max3100_hw.h b/sw/airborne/modules/max3100/max3100_hw.h
index fb3f831334..0847bedf04 100644
--- a/sw/airborne/modules/max3100/max3100_hw.h
+++ b/sw/airborne/modules/max3100/max3100_hw.h
@@ -3,7 +3,7 @@
#include
#include "std.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi_hw.h"
#include "led.h"
/* Pin configuration for max3100 IRQ */
diff --git a/sw/airborne/modules/meteo/dust_gp2y.c b/sw/airborne/modules/meteo/dust_gp2y.c
index ad1be858c2..25d5041a54 100644
--- a/sw/airborne/modules/meteo/dust_gp2y.c
+++ b/sw/airborne/modules/meteo/dust_gp2y.c
@@ -30,10 +30,10 @@
*/
-#include "dust_gp2y.h"
-#include "i2c.h"
+#include "modules/meteo/dust_gp2y.h"
+#include "mcu_periph/i2c.h"
#include "sys_time.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/humid_dpicco.c b/sw/airborne/modules/meteo/humid_dpicco.c
index 99bbb9f97b..6b45e31a7e 100644
--- a/sw/airborne/modules/meteo/humid_dpicco.c
+++ b/sw/airborne/modules/meteo/humid_dpicco.c
@@ -5,11 +5,11 @@
*/
-#include "humid_dpicco.h"
+#include "modules/meteo/humid_dpicco.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/humid_hih.c b/sw/airborne/modules/meteo/humid_hih.c
index d07eb9fba4..b155ccbeb4 100644
--- a/sw/airborne/modules/meteo/humid_hih.c
+++ b/sw/airborne/modules/meteo/humid_hih.c
@@ -29,10 +29,10 @@
*/
#include
-#include "humid_hih.h"
-#include "temp_tmp102.h"
-#include "adc.h"
-#include "uart.h"
+#include "modules/meteo/humid_hih.h"
+#include "modules/meteo/temp_tmp102.h"
+#include "mcu_periph/adc.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/humid_sht.c b/sw/airborne/modules/meteo/humid_sht.c
index 6dd38cd44d..6b9128a40e 100644
--- a/sw/airborne/modules/meteo/humid_sht.c
+++ b/sw/airborne/modules/meteo/humid_sht.c
@@ -8,7 +8,7 @@
#include "std.h"
#include "LPC21xx.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "humid_sht.h"
diff --git a/sw/airborne/modules/meteo/humid_sht_i2c.c b/sw/airborne/modules/meteo/humid_sht_i2c.c
index a1554d64bd..8fdccf61e4 100644
--- a/sw/airborne/modules/meteo/humid_sht_i2c.c
+++ b/sw/airborne/modules/meteo/humid_sht_i2c.c
@@ -28,10 +28,10 @@
*/
-#include "humid_sht_i2c.h"
+#include "modules/meteo/humid_sht_i2c.h"
-#include "i2c.h"
-#include "uart.h"
+#include "mcu_periph/i2c.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/ir_mlx.c b/sw/airborne/modules/meteo/ir_mlx.c
index c1f02a9e3b..105e636f22 100644
--- a/sw/airborne/modules/meteo/ir_mlx.c
+++ b/sw/airborne/modules/meteo/ir_mlx.c
@@ -29,12 +29,12 @@
*/
-#include "ir_mlx.h"
+#include "modules/meteo/ir_mlx.h"
#include "sys_time.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/light_temt.c b/sw/airborne/modules/meteo/light_temt.c
index 0a8d9fd7af..2272844a61 100644
--- a/sw/airborne/modules/meteo/light_temt.c
+++ b/sw/airborne/modules/meteo/light_temt.c
@@ -29,9 +29,9 @@
*/
-#include "light_temt.h"
-#include "adc.h"
-#include "uart.h"
+#include "modules/meteo/light_temt.h"
+#include "mcu_periph/adc.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/temp_lm75.c b/sw/airborne/modules/meteo/temp_lm75.c
index 0690536f4c..eb73662c1f 100644
--- a/sw/airborne/modules/meteo/temp_lm75.c
+++ b/sw/airborne/modules/meteo/temp_lm75.c
@@ -29,11 +29,11 @@
*/
-#include "temp_lm75.h"
+#include "modules/meteo/temp_lm75.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/temp_temod.c b/sw/airborne/modules/meteo/temp_temod.c
index 6d34906f38..3e2ff4fbe3 100644
--- a/sw/airborne/modules/meteo/temp_temod.c
+++ b/sw/airborne/modules/meteo/temp_temod.c
@@ -28,10 +28,10 @@
*/
-#include "temp_temod.h"
-#include "i2c.h"
+#include "modules/meteo/temp_temod.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/temp_tmp102.c b/sw/airborne/modules/meteo/temp_tmp102.c
index b0acba7ec7..4b366b6776 100644
--- a/sw/airborne/modules/meteo/temp_tmp102.c
+++ b/sw/airborne/modules/meteo/temp_tmp102.c
@@ -29,11 +29,11 @@
*/
-#include "temp_tmp102.h"
+#include "modules/meteo/temp_tmp102.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/wind_gfi.c b/sw/airborne/modules/meteo/wind_gfi.c
index 32c8f6b415..27d81ddb1a 100644
--- a/sw/airborne/modules/meteo/wind_gfi.c
+++ b/sw/airborne/modules/meteo/wind_gfi.c
@@ -29,11 +29,11 @@
*/
-#include "wind_gfi.h"
+#include "modules/meteo/wind_gfi.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/meteo/windturbine.c b/sw/airborne/modules/meteo/windturbine.c
index c482cb9cda..5e356d5536 100644
--- a/sw/airborne/modules/meteo/windturbine.c
+++ b/sw/airborne/modules/meteo/windturbine.c
@@ -38,7 +38,7 @@
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
#endif
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/sensors/airspeed_adc.c b/sw/airborne/modules/sensors/airspeed_adc.c
index d554246d24..776a15ae91 100644
--- a/sw/airborne/modules/sensors/airspeed_adc.c
+++ b/sw/airborne/modules/sensors/airspeed_adc.c
@@ -20,8 +20,8 @@
*
*/
-#include "sensors/airspeed_adc.h"
-#include "adc.h"
+#include "modules/sensors/airspeed_adc.h"
+#include "mcu_periph/adc.h"
#include BOARD_CONFIG
#include "generated/airframe.h"
#include "estimator.h"
diff --git a/sw/airborne/modules/sensors/airspeed_ets.c b/sw/airborne/modules/sensors/airspeed_ets.c
index e00164cb96..b338e1a055 100644
--- a/sw/airborne/modules/sensors/airspeed_ets.c
+++ b/sw/airborne/modules/sensors/airspeed_ets.c
@@ -36,8 +36,8 @@
*/
#include "sensors/airspeed_ets.h"
#include "estimator.h"
-#include "i2c.h"
-#include "uart.h"
+#include "mcu_periph/i2c.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include
diff --git a/sw/airborne/modules/sensors/airspeed_ets.h b/sw/airborne/modules/sensors/airspeed_ets.h
index 6ce9db430c..1b27ddd181 100644
--- a/sw/airborne/modules/sensors/airspeed_ets.h
+++ b/sw/airborne/modules/sensors/airspeed_ets.h
@@ -39,7 +39,7 @@
#define AIRSPEED_ETS_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
extern uint16_t airspeed_ets_raw;
extern uint16_t airspeed_ets_offset;
diff --git a/sw/airborne/modules/sensors/alt_srf08.c b/sw/airborne/modules/sensors/alt_srf08.c
index fca3474dda..c23e9925cf 100644
--- a/sw/airborne/modules/sensors/alt_srf08.c
+++ b/sw/airborne/modules/sensors/alt_srf08.c
@@ -27,9 +27,9 @@
*
*/
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "alt_srf08.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
#include "led.h"
diff --git a/sw/airborne/modules/sensors/baro_MS5534A.c b/sw/airborne/modules/sensors/baro_MS5534A.c
index 706ce3800a..d922cff51b 100644
--- a/sw/airborne/modules/sensors/baro_MS5534A.c
+++ b/sw/airborne/modules/sensors/baro_MS5534A.c
@@ -28,9 +28,9 @@
* uses: MOSI, MISO, SCK and 32kHz @ P0.7 with 5V for the -A type
*/
-#include "baro_MS5534A.h"
-#include "spi.h"
-#include "uart.h"
+#include "modules/sensors/baro_MS5534A.h"
+#include "mcu_periph/spi.h"
+#include "mcu_periph/uart.h"
#ifndef BARO_NO_DOWNLINK
#include "ap_downlink.h"
#endif
diff --git a/sw/airborne/modules/sensors/baro_bmp.c b/sw/airborne/modules/sensors/baro_bmp.c
index 34860b1ca0..261991dcac 100644
--- a/sw/airborne/modules/sensors/baro_bmp.c
+++ b/sw/airborne/modules/sensors/baro_bmp.c
@@ -32,9 +32,9 @@
#include "baro_bmp.h"
#include "sys_time.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/sensors/baro_ets.c b/sw/airborne/modules/sensors/baro_ets.c
index d1164a0d19..462956a181 100644
--- a/sw/airborne/modules/sensors/baro_ets.c
+++ b/sw/airborne/modules/sensors/baro_ets.c
@@ -36,7 +36,7 @@
*/
#include "sensors/baro_ets.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "estimator.h"
#include
diff --git a/sw/airborne/modules/sensors/baro_ets.h b/sw/airborne/modules/sensors/baro_ets.h
index 337c4c041c..bfdc568b6d 100644
--- a/sw/airborne/modules/sensors/baro_ets.h
+++ b/sw/airborne/modules/sensors/baro_ets.h
@@ -39,7 +39,7 @@
#define BARO_ETS_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#define BARO_ETS_DT 0.05
diff --git a/sw/airborne/modules/sensors/baro_scp.c b/sw/airborne/modules/sensors/baro_scp.c
index 80808ee28e..edcaa34ae1 100644
--- a/sw/airborne/modules/sensors/baro_scp.c
+++ b/sw/airborne/modules/sensors/baro_scp.c
@@ -1,16 +1,15 @@
#include "std.h"
-#include "init_hw.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
+#include "mcu.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
-#include "spi_hw.h"
+#include "mcu_periph/spi.h"
-#include "baro_scp.h"
+#include "modules/sensors/baro_scp.h"
#ifndef SENSOR_SYNC_SEND
#warning set SENSOR_SYNC_SEND to use baro_scp
diff --git a/sw/airborne/modules/sensors/baro_scp_i2c.c b/sw/airborne/modules/sensors/baro_scp_i2c.c
index f45f89abd0..3fbcccf556 100644
--- a/sw/airborne/modules/sensors/baro_scp_i2c.c
+++ b/sw/airborne/modules/sensors/baro_scp_i2c.c
@@ -8,9 +8,9 @@
#include "baro_scp_i2c.h"
#include "sys_time.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/sensors/infrared_i2c.h b/sw/airborne/modules/sensors/infrared_i2c.h
index 2b91acfb22..0b3422667c 100644
--- a/sw/airborne/modules/sensors/infrared_i2c.h
+++ b/sw/airborne/modules/sensors/infrared_i2c.h
@@ -29,8 +29,8 @@
#include "std.h"
#include "generated/airframe.h"
-#include "infrared.h"
-#include "i2c.h"
+#include "subsystems/sensors/infrared.h"
+#include "mcu_periph/i2c.h"
extern int16_t ir_i2c_ir1;
extern int16_t ir_i2c_ir2;
diff --git a/sw/airborne/modules/sensors/mag_micromag_fw.c b/sw/airborne/modules/sensors/mag_micromag_fw.c
index a1544a698a..663845e00a 100644
--- a/sw/airborne/modules/sensors/mag_micromag_fw.c
+++ b/sw/airborne/modules/sensors/mag_micromag_fw.c
@@ -1,7 +1,7 @@
#include "mag_micromag_fw.h"
#include "sensors/mag_micromag_fw_hw.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/sensors/pressure_board_navarro.h b/sw/airborne/modules/sensors/pressure_board_navarro.h
index 91bb7a909a..2bd4edba89 100644
--- a/sw/airborne/modules/sensors/pressure_board_navarro.h
+++ b/sw/airborne/modules/sensors/pressure_board_navarro.h
@@ -36,7 +36,7 @@
#define PRESSURE_BOARD_NAVARRO_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
extern uint16_t altitude_adc;
extern uint16_t airspeed_adc;
diff --git a/sw/airborne/modules/sensors/trigger_ext.c b/sw/airborne/modules/sensors/trigger_ext.c
index 74205b8e76..635ff50df6 100644
--- a/sw/airborne/modules/sensors/trigger_ext.c
+++ b/sw/airborne/modules/sensors/trigger_ext.c
@@ -34,7 +34,7 @@
#include "modules/sensors/trig_ext_hw.h"
#include "gps.h"
#include "sys_time.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/modules/vehicle_interface/vi_overo_link.c b/sw/airborne/modules/vehicle_interface/vi_overo_link.c
index 7a38cb0b15..da14c6bcdb 100644
--- a/sw/airborne/modules/vehicle_interface/vi_overo_link.c
+++ b/sw/airborne/modules/vehicle_interface/vi_overo_link.c
@@ -26,7 +26,7 @@
#include "lisa/lisa_overo_link.h"
#include "subsystems/imu.h"
#include
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
#include
diff --git a/sw/airborne/3dmg.c b/sw/airborne/obsolete/3dmg.c
similarity index 100%
rename from sw/airborne/3dmg.c
rename to sw/airborne/obsolete/3dmg.c
diff --git a/sw/airborne/3dmg.h b/sw/airborne/obsolete/3dmg.h
similarity index 100%
rename from sw/airborne/3dmg.h
rename to sw/airborne/obsolete/3dmg.h
diff --git a/sw/airborne/peripherals/ami601.h b/sw/airborne/peripherals/ami601.h
index 0036413962..38be9a347a 100644
--- a/sw/airborne/peripherals/ami601.h
+++ b/sw/airborne/peripherals/ami601.h
@@ -2,7 +2,7 @@
#define AMI601_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
extern void ami601_init( void );
diff --git a/sw/airborne/peripherals/hmc5843.h b/sw/airborne/peripherals/hmc5843.h
index a3d75c297d..ed31ebeed3 100644
--- a/sw/airborne/peripherals/hmc5843.h
+++ b/sw/airborne/peripherals/hmc5843.h
@@ -25,7 +25,7 @@
#define HMC5843_H
#include "std.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "peripherals/hmc5843_arch.h"
diff --git a/sw/airborne/pprz_debug.h b/sw/airborne/pprz_debug.h
index 966a004c19..79d764b26f 100644
--- a/sw/airborne/pprz_debug.h
+++ b/sw/airborne/pprz_debug.h
@@ -31,7 +31,7 @@
#ifdef PPRZ_DEBUG
#include "std.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
diff --git a/sw/airborne/pprz_transport.c b/sw/airborne/pprz_transport.c
index 7985e6decd..90b4a93e06 100644
--- a/sw/airborne/pprz_transport.c
+++ b/sw/airborne/pprz_transport.c
@@ -24,7 +24,7 @@
#include
#include "pprz_transport.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
uint8_t ck_a, ck_b;
volatile bool_t pprz_msg_received = FALSE;
diff --git a/sw/airborne/print.h b/sw/airborne/print.h
index 6b1dbc95d9..949e14c258 100644
--- a/sw/airborne/print.h
+++ b/sw/airborne/print.h
@@ -25,7 +25,7 @@
#ifndef PRINT_H
#define PRINT_H
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "usb_serial.h"
#define _PrintString(out_fun, s) { \
diff --git a/sw/airborne/rc_settings.c b/sw/airborne/rc_settings.c
index 35eb8b1a2a..91cdc614e7 100644
--- a/sw/airborne/rc_settings.c
+++ b/sw/airborne/rc_settings.c
@@ -28,8 +28,8 @@
#include "rc_settings.h"
#include "generated/radio.h"
#include "autopilot.h"
-#include "infrared.h"
#include "subsystems/nav.h"
+#include "subsystems/sensors/infrared.h"
#include "estimator.h"
#include "inter_mcu.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
diff --git a/sw/airborne/sd_card/main.c b/sw/airborne/sd_card/main.c
index 5be480f5f7..a77f922b58 100644
--- a/sw/airborne/sd_card/main.c
+++ b/sw/airborne/sd_card/main.c
@@ -1,9 +1,8 @@
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "interrupt_hw.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
@@ -12,7 +11,7 @@
#include "generated/settings.h"
#include "dl_protocol.h"
-#include "spi.h"
+#include "mcu_periph/spi.h"
#include "sd_card.h"
static inline void main_init( void );
diff --git a/sw/airborne/subsystems/imu/imu_aspirin.c b/sw/airborne/subsystems/imu/imu_aspirin.c
index f57aef4dfc..887bd724c8 100644
--- a/sw/airborne/subsystems/imu/imu_aspirin.c
+++ b/sw/airborne/subsystems/imu/imu_aspirin.c
@@ -1,6 +1,6 @@
#include "subsystems/imu.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
struct ImuAspirin imu_aspirin;
diff --git a/sw/airborne/subsystems/imu/imu_aspirin.h b/sw/airborne/subsystems/imu/imu_aspirin.h
index ea13d0a6d8..740fad584c 100644
--- a/sw/airborne/subsystems/imu/imu_aspirin.h
+++ b/sw/airborne/subsystems/imu/imu_aspirin.h
@@ -27,7 +27,7 @@
#include "generated/airframe.h"
#include "subsystems/imu.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "peripherals/itg3200.h"
#include "peripherals/hmc5843.h"
#include "peripherals/adxl345.h"
diff --git a/sw/airborne/subsystems/ins.c b/sw/airborne/subsystems/ins.c
index 779fec6f0c..eec5f17ea1 100644
--- a/sw/airborne/subsystems/ins.c
+++ b/sw/airborne/subsystems/ins.c
@@ -25,7 +25,7 @@
#include "subsystems/ins.h"
#include "subsystems/imu.h"
-#include "firmwares/rotorcraft/baro.h"
+#include "subsystems/sensors/baro.h"
#include "booz_gps.h"
#include "generated/airframe.h"
diff --git a/sw/airborne/subsystems/radio_control/joby.h b/sw/airborne/subsystems/radio_control/joby.h
index b7640e7991..2b57661e9c 100644
--- a/sw/airborne/subsystems/radio_control/joby.h
+++ b/sw/airborne/subsystems/radio_control/joby.h
@@ -26,7 +26,7 @@
#define RADIO_CONTROL_JOBY_H
#include "std.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#define RC_JOBY_MAGIC_START 13999
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/firmwares/rotorcraft/baro.h b/sw/airborne/subsystems/sensors/baro.h
similarity index 73%
rename from sw/airborne/firmwares/rotorcraft/baro.h
rename to sw/airborne/subsystems/sensors/baro.h
index 2523823087..8c5669060f 100644
--- a/sw/airborne/firmwares/rotorcraft/baro.h
+++ b/sw/airborne/subsystems/sensors/baro.h
@@ -23,12 +23,12 @@
/*
*
- * Brief: common baro for a rotorcraft firmware
+ * Brief: common barometric sensor implementation
*
*/
-#ifndef ROTORCRAFT_BARO_H
-#define ROTORCRAFT_BARO_H
+#ifndef SUBSYSTEMS_SENSORS_BARO_H
+#define SUBSYSTEMS_SENSORS_BARO_H
#include
@@ -37,6 +37,7 @@ enum BaroStatus {
BS_RUNNING
};
+/* pressure in which units ? */
struct Baro {
int32_t absolute;
int32_t differential;
@@ -45,20 +46,12 @@ struct Baro {
extern struct Baro baro;
-#if 0
#include BOARD_CONFIG
-#define BOARD_MODEL_BOOZ 0
-#define BOARD_MODEL_LISA_L 1
-#if defined BOARD_MODEL && BOARD_MODEL==BOARD_MODEL_BOOZ
-#include "boards/booz/baro_board.h"
-#elsif defined BOARD_MODEL && BOARD_MODEL==BOARD_MODEL_LISA_L
-#include "boards/lisa_l/baro_board.h"
-#endif
-#else /* 0 */
+#if defined BOARD_HAS_BARO
#include "baro_board.h"
-#endif /* 0 */
+#endif
extern void baro_init(void);
extern void baro_periodic(void);
-#endif /* ROTORCRAFT_BARO_H */
+#endif /* SUBSYSTEMS_SENSORS_BARO_H */
diff --git a/sw/airborne/infrared.c b/sw/airborne/subsystems/sensors/infrared.c
similarity index 83%
rename from sw/airborne/infrared.c
rename to sw/airborne/subsystems/sensors/infrared.c
index 543de22d11..8fca1d04df 100644
--- a/sw/airborne/infrared.c
+++ b/sw/airborne/subsystems/sensors/infrared.c
@@ -1,7 +1,7 @@
/*
- * Paparazzi mcu0 $Id$
+ * $Id$
*
- * Copyright (C) 2003 Pascal Brisset, Antoine Drouin
+ * Copyright (C) 2003-2010 The Paparazzi Team
*
* This file is part of paparazzi.
*
@@ -30,11 +30,8 @@
#include
-#include "infrared.h"
-#include "adc.h"
-#include "gps.h"
-#include "firmwares/fixedwing/autopilot.h"
-#include "estimator.h"
+#include "subsystems/sensors/infrared.h"
+#include "mcu_periph/adc.h"
#include "ap_downlink.h"
#include "sys_time.h"
#include "generated/airframe.h"
@@ -197,35 +194,15 @@ void ir_init(void) {
*/
void ir_update(void) {
#if ! (defined SITL || defined HITL)
- ir_ir1 = (IR_IR1_SIGN)*(buf_ir1.sum/buf_ir1.av_nb_sample - IR_ADC_IR1_NEUTRAL);
- ir_ir2 = (IR_IR2_SIGN)*(buf_ir2.sum/buf_ir2.av_nb_sample - IR_ADC_IR2_NEUTRAL);
+ ir_ir1 = (IR_IR1_SIGN)*((int32_t)(buf_ir1.sum/buf_ir1.av_nb_sample) - IR_ADC_IR1_NEUTRAL);
+ ir_ir2 = (IR_IR2_SIGN)*((int32_t)(buf_ir2.sum/buf_ir2.av_nb_sample) - IR_ADC_IR2_NEUTRAL);
ir_roll = ir_lateral_correction * IR_RollOfIrs(ir_ir1, ir_ir2);
ir_pitch = ir_longitudinal_correction * IR_PitchOfIrs(ir_ir1, ir_ir2);
#ifdef ADC_CHANNEL_IR_TOP
- ir_top = ir_vertical_correction * IR_TopOfIr(buf_ir_top.sum/buf_ir_top.av_nb_sample - IR_ADC_TOP_NEUTRAL);
+ const int16_t ir3 = (int32_t)(buf_ir_top.sum/buf_ir_top.av_nb_sample) - IR_ADC_TOP_NEUTRAL;
+ ir_top = ir_vertical_correction * IR_TopOfIr(ir3);
#endif // IR_TOP
#endif /* !SITL && !HITL */
/** #else ir_roll set by simulator in sim_ir.c */
}
-void estimator_update_state_infrared( void ) {
- estimator_phi = atan2(ir_roll, ir_top) - ir_roll_neutral;
-
- estimator_theta = atan2(ir_pitch, ir_top) - ir_pitch_neutral;
-
- if (estimator_theta < -M_PI_2)
- estimator_theta += M_PI;
- else if (estimator_theta > M_PI_2)
- estimator_theta -= M_PI;
-
- if (estimator_phi >= 0)
- estimator_phi *= ir_correction_right;
- else
- estimator_phi *= ir_correction_left;
-
- if (estimator_theta >= 0)
- estimator_theta *= ir_correction_up;
- else
- estimator_theta *= ir_correction_down;
-
-}
diff --git a/sw/airborne/infrared.h b/sw/airborne/subsystems/sensors/infrared.h
similarity index 92%
rename from sw/airborne/infrared.h
rename to sw/airborne/subsystems/sensors/infrared.h
index 298a70b0cf..1c555b27d0 100644
--- a/sw/airborne/infrared.h
+++ b/sw/airborne/subsystems/sensors/infrared.h
@@ -22,8 +22,8 @@
*
*/
-#ifndef INFRARED_H
-#define INFRARED_H
+#ifndef SUBSYSTEMS_SENSORS_INFRARED_H
+#define SUBSYSTEMS_SENSORS_INFRARED_H
#include "std.h"
#include "generated/airframe.h"
@@ -44,11 +44,10 @@ extern float ir_correction_down;
void ir_init(void);
void ir_update(void);
-void estimator_update_state_infrared( void );
extern float ir_lateral_correction;
extern float ir_longitudinal_correction;
extern float ir_vertical_correction;
-#endif /* INFRARED_H */
+#endif /* SUBSYSTEMS_SENSORS_INFRARED_H */
diff --git a/sw/airborne/test/peripherals/test_ami601.c b/sw/airborne/test/peripherals/test_ami601.c
index ad7798b42d..557e3c529d 100644
--- a/sw/airborne/test/peripherals/test_ami601.c
+++ b/sw/airborne/test/peripherals/test_ami601.c
@@ -24,18 +24,17 @@
#include
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "messages.h"
#include "downlink.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "peripherals/ami601.h"
#include "math/pprz_algebra_int.h"
-#include "interrupt_hw.h"
#include "std.h"
static inline void main_init( void );
@@ -55,13 +54,13 @@ int main( void ) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
LED_ON(4);
ami601_init();
- int_enable();
+ mcu_int_enable();
}
static inline void main_periodic_task( void ) {
diff --git a/sw/airborne/test/test_actuators.c b/sw/airborne/test/test_actuators.c
index f3579af913..ce99e5c72f 100644
--- a/sw/airborne/test/test_actuators.c
+++ b/sw/airborne/test/test_actuators.c
@@ -22,11 +22,11 @@
*/
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
#include "booz/booz2_commands.h"
#include "firmwares/rotorcraft/actuators.h"
@@ -47,7 +47,7 @@ int main(void) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
actuators_init();
}
diff --git a/sw/airborne/test/test_adcs.c b/sw/airborne/test/test_adcs.c
index e302b89bc0..0bfd29a3b3 100644
--- a/sw/airborne/test/test_adcs.c
+++ b/sw/airborne/test/test_adcs.c
@@ -3,14 +3,13 @@
*/
-#include "interrupt_hw.h"
#include "std.h"
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
-#include "adc.h"
+#include "mcu_periph/adc.h"
#include "messages.h"
#include "led.h"
-#include "uart.h"
+#include "mcu_periph/uart.h"
#include "downlink.h"
@@ -20,7 +19,7 @@
static struct adc_buf buf_adc[NB_ADC];
int main (int argc, char** argv) {
- hw_init();
+ mcu_init();
sys_time_init();
led_init();
adc_init();
@@ -49,7 +48,7 @@ int main (int argc, char** argv) {
Uart1Init();
#endif
- int_enable();
+ mcu_int_enable();
while(1) {
if (sys_time_periodic()) {
diff --git a/sw/airborne/test/test_esc_asctecv1_simple.c b/sw/airborne/test/test_esc_asctecv1_simple.c
index 8acc668a5e..33e9957a1c 100644
--- a/sw/airborne/test/test_esc_asctecv1_simple.c
+++ b/sw/airborne/test/test_esc_asctecv1_simple.c
@@ -22,11 +22,11 @@
*/
-#include "init_hw.h"
+#include "mcu.h"
#include "sys_time.h"
#include "led.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
static inline void main_init( void );
static inline void main_periodic_task( void );
@@ -47,7 +47,7 @@ int main(void) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
}
diff --git a/sw/airborne/test/test_esc_mkk_simple.c b/sw/airborne/test/test_esc_mkk_simple.c
index 7ab0424bd1..bc0f778bca 100644
--- a/sw/airborne/test/test_esc_mkk_simple.c
+++ b/sw/airborne/test/test_esc_mkk_simple.c
@@ -22,11 +22,11 @@
*/
-#include "init_hw.h"
+#include "mcuw.h"
#include "sys_time.h"
#include "led.h"
-#include "i2c.h"
+#include "mcu_periph/i2c.h"
static inline void main_init( void );
static inline void main_periodic_task( void );
@@ -47,7 +47,7 @@ int main(void) {
}
static inline void main_init( void ) {
- hw_init();
+ mcu_init();
sys_time_init();
}
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