From cfbbf0d435484888fdbd6d423bfa92a05a6ee17a Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Sat, 26 Dec 2015 23:48:17 +0100 Subject: [PATCH] [pprlink] start using pprzlink for airborne code some stuff are compiling but not working (at least sim) needs a lot of cleaning needs a better way to init transport types --- .gitmodules | 3 + Makefile | 17 +- .../subsystems/fixedwing/autopilot.makefile | 2 +- .../subsystems/shared/telemetry_ivy.makefile | 2 +- .../shared/telemetry_xbee_api.makefile | 2 +- .../arch/lpc21/mcu_periph/spi_slave_hs_arch.h | 2 +- sw/airborne/boards/apogee/imu_apogee.c | 2 +- sw/airborne/boards/baro_board_ms5611_i2c.c | 2 +- sw/airborne/boards/baro_board_ms5611_spi.c | 2 +- sw/airborne/boards/hbmini/imu_hbmini.c | 2 +- sw/airborne/boards/krooz/imu_krooz.c | 2 +- sw/airborne/boards/navgo/imu_navgo.c | 2 +- sw/airborne/boards/umarim/imu_umarim.c | 2 +- sw/airborne/firmwares/fixedwing/autopilot.h | 2 +- .../firmwares/motor_bench/main_motor_bench.c | 2 +- .../firmwares/motor_bench/main_turntable.c | 2 +- sw/airborne/firmwares/rotorcraft/autopilot.h | 2 +- sw/airborne/firmwares/rotorcraft/datalink.c | 4 +- sw/airborne/firmwares/rotorcraft/navigation.c | 2 +- sw/airborne/firmwares/tutorial/main_demo4.c | 2 +- sw/airborne/firmwares/tutorial/main_demo5.c | 2 +- sw/airborne/firmwares/tutorial/main_demo6.c | 2 +- sw/airborne/firmwares/wind_tunnel/main.c | 4 +- sw/airborne/firmwares/wind_tunnel/main_mb.c | 4 +- sw/airborne/mcu_periph/link_device.h | 58 ----- sw/airborne/mcu_periph/uart.c | 1 + sw/airborne/mcu_periph/uart.h | 2 +- sw/airborne/mcu_periph/udp.h | 2 +- sw/airborne/mcu_periph/usb_serial.h | 2 +- sw/airborne/modules/adcs/adc_generic.c | 2 +- sw/airborne/modules/adcs/max11040.c | 2 +- .../modules/benchmark/flight_benchmark.c | 2 +- .../calibration/send_imu_mag_current.c | 2 +- sw/airborne/modules/config/config_mkk_v2.c | 2 +- sw/airborne/modules/core/sys_mon.c | 2 +- sw/airborne/modules/datalink/extra_pprz_dl.h | 2 +- .../modules/datalink/mavlink_decoder.c | 2 +- .../modules/datalink/mavlink_decoder.h | 2 +- sw/airborne/modules/datalink/xtend_rssi.c | 2 +- .../modules/digital_cam/atmega_i2c_cam_ctrl.c | 2 +- sw/airborne/modules/digital_cam/dc.c | 2 +- sw/airborne/modules/digital_cam/hackhd.c | 2 +- .../modules/digital_cam/sim_i2c_cam_ctrl.c | 2 +- sw/airborne/modules/energy/MPPT.c | 2 +- sw/airborne/modules/energy/sim_MPPT.c | 2 +- sw/airborne/modules/enose/enose.c | 2 +- sw/airborne/modules/gps/gps_ubx_ucenter.h | 2 +- .../gumstix_interface/qr_code_spi_link.c | 2 +- sw/airborne/modules/ins/ahrs_chimu_spi.c | 2 +- sw/airborne/modules/ins/ahrs_chimu_uart.c | 2 +- sw/airborne/modules/ins/alt_filter.c | 2 +- sw/airborne/modules/ins/ins_arduimu.c | 2 +- sw/airborne/modules/ins/ins_arduimu_basic.c | 2 +- sw/airborne/modules/ins/ins_module.h | 2 +- sw/airborne/modules/ins/ins_vn100.c | 4 +- sw/airborne/modules/ins/ins_xsens.c | 4 +- sw/airborne/modules/ins/ins_xsens700.c | 4 +- sw/airborne/modules/loggers/flight_recorder.c | 2 +- sw/airborne/modules/loggers/openlog.c | 2 +- .../modules/loggers/sdlogger_spi_direct.c | 2 +- .../modules/loggers/sdlogger_spi_direct.h | 2 +- sw/airborne/modules/meteo/charge_sens.c | 2 +- sw/airborne/modules/meteo/dust_gp2y.c | 2 +- sw/airborne/modules/meteo/geiger_counter.c | 2 +- sw/airborne/modules/meteo/humid_dpicco.c | 2 +- sw/airborne/modules/meteo/humid_hih.c | 2 +- sw/airborne/modules/meteo/humid_htm_b71.c | 2 +- sw/airborne/modules/meteo/humid_pcap01.c | 2 +- sw/airborne/modules/meteo/humid_sht.c | 2 +- sw/airborne/modules/meteo/humid_sht_i2c.c | 2 +- sw/airborne/modules/meteo/ir_mlx.c | 2 +- sw/airborne/modules/meteo/light_solar.c | 2 +- sw/airborne/modules/meteo/light_temt.c | 2 +- sw/airborne/modules/meteo/meteo_stick.c | 2 +- sw/airborne/modules/meteo/mf_ptu.c | 2 +- sw/airborne/modules/meteo/temp_lm75.c | 2 +- sw/airborne/modules/meteo/temp_tcouple_adc.c | 2 +- sw/airborne/modules/meteo/temp_temod.c | 2 +- sw/airborne/modules/meteo/temp_tmp102.c | 2 +- sw/airborne/modules/meteo/wind_gfi.c | 2 +- sw/airborne/modules/meteo/windturbine.c | 2 +- sw/airborne/modules/multi/follow.c | 4 +- sw/airborne/modules/multi/formation.c | 2 +- sw/airborne/modules/multi/potential.c | 2 +- sw/airborne/modules/multi/tcas.c | 2 +- sw/airborne/modules/nav/nav_catapult.c | 2 +- .../modules/nav/nav_survey_poly_rotorcraft.c | 2 +- .../nav/nav_survey_rectangle_rotorcraft.c | 2 +- sw/airborne/modules/optical_flow/px4flow.c | 2 +- sw/airborne/modules/sensors/airspeed_amsys.c | 2 +- sw/airborne/modules/sensors/airspeed_ets.c | 2 +- .../modules/sensors/airspeed_ms45xx_i2c.c | 2 +- sw/airborne/modules/sensors/airspeed_otf.c | 2 +- sw/airborne/modules/sensors/alt_srf08.c | 2 +- sw/airborne/modules/sensors/aoa_adc.c | 2 +- sw/airborne/modules/sensors/aoa_pwm.c | 2 +- sw/airborne/modules/sensors/baro_amsys.c | 2 +- sw/airborne/modules/sensors/baro_bmp.c | 2 +- sw/airborne/modules/sensors/baro_ets.c | 2 +- sw/airborne/modules/sensors/baro_hca.c | 2 +- sw/airborne/modules/sensors/baro_mpl3115.c | 2 +- sw/airborne/modules/sensors/baro_ms5611_i2c.c | 2 +- sw/airborne/modules/sensors/baro_ms5611_spi.c | 2 +- sw/airborne/modules/sensors/baro_scp.c | 2 +- sw/airborne/modules/sensors/baro_scp_i2c.c | 2 +- sw/airborne/modules/sensors/imu_aspirin2.c | 2 +- sw/airborne/modules/sensors/mag_hmc5843.c | 2 +- sw/airborne/modules/sensors/mag_hmc58xx.c | 2 +- sw/airborne/modules/sensors/mag_micromag_fw.c | 2 +- sw/airborne/modules/sensors/temp_adc.c | 2 +- sw/airborne/modules/sensors/trigger_ext.c | 2 +- sw/airborne/modules/sonar/sonar_adc.c | 2 +- .../stereocam/droplet/stereocam_droplet.c | 2 +- .../nav_line_avoid/avoid_navigation.c | 2 +- .../modules/stereocam/stereoprotocol.h | 2 +- sw/airborne/peripherals/cyrf6936.c | 2 +- sw/airborne/pprz_debug.h | 2 +- sw/airborne/subsystems/ahrs/ahrs_float_dcm.c | 2 +- .../chibios-libopencm3/chibios_sdlog.h | 2 +- .../subsystems/datalink/audio_telemetry.h | 75 ------ sw/airborne/subsystems/datalink/bluegiga.h | 4 +- sw/airborne/subsystems/datalink/datalink.h | 6 +- sw/airborne/subsystems/datalink/downlink.c | 22 +- sw/airborne/subsystems/datalink/downlink.h | 56 +++-- .../subsystems/datalink/downlink_transport.h | 63 ----- .../subsystems/datalink/ivy_transport.c | 204 ---------------- .../subsystems/datalink/ivy_transport.h | 53 ---- .../subsystems/datalink/pprz_transport.c | 131 ---------- .../subsystems/datalink/pprz_transport.h | 159 ------------ .../subsystems/datalink/pprzlog_transport.c | 125 ---------- .../subsystems/datalink/pprzlog_transport.h | 48 ---- sw/airborne/subsystems/datalink/superbitrf.h | 4 +- .../subsystems/datalink/telemetry_common.h | 6 +- sw/airborne/subsystems/datalink/transport.h | 102 -------- sw/airborne/subsystems/datalink/uart_print.h | 2 +- sw/airborne/subsystems/datalink/w5100.h | 4 +- sw/airborne/subsystems/datalink/xbee.c | 230 ------------------ sw/airborne/subsystems/datalink/xbee.h | 152 ------------ sw/airborne/subsystems/datalink/xbee24.h | 46 ---- sw/airborne/subsystems/datalink/xbee868.h | 55 ----- sw/airborne/subsystems/gps/gps_mtk.c | 2 +- sw/airborne/subsystems/gps/gps_mtk.h | 2 +- sw/airborne/subsystems/gps/gps_nmea.h | 2 +- sw/airborne/subsystems/gps/gps_sirf.h | 2 +- sw/airborne/subsystems/gps/gps_skytraq.h | 2 +- sw/airborne/subsystems/gps/gps_ubx.h | 2 +- .../subsystems/ins/vf_extended_float.c | 2 +- sw/airborne/subsystems/intermcu/intermcu_ap.c | 2 +- .../subsystems/intermcu/intermcu_fbw.c | 2 +- sw/airborne/test/subsystems/test_ahrs.c | 2 +- sw/airborne/test/subsystems/test_imu.c | 2 +- sw/ext/pprzlink | 1 + sw/tools/generators/gen_modules.ml | 2 +- sw/tools/generators/gen_ubx.ml | 2 +- 154 files changed, 217 insertions(+), 1680 deletions(-) delete mode 100644 sw/airborne/mcu_periph/link_device.h delete mode 100644 sw/airborne/subsystems/datalink/audio_telemetry.h delete mode 100644 sw/airborne/subsystems/datalink/downlink_transport.h delete mode 100644 sw/airborne/subsystems/datalink/ivy_transport.c delete mode 100644 sw/airborne/subsystems/datalink/ivy_transport.h delete mode 100644 sw/airborne/subsystems/datalink/pprz_transport.c delete mode 100644 sw/airborne/subsystems/datalink/pprz_transport.h delete mode 100644 sw/airborne/subsystems/datalink/pprzlog_transport.c delete mode 100644 sw/airborne/subsystems/datalink/pprzlog_transport.h delete mode 100644 sw/airborne/subsystems/datalink/transport.h delete mode 100644 sw/airborne/subsystems/datalink/xbee.c delete mode 100644 sw/airborne/subsystems/datalink/xbee.h delete mode 100644 sw/airborne/subsystems/datalink/xbee24.h delete mode 100644 sw/airborne/subsystems/datalink/xbee868.h create mode 160000 sw/ext/pprzlink diff --git a/.gitmodules b/.gitmodules index 4c2d20aa4d..4a2ea3a539 100644 --- a/.gitmodules +++ b/.gitmodules @@ -19,3 +19,6 @@ [submodule "sw/ext/mavlink"] path = sw/ext/mavlink url = https://github.com/paparazzi/mavlink.git +[submodule "sw/ext/pprzlink"] + path = sw/ext/pprzlink + url = https://github.com/paparazzi/pprzlink.git diff --git a/Makefile b/Makefile index 2a43d6eff5..fb0763b368 100644 --- a/Makefile +++ b/Makefile @@ -58,6 +58,7 @@ endif # LIB=sw/lib STATICINCLUDE =$(PAPARAZZI_HOME)/var/include +MESSAGES_INSTALL =$(PAPARAZZI_HOME)/var CONF=$(PAPARAZZI_SRC)/conf AIRBORNE=sw/airborne SIMULATOR=sw/simulator @@ -68,6 +69,7 @@ GENERATORS=$(PAPARAZZI_SRC)/sw/tools/generators JOYSTICK=sw/ground_segment/joystick EXT=sw/ext TOOLS=sw/tools +PPRZLINK_DIR=sw/ext/pprzlink # # build some stuff in subdirs @@ -103,8 +105,8 @@ INTERMCU_MSG_H=$(STATICINCLUDE)/intermcu_msg.h MAVLINK_DIR=$(STATICINCLUDE)/mavlink/ MAVLINK_PROTOCOL_H=$(MAVLINK_DIR)protocol.h -GEN_HEADERS = $(MESSAGES_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(XSENS_PROTOCOL_H) $(DL_PROTOCOL_H) $(ABI_MESSAGES_H) $(INTERMCU_MSG_H) $(MAVLINK_PROTOCOL_H) - +GEN_HEADERS = $(MESSAGES_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(XSENS_PROTOCOL_H) $(ABI_MESSAGES_H) $(INTERMCU_MSG_H) $(MAVLINK_PROTOCOL_H) +#$(DL_PROTOCOL_H) all: ground_segment ext lpctools @@ -184,16 +186,17 @@ $(PPRZCENTER): libpprz $(LOGALIZER): libpprz +pprzlink: + @echo BUILD PPRZLINK + $(Q)$(MAKE) -C $(PPRZLINK_DIR) generators static_h: $(GEN_HEADERS) -$(MESSAGES_H) : $(MESSAGES_XML) generators +$(MESSAGES_H) : $(MESSAGES_XML) pprzlink $(Q)test -d $(STATICINCLUDE) || mkdir -p $(STATICINCLUDE) + $(Q)test -d $(STATICLIB) || mkdir -p $(STATICLIB) @echo GENERATE $@ - $(eval $@_TMP := $(shell $(MKTEMP))) - $(Q)PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME) $(GENERATORS)/gen_messages.out $< telemetry > $($@_TMP) - $(Q)mv $($@_TMP) $@ - $(Q)chmod a+r $@ + $(Q)MESSAGES_INSTALL=$(MESSAGES_INSTALL) $(MAKE) -C $(PPRZLINK_DIR) pymessages $(MESSAGES2_H) : $(MESSAGES_XML) generators $(Q)test -d $(STATICINCLUDE) || mkdir -p $(STATICINCLUDE) diff --git a/conf/firmwares/subsystems/fixedwing/autopilot.makefile b/conf/firmwares/subsystems/fixedwing/autopilot.makefile index 47f742a092..01afcadb5d 100644 --- a/conf/firmwares/subsystems/fixedwing/autopilot.makefile +++ b/conf/firmwares/subsystems/fixedwing/autopilot.makefile @@ -196,7 +196,7 @@ sim.CFLAGS += -DSITL sim.srcs += $(SRC_ARCH)/sim_ap.c sim.CFLAGS += -DDOWNLINK -DPERIODIC_TELEMETRY -DDOWNLINK_TRANSPORT=ivy_tp -DDOWNLINK_DEVICE=ivy_tp -sim.srcs += subsystems/datalink/downlink.c $(SRC_FIRMWARE)/datalink.c subsystems/datalink/ivy_transport.c subsystems/datalink/telemetry.c $(SRC_FIRMWARE)/ap_downlink.c $(SRC_FIRMWARE)/fbw_downlink.c +sim.srcs += subsystems/datalink/downlink.c $(SRC_FIRMWARE)/datalink.c $(PAPARAZZI_HOME)/var/lib/pprzlink/ivy_transport.c subsystems/datalink/telemetry.c $(SRC_FIRMWARE)/ap_downlink.c $(SRC_FIRMWARE)/fbw_downlink.c sim.srcs += $(SRC_ARCH)/sim_gps.c $(SRC_ARCH)/sim_adc_generic.c diff --git a/conf/firmwares/subsystems/shared/telemetry_ivy.makefile b/conf/firmwares/subsystems/shared/telemetry_ivy.makefile index c8c0dc8600..2b5ba2901c 100644 --- a/conf/firmwares/subsystems/shared/telemetry_ivy.makefile +++ b/conf/firmwares/subsystems/shared/telemetry_ivy.makefile @@ -1,3 +1,3 @@ $(TARGET).CFLAGS += -DDOWNLINK -DPERIODIC_TELEMETRY -DDOWNLINK_TRANSPORT=ivy_tp -DDOWNLINK_DEVICE=ivy_tp -$(TARGET).srcs += subsystems/datalink/ivy_transport.c +$(TARGET).srcs += $(PAPARAZZI_HOME)/var/lib/pprzlink/ivy_transport.c $(TARGET).srcs += subsystems/datalink/downlink.c subsystems/datalink/telemetry.c diff --git a/conf/firmwares/subsystems/shared/telemetry_xbee_api.makefile b/conf/firmwares/subsystems/shared/telemetry_xbee_api.makefile index 01f39a9a22..593aa0f5e7 100644 --- a/conf/firmwares/subsystems/shared/telemetry_xbee_api.makefile +++ b/conf/firmwares/subsystems/shared/telemetry_xbee_api.makefile @@ -14,4 +14,4 @@ $(TARGET).CFLAGS += -D$(XBEE_MODEM_PORT_UPPER)_BAUD=$(MODEM_BAUD) -DXBEE_BAUD=$( $(TARGET).CFLAGS += -DDOWNLINK -DPERIODIC_TELEMETRY -DDOWNLINK_DEVICE=$(XBEE_MODEM_PORT_LOWER) -DXBEE_UART=$(XBEE_MODEM_PORT_LOWER) $(TARGET).CFLAGS += -DDOWNLINK_TRANSPORT=xbee_tp -DDATALINK=XBEE -$(TARGET).srcs += subsystems/datalink/downlink.c subsystems/datalink/xbee.c subsystems/datalink/telemetry.c +$(TARGET).srcs += subsystems/datalink/downlink.c $(PAPARAZZI_HOME)/var/lib/pprzlink/xbee_transport.c subsystems/datalink/telemetry.c diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.h b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.h index f695de20e9..4cbf94d925 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.h +++ b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.h @@ -32,7 +32,7 @@ #define SPI_SLAVE_HS_ARCH_H #include "std.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" struct spi_slave_hs { /** Generic device interface */ diff --git a/sw/airborne/boards/apogee/imu_apogee.c b/sw/airborne/boards/apogee/imu_apogee.c index 12052bdab0..3752226e84 100644 --- a/sw/airborne/boards/apogee/imu_apogee.c +++ b/sw/airborne/boards/apogee/imu_apogee.c @@ -35,7 +35,7 @@ // Downlink #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #ifndef IMU_APOGEE_CHAN_X diff --git a/sw/airborne/boards/baro_board_ms5611_i2c.c b/sw/airborne/boards/baro_board_ms5611_i2c.c index 8e55b850a2..b7d2225483 100644 --- a/sw/airborne/boards/baro_board_ms5611_i2c.c +++ b/sw/airborne/boards/baro_board_ms5611_i2c.c @@ -36,7 +36,7 @@ #include "subsystems/abi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #ifdef BARO_PERIODIC_FREQUENCY diff --git a/sw/airborne/boards/baro_board_ms5611_spi.c b/sw/airborne/boards/baro_board_ms5611_spi.c index 0185d0d600..c0486c8946 100644 --- a/sw/airborne/boards/baro_board_ms5611_spi.c +++ b/sw/airborne/boards/baro_board_ms5611_spi.c @@ -36,7 +36,7 @@ #include "subsystems/abi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #ifdef BARO_PERIODIC_FREQUENCY diff --git a/sw/airborne/boards/hbmini/imu_hbmini.c b/sw/airborne/boards/hbmini/imu_hbmini.c index d3d3b1098c..e2886d29d8 100644 --- a/sw/airborne/boards/hbmini/imu_hbmini.c +++ b/sw/airborne/boards/hbmini/imu_hbmini.c @@ -38,7 +38,7 @@ // Downlink #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index e81400faaf..ff4a49f48e 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -38,7 +38,7 @@ // Downlink #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #if !defined KROOZ_LOWPASS_FILTER && !defined KROOZ_SMPLRT_DIV diff --git a/sw/airborne/boards/navgo/imu_navgo.c b/sw/airborne/boards/navgo/imu_navgo.c index a628daaf9e..c516703b0f 100644 --- a/sw/airborne/boards/navgo/imu_navgo.c +++ b/sw/airborne/boards/navgo/imu_navgo.c @@ -38,7 +38,7 @@ // Downlink #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/boards/umarim/imu_umarim.c b/sw/airborne/boards/umarim/imu_umarim.c index ad9ff9e7ae..5006a02d7b 100644 --- a/sw/airborne/boards/umarim/imu_umarim.c +++ b/sw/airborne/boards/umarim/imu_umarim.c @@ -37,7 +37,7 @@ // Downlink #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/firmwares/fixedwing/autopilot.h b/sw/airborne/firmwares/fixedwing/autopilot.h index 29a7d5a409..bc823b8cd6 100644 --- a/sw/airborne/firmwares/fixedwing/autopilot.h +++ b/sw/airborne/firmwares/fixedwing/autopilot.h @@ -165,7 +165,7 @@ static inline void autopilot_ClearSettings(float clear) } #if DOWNLINK -#include "subsystems/datalink/transport.h" +#include "pprzlink/pprzlink_transport.h" extern void send_autopilot_version(struct transport_tx *trans, struct link_device *dev); #endif diff --git a/sw/airborne/firmwares/motor_bench/main_motor_bench.c b/sw/airborne/firmwares/motor_bench/main_motor_bench.c index cf6369ca86..011407ed5a 100644 --- a/sw/airborne/firmwares/motor_bench/main_motor_bench.c +++ b/sw/airborne/firmwares/motor_bench/main_motor_bench.c @@ -13,7 +13,7 @@ #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "generated/settings.h" diff --git a/sw/airborne/firmwares/motor_bench/main_turntable.c b/sw/airborne/firmwares/motor_bench/main_turntable.c index 28fe92aa33..86d28b29de 100644 --- a/sw/airborne/firmwares/motor_bench/main_turntable.c +++ b/sw/airborne/firmwares/motor_bench/main_turntable.c @@ -6,7 +6,7 @@ #include "mcu_periph/uart.h" #include "mcu_arch.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "armVIC.h" diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.h b/sw/airborne/firmwares/rotorcraft/autopilot.h index f4213f7daf..1f96cd9c26 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot.h @@ -179,7 +179,7 @@ static inline void autopilot_ClearSettings(float clear) } #if DOWNLINK -#include "subsystems/datalink/transport.h" +#include "pprzlink/pprzlink_transport.h" extern void send_autopilot_version(struct transport_tx *trans, struct link_device *dev); #endif diff --git a/sw/airborne/firmwares/rotorcraft/datalink.c b/sw/airborne/firmwares/rotorcraft/datalink.c index a9e505b685..b726d08bcc 100644 --- a/sw/airborne/firmwares/rotorcraft/datalink.c +++ b/sw/airborne/firmwares/rotorcraft/datalink.c @@ -34,8 +34,8 @@ #include "generated/settings.h" #include "subsystems/datalink/downlink.h" -#include "messages.h" -#include "dl_protocol.h" +#include "pprzlink/messages.h" +#include "pprzlink/dl_protocol.h" #include "mcu_periph/uart.h" #if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c index 57b22a6fb1..eeeb26f462 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.c +++ b/sw/airborne/firmwares/rotorcraft/navigation.c @@ -45,7 +45,7 @@ #include "math/pprz_algebra_int.h" #include "subsystems/datalink/downlink.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "mcu_periph/uart.h" struct EnuCoor_i navigation_target; diff --git a/sw/airborne/firmwares/tutorial/main_demo4.c b/sw/airborne/firmwares/tutorial/main_demo4.c index cc8af43436..f573fe8893 100644 --- a/sw/airborne/firmwares/tutorial/main_demo4.c +++ b/sw/airborne/firmwares/tutorial/main_demo4.c @@ -4,7 +4,7 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" static inline void main_init(void); diff --git a/sw/airborne/firmwares/tutorial/main_demo5.c b/sw/airborne/firmwares/tutorial/main_demo5.c index cb020add05..ea56b03cab 100644 --- a/sw/airborne/firmwares/tutorial/main_demo5.c +++ b/sw/airborne/firmwares/tutorial/main_demo5.c @@ -4,7 +4,7 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" static inline void main_init(void); diff --git a/sw/airborne/firmwares/tutorial/main_demo6.c b/sw/airborne/firmwares/tutorial/main_demo6.c index c1739caec9..c9ee9696ff 100644 --- a/sw/airborne/firmwares/tutorial/main_demo6.c +++ b/sw/airborne/firmwares/tutorial/main_demo6.c @@ -4,7 +4,7 @@ #include "led.h" #include "mcu_periph/usb_serial.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" static inline void main_init(void); diff --git a/sw/airborne/firmwares/wind_tunnel/main.c b/sw/airborne/firmwares/wind_tunnel/main.c index 26a866c552..ee1d7606ea 100644 --- a/sw/airborne/firmwares/wind_tunnel/main.c +++ b/sw/airborne/firmwares/wind_tunnel/main.c @@ -4,12 +4,12 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "subsystems/datalink/datalink.h" #include "generated/settings.h" -#include "dl_protocol.h" +#include "pprzlink/dl_protocol.h" #include "wt_servo.h" diff --git a/sw/airborne/firmwares/wind_tunnel/main_mb.c b/sw/airborne/firmwares/wind_tunnel/main_mb.c index e7efcc4f53..48cd7172a2 100644 --- a/sw/airborne/firmwares/wind_tunnel/main_mb.c +++ b/sw/airborne/firmwares/wind_tunnel/main_mb.c @@ -4,12 +4,12 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "subsystems/datalink/datalink.h" #include "generated/settings.h" -#include "dl_protocol.h" +#include "pprzlink/dl_protocol.h" #include "i2c.h" #include "mb_twi_controller_mkk.h" diff --git a/sw/airborne/mcu_periph/link_device.h b/sw/airborne/mcu_periph/link_device.h deleted file mode 100644 index 68bd498daa..0000000000 --- a/sw/airborne/mcu_periph/link_device.h +++ /dev/null @@ -1,58 +0,0 @@ -/* - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** \file mcu_periph/link_device.h - * generic device header - */ - -#ifndef LINK_DEVICE_H -#define LINK_DEVICE_H - -#include - -/** Function pointers definition - * - * they are used to cast the real functions with the correct type - * to store in the device structure - */ -typedef int (*check_free_space_t)(void *, uint8_t); -typedef void (*put_byte_t)(void *, uint8_t); -typedef void (*send_message_t)(void *); -typedef int (*char_available_t)(void *); -typedef uint8_t (*get_byte_t)(void *); - -/** Device structure - */ -struct link_device { - check_free_space_t check_free_space; ///< check if transmit buffer is not full - put_byte_t put_byte; ///< put one byte - send_message_t send_message; ///< send completed buffer - char_available_t char_available; ///< check if a new character is available - get_byte_t get_byte; ///< get a new char - void *periph; ///< pointer to parent implementation - - uint16_t nb_msgs; ///< The number of messages send - uint8_t nb_ovrn; ///< The number of overruns - uint32_t nb_bytes; ///< The number of bytes send -}; - -#endif // LINK_DEVICE_H - diff --git a/sw/airborne/mcu_periph/uart.c b/sw/airborne/mcu_periph/uart.c index c2125bd445..bbb98f4246 100644 --- a/sw/airborne/mcu_periph/uart.c +++ b/sw/airborne/mcu_periph/uart.c @@ -246,6 +246,7 @@ void uart_periph_init(struct uart_periph *p) p->device.send_message = (send_message_t)null_function; p->device.char_available = (char_available_t)uart_char_available; p->device.get_byte = (get_byte_t)uart_getch; + p->device.set_baudrate = (set_baudrate_t)uart_periph_set_baudrate; #if PERIODIC_TELEMETRY // the first to register do it for the others diff --git a/sw/airborne/mcu_periph/uart.h b/sw/airborne/mcu_periph/uart.h index c7b1c5c897..22be5f5800 100644 --- a/sw/airborne/mcu_periph/uart.h +++ b/sw/airborne/mcu_periph/uart.h @@ -29,7 +29,7 @@ #define MCU_PERIPH_UART_H #include "mcu_periph/uart_arch.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #include "std.h" #ifndef UART_RX_BUFFER_SIZE diff --git a/sw/airborne/mcu_periph/udp.h b/sw/airborne/mcu_periph/udp.h index 775cab5d5f..1d33f03325 100644 --- a/sw/airborne/mcu_periph/udp.h +++ b/sw/airborne/mcu_periph/udp.h @@ -30,7 +30,7 @@ #include "std.h" #include "mcu_periph/udp_arch.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #define UDP_RX_BUFFER_SIZE 256 #define UDP_TX_BUFFER_SIZE 256 diff --git a/sw/airborne/mcu_periph/usb_serial.h b/sw/airborne/mcu_periph/usb_serial.h index 3d7ab5eb27..85126dc0f1 100644 --- a/sw/airborne/mcu_periph/usb_serial.h +++ b/sw/airborne/mcu_periph/usb_serial.h @@ -30,7 +30,7 @@ #include #include "std.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" struct usb_serial_periph { /** Generic device interface */ diff --git a/sw/airborne/modules/adcs/adc_generic.c b/sw/airborne/modules/adcs/adc_generic.c index 318de1995e..5546f10eca 100644 --- a/sw/airborne/modules/adcs/adc_generic.c +++ b/sw/airborne/modules/adcs/adc_generic.c @@ -1,7 +1,7 @@ #include "adc_generic.h" #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include BOARD_CONFIG diff --git a/sw/airborne/modules/adcs/max11040.c b/sw/airborne/modules/adcs/max11040.c index b714c359cc..a8c509f598 100644 --- a/sw/airborne/modules/adcs/max11040.c +++ b/sw/airborne/modules/adcs/max11040.c @@ -27,7 +27,7 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "max11040.h" #include "adcs/max11040_hw.h" diff --git a/sw/airborne/modules/benchmark/flight_benchmark.c b/sw/airborne/modules/benchmark/flight_benchmark.c index 7529c8153c..05b931d805 100644 --- a/sw/airborne/modules/benchmark/flight_benchmark.c +++ b/sw/airborne/modules/benchmark/flight_benchmark.c @@ -8,7 +8,7 @@ #include "firmwares/fixedwing/guidance/guidance_v.h" #include "state.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "mcu_periph/uart.h" #include "generated/airframe.h" diff --git a/sw/airborne/modules/calibration/send_imu_mag_current.c b/sw/airborne/modules/calibration/send_imu_mag_current.c index 38ef498e05..dc3df49cdb 100644 --- a/sw/airborne/modules/calibration/send_imu_mag_current.c +++ b/sw/airborne/modules/calibration/send_imu_mag_current.c @@ -27,7 +27,7 @@ #include "subsystems/imu.h" #include "subsystems/electrical.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "mcu_periph/uart.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/config/config_mkk_v2.c b/sw/airborne/modules/config/config_mkk_v2.c index a5742b4b83..97f214408e 100644 --- a/sw/airborne/modules/config/config_mkk_v2.c +++ b/sw/airborne/modules/config/config_mkk_v2.c @@ -59,7 +59,7 @@ void config_mkk_v2_periodic_read_status(void) } #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/core/sys_mon.c b/sw/airborne/modules/core/sys_mon.c index 18742e7a2e..cdf68ee1a7 100644 --- a/sw/airborne/modules/core/sys_mon.c +++ b/sw/airborne/modules/core/sys_mon.c @@ -60,7 +60,7 @@ void init_sysmon(void) } #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" void periodic_report_sysmon(void) diff --git a/sw/airborne/modules/datalink/extra_pprz_dl.h b/sw/airborne/modules/datalink/extra_pprz_dl.h index 386866f619..051d5e5c92 100644 --- a/sw/airborne/modules/datalink/extra_pprz_dl.h +++ b/sw/airborne/modules/datalink/extra_pprz_dl.h @@ -29,7 +29,7 @@ #define EXTRA_PPRZ_DL_H #include "subsystems/datalink/datalink.h" -#include "subsystems/datalink/pprz_transport.h" +#include "pprzlink/pprz_transport.h" /* PPRZ transport structure */ extern struct pprz_transport extra_pprz_tp; diff --git a/sw/airborne/modules/datalink/mavlink_decoder.c b/sw/airborne/modules/datalink/mavlink_decoder.c index 3d86c5ad17..1fa08902b8 100644 --- a/sw/airborne/modules/datalink/mavlink_decoder.c +++ b/sw/airborne/modules/datalink/mavlink_decoder.c @@ -34,7 +34,7 @@ uint8_t mavlink_crc_extra[256] = {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, #if MAVLINK_DECODER_DEBUG #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" void mavlink_send_debug(struct mavlink_transport *t) diff --git a/sw/airborne/modules/datalink/mavlink_decoder.h b/sw/airborne/modules/datalink/mavlink_decoder.h index ee0970d256..d93d482d26 100644 --- a/sw/airborne/modules/datalink/mavlink_decoder.h +++ b/sw/airborne/modules/datalink/mavlink_decoder.h @@ -29,7 +29,7 @@ #define MAVLINK_DECODER_H #include "std.h" -#include "subsystems/datalink/transport.h" +#include "pprzlink/pprzlink_transport.h" #include "mcu_periph/uart.h" /* MAVLINK Transport diff --git a/sw/airborne/modules/datalink/xtend_rssi.c b/sw/airborne/modules/datalink/xtend_rssi.c index 93ffadb79f..44b7093117 100644 --- a/sw/airborne/modules/datalink/xtend_rssi.c +++ b/sw/airborne/modules/datalink/xtend_rssi.c @@ -33,7 +33,7 @@ #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" //from Digi XTend manual 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 ed97b64aa6..3d396e6fc9 100644 --- a/sw/airborne/modules/digital_cam/atmega_i2c_cam_ctrl.c +++ b/sw/airborne/modules/digital_cam/atmega_i2c_cam_ctrl.c @@ -34,7 +34,7 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" // In I2C mode we can not inline this function: diff --git a/sw/airborne/modules/digital_cam/dc.c b/sw/airborne/modules/digital_cam/dc.c index 597170738d..470b87d989 100644 --- a/sw/airborne/modules/digital_cam/dc.c +++ b/sw/airborne/modules/digital_cam/dc.c @@ -88,7 +88,7 @@ float dc_autoshoot_period; uint16_t dc_photo_nr = 0; #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "state.h" #include "subsystems/gps.h" diff --git a/sw/airborne/modules/digital_cam/hackhd.c b/sw/airborne/modules/digital_cam/hackhd.c index 565f9834ca..cd37c2dd42 100644 --- a/sw/airborne/modules/digital_cam/hackhd.c +++ b/sw/airborne/modules/digital_cam/hackhd.c @@ -83,7 +83,7 @@ static inline uint16_t pin_of_gpio(uint32_t __attribute__((unused)) port, uint16 #if HACKHD_SYNC_SEND #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "state.h" #include "subsystems/gps.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 1525b3f590..b91f095aa4 100644 --- a/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c +++ b/sw/airborne/modules/digital_cam/sim_i2c_cam_ctrl.c @@ -31,7 +31,7 @@ #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "state.h" diff --git a/sw/airborne/modules/energy/MPPT.c b/sw/airborne/modules/energy/MPPT.c index 4112331b07..1305e13472 100644 --- a/sw/airborne/modules/energy/MPPT.c +++ b/sw/airborne/modules/energy/MPPT.c @@ -54,7 +54,7 @@ struct i2c_transaction mppt_trans; #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" uint8_t MPPT_mode; diff --git a/sw/airborne/modules/energy/sim_MPPT.c b/sw/airborne/modules/energy/sim_MPPT.c index 1b0e6a82be..321e3ca78e 100644 --- a/sw/airborne/modules/energy/sim_MPPT.c +++ b/sw/airborne/modules/energy/sim_MPPT.c @@ -22,7 +22,7 @@ #include "modules/energy/MPPT.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/enose/enose.c b/sw/airborne/modules/enose/enose.c index 509689729e..47bb5d1bc8 100644 --- a/sw/airborne/modules/enose/enose.c +++ b/sw/airborne/modules/enose/enose.c @@ -47,7 +47,7 @@ void enose_set_heat(uint8_t no_sensor, uint8_t value) #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" void enose_periodic(void) diff --git a/sw/airborne/modules/gps/gps_ubx_ucenter.h b/sw/airborne/modules/gps/gps_ubx_ucenter.h index a21d61928d..0730adf452 100644 --- a/sw/airborne/modules/gps/gps_ubx_ucenter.h +++ b/sw/airborne/modules/gps/gps_ubx_ucenter.h @@ -29,7 +29,7 @@ #define GPS_UBX_UCENTER_H #include "std.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" /** U-Center Variables */ #define GPS_UBX_UCENTER_CONFIG_STEPS 19 diff --git a/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c index 9a4fdc30ae..47081b186e 100644 --- a/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c +++ b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c @@ -26,7 +26,7 @@ #include "mcu_periph/spi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" //struct qr_code_spi_link_data qr_code_spi_link_data; diff --git a/sw/airborne/modules/ins/ahrs_chimu_spi.c b/sw/airborne/modules/ins/ahrs_chimu_spi.c index 9d4f196cca..18ed9222d2 100644 --- a/sw/airborne/modules/ins/ahrs_chimu_spi.c +++ b/sw/airborne/modules/ins/ahrs_chimu_spi.c @@ -20,7 +20,7 @@ #if CHIMU_DOWNLINK_IMMEDIATE #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #endif diff --git a/sw/airborne/modules/ins/ahrs_chimu_uart.c b/sw/airborne/modules/ins/ahrs_chimu_uart.c index 7d5d83f6df..913c28cefa 100644 --- a/sw/airborne/modules/ins/ahrs_chimu_uart.c +++ b/sw/airborne/modules/ins/ahrs_chimu_uart.c @@ -16,7 +16,7 @@ #if CHIMU_DOWNLINK_IMMEDIATE #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #endif diff --git a/sw/airborne/modules/ins/alt_filter.c b/sw/airborne/modules/ins/alt_filter.c index bafb13e244..88479aca5e 100644 --- a/sw/airborne/modules/ins/alt_filter.c +++ b/sw/airborne/modules/ins/alt_filter.c @@ -25,7 +25,7 @@ #include "modules/sensors/baro_ets.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" TypeKalman alt_filter; diff --git a/sw/airborne/modules/ins/ins_arduimu.c b/sw/airborne/modules/ins/ins_arduimu.c index 043a88f257..42f06aaa25 100644 --- a/sw/airborne/modules/ins/ins_arduimu.c +++ b/sw/airborne/modules/ins/ins_arduimu.c @@ -31,7 +31,7 @@ int32_t GPS_Data[14]; #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" struct i2c_transaction ardu_gps_trans; diff --git a/sw/airborne/modules/ins/ins_arduimu_basic.c b/sw/airborne/modules/ins/ins_arduimu_basic.c index 9303dfd4b4..f9e319fa1f 100644 --- a/sw/airborne/modules/ins/ins_arduimu_basic.c +++ b/sw/airborne/modules/ins/ins_arduimu_basic.c @@ -50,7 +50,7 @@ #ifdef ARDUIMU_SYNC_SEND #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #endif diff --git a/sw/airborne/modules/ins/ins_module.h b/sw/airborne/modules/ins/ins_module.h index 3256e26626..bfb01dfad0 100644 --- a/sw/airborne/modules/ins/ins_module.h +++ b/sw/airborne/modules/ins/ins_module.h @@ -71,7 +71,7 @@ void handle_ins_msg(void); void parse_ins_msg(void); void parse_ins_buffer(uint8_t); -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #define InsLinkDevice (&((INS_LINK).device)) diff --git a/sw/airborne/modules/ins/ins_vn100.c b/sw/airborne/modules/ins/ins_vn100.c index f35c2c5e78..15bf8cbce6 100644 --- a/sw/airborne/modules/ins/ins_vn100.c +++ b/sw/airborne/modules/ins/ins_vn100.c @@ -33,7 +33,7 @@ // for telemetry report #include "mcu_periph/uart.h" #include "subsystems/datalink/downlink.h" -#include "messages.h" +#include "pprzlink/messages.h" #ifndef INS_YAW_NEUTRAL_DEFAULT #define INS_YAW_NEUTRAL_DEFAULT 0. @@ -305,7 +305,7 @@ static inline void parse_ins_msg(void) } #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" extern void vn100_report_task(void) diff --git a/sw/airborne/modules/ins/ins_xsens.c b/sw/airborne/modules/ins/ins_xsens.c index 8a98e60c8c..39d9d55969 100644 --- a/sw/airborne/modules/ins/ins_xsens.c +++ b/sw/airborne/modules/ins/ins_xsens.c @@ -33,7 +33,7 @@ #include "generated/airframe.h" #include "mcu_periph/sys_time.h" -#include "messages.h" +#include "pprzlink/messages.h" #if USE_GPS_XSENS #if !USE_GPS @@ -178,7 +178,7 @@ uint8_t xsens_msg_buf[XSENS_MAX_PAYLOAD]; // FIXME Debugging Only #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/ins/ins_xsens700.c b/sw/airborne/modules/ins/ins_xsens700.c index 727ad4943b..102f9b39f3 100644 --- a/sw/airborne/modules/ins/ins_xsens700.c +++ b/sw/airborne/modules/ins/ins_xsens700.c @@ -35,7 +35,7 @@ #include "mcu_periph/sys_time.h" #include "subsystems/datalink/downlink.h" -#include "messages.h" +#include "pprzlink/messages.h" #if USE_GPS_XSENS #if !USE_GPS @@ -126,7 +126,7 @@ uint8_t xsens_msg_buf[XSENS_MAX_PAYLOAD]; // FIXME Debugging Only #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/loggers/flight_recorder.c b/sw/airborne/modules/loggers/flight_recorder.c index 2fc52e977b..013b9e9e25 100644 --- a/sw/airborne/modules/loggers/flight_recorder.c +++ b/sw/airborne/modules/loggers/flight_recorder.c @@ -28,7 +28,7 @@ #include "modules/loggers/flight_recorder.h" #include "subsystems/datalink/telemetry.h" -#include "subsystems/datalink/pprzlog_transport.h" +#include "pprzlink/pprzlog_transport.h" #if FLIGHTRECORDER_SDLOG #include "sdLog.h" diff --git a/sw/airborne/modules/loggers/openlog.c b/sw/airborne/modules/loggers/openlog.c index 2e51ac5c95..27c9f506fd 100644 --- a/sw/airborne/modules/loggers/openlog.c +++ b/sw/airborne/modules/loggers/openlog.c @@ -29,7 +29,7 @@ */ #include "openlog.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "mcu_periph/sys_time.h" diff --git a/sw/airborne/modules/loggers/sdlogger_spi_direct.c b/sw/airborne/modules/loggers/sdlogger_spi_direct.c index 099a32a27b..8e12c7e2a5 100644 --- a/sw/airborne/modules/loggers/sdlogger_spi_direct.c +++ b/sw/airborne/modules/loggers/sdlogger_spi_direct.c @@ -30,7 +30,7 @@ #define PERIODIC_C_LOGGER #include "modules/loggers/sdlogger_spi_direct.h" -#include "subsystems/datalink/pprzlog_transport.h" +#include "pprzlink/pprzlog_transport.h" #include "subsystems/datalink/telemetry.h" #include "subsystems/radio_control.h" #include "led.h" diff --git a/sw/airborne/modules/loggers/sdlogger_spi_direct.h b/sw/airborne/modules/loggers/sdlogger_spi_direct.h index f5bb79c6ef..2d55fa744e 100644 --- a/sw/airborne/modules/loggers/sdlogger_spi_direct.h +++ b/sw/airborne/modules/loggers/sdlogger_spi_direct.h @@ -28,7 +28,7 @@ #define SDLOGGER_BUFFER_SIZE 128 -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #include "peripherals/sdcard_spi.h" enum SDLoggerStatus { diff --git a/sw/airborne/modules/meteo/charge_sens.c b/sw/airborne/modules/meteo/charge_sens.c index d9c969bbc6..d548be6baf 100644 --- a/sw/airborne/modules/meteo/charge_sens.c +++ b/sw/airborne/modules/meteo/charge_sens.c @@ -28,7 +28,7 @@ #include "modules/meteo/charge_sens.h" #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/dust_gp2y.c b/sw/airborne/modules/meteo/dust_gp2y.c index ea6a191c16..ee60752e1f 100644 --- a/sw/airborne/modules/meteo/dust_gp2y.c +++ b/sw/airborne/modules/meteo/dust_gp2y.c @@ -32,7 +32,7 @@ #include "mcu_periph/i2c.h" #include "mcu_periph/sys_time.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" uint8_t dust_gp2y_status; diff --git a/sw/airborne/modules/meteo/geiger_counter.c b/sw/airborne/modules/meteo/geiger_counter.c index 2563a0fa56..cb3298864d 100644 --- a/sw/airborne/modules/meteo/geiger_counter.c +++ b/sw/airborne/modules/meteo/geiger_counter.c @@ -28,7 +28,7 @@ #include "modules/meteo/geiger_counter.h" #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/humid_dpicco.c b/sw/airborne/modules/meteo/humid_dpicco.c index 2109358198..51608bb13f 100644 --- a/sw/airborne/modules/meteo/humid_dpicco.c +++ b/sw/airborne/modules/meteo/humid_dpicco.c @@ -33,7 +33,7 @@ #include "mcu_periph/i2c.h" #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/humid_hih.c b/sw/airborne/modules/meteo/humid_hih.c index eb10ae662d..c84d3e6b5d 100644 --- a/sw/airborne/modules/meteo/humid_hih.c +++ b/sw/airborne/modules/meteo/humid_hih.c @@ -33,7 +33,7 @@ #include "modules/meteo/humid_sht.h" #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/humid_htm_b71.c b/sw/airborne/modules/meteo/humid_htm_b71.c index 68dfcd2a77..1bfffc822a 100644 --- a/sw/airborne/modules/meteo/humid_htm_b71.c +++ b/sw/airborne/modules/meteo/humid_htm_b71.c @@ -33,7 +33,7 @@ #include "mcu_periph/sys_time.h" #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/humid_pcap01.c b/sw/airborne/modules/meteo/humid_pcap01.c index 22373602d6..570d8e4d7a 100644 --- a/sw/airborne/modules/meteo/humid_pcap01.c +++ b/sw/airborne/modules/meteo/humid_pcap01.c @@ -32,7 +32,7 @@ #include "mcu_periph/sys_time.h" #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "modules/meteo/humid_pcap01.h" #ifdef PCAP01_LOAD_FIRMWARE diff --git a/sw/airborne/modules/meteo/humid_sht.c b/sw/airborne/modules/meteo/humid_sht.c index ba77043e91..ec89245930 100644 --- a/sw/airborne/modules/meteo/humid_sht.c +++ b/sw/airborne/modules/meteo/humid_sht.c @@ -31,7 +31,7 @@ #include "std.h" #include "mcu_periph/gpio.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/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 b56074210a..23757a82d2 100644 --- a/sw/airborne/modules/meteo/humid_sht_i2c.c +++ b/sw/airborne/modules/meteo/humid_sht_i2c.c @@ -30,7 +30,7 @@ #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/ir_mlx.c b/sw/airborne/modules/meteo/ir_mlx.c index fecfad91a0..1dabd53d2f 100644 --- a/sw/airborne/modules/meteo/ir_mlx.c +++ b/sw/airborne/modules/meteo/ir_mlx.c @@ -33,7 +33,7 @@ #include "mcu_periph/i2c.h" #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/light_solar.c b/sw/airborne/modules/meteo/light_solar.c index 69a2cb5355..d03c4ed07a 100644 --- a/sw/airborne/modules/meteo/light_solar.c +++ b/sw/airborne/modules/meteo/light_solar.c @@ -29,7 +29,7 @@ #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "modules/meteo/light_solar.h" diff --git a/sw/airborne/modules/meteo/light_temt.c b/sw/airborne/modules/meteo/light_temt.c index 2b9914465d..4de52db2a5 100644 --- a/sw/airborne/modules/meteo/light_temt.c +++ b/sw/airborne/modules/meteo/light_temt.c @@ -30,7 +30,7 @@ #include "modules/meteo/light_temt.h" #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #ifndef ADC_CHANNEL_LIGHT_TEMT diff --git a/sw/airborne/modules/meteo/meteo_stick.c b/sw/airborne/modules/meteo/meteo_stick.c index 2d44673ab3..ff0a836950 100644 --- a/sw/airborne/modules/meteo/meteo_stick.c +++ b/sw/airborne/modules/meteo/meteo_stick.c @@ -188,7 +188,7 @@ bool_t log_ptu_started; #if SEND_MS #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "subsystems/gps.h" diff --git a/sw/airborne/modules/meteo/mf_ptu.c b/sw/airborne/modules/meteo/mf_ptu.c index 6660fa09db..45ebadb974 100644 --- a/sw/airborne/modules/meteo/mf_ptu.c +++ b/sw/airborne/modules/meteo/mf_ptu.c @@ -69,7 +69,7 @@ bool_t log_ptu_started; #if SEND_PTU #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "subsystems/gps.h" #endif diff --git a/sw/airborne/modules/meteo/temp_lm75.c b/sw/airborne/modules/meteo/temp_lm75.c index 2318f0176c..208674a109 100644 --- a/sw/airborne/modules/meteo/temp_lm75.c +++ b/sw/airborne/modules/meteo/temp_lm75.c @@ -32,7 +32,7 @@ #include "mcu_periph/i2c.h" #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/temp_tcouple_adc.c b/sw/airborne/modules/meteo/temp_tcouple_adc.c index 5a845fb62a..5e672564f9 100644 --- a/sw/airborne/modules/meteo/temp_tcouple_adc.c +++ b/sw/airborne/modules/meteo/temp_tcouple_adc.c @@ -30,7 +30,7 @@ #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "modules/meteo/temp_tcouple_adc.h" diff --git a/sw/airborne/modules/meteo/temp_temod.c b/sw/airborne/modules/meteo/temp_temod.c index e45251260f..3ab9522534 100644 --- a/sw/airborne/modules/meteo/temp_temod.c +++ b/sw/airborne/modules/meteo/temp_temod.c @@ -30,7 +30,7 @@ #include "mcu_periph/i2c.h" #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" float ftmd_temperature; diff --git a/sw/airborne/modules/meteo/temp_tmp102.c b/sw/airborne/modules/meteo/temp_tmp102.c index 7c7b5d438c..2a98612b59 100644 --- a/sw/airborne/modules/meteo/temp_tmp102.c +++ b/sw/airborne/modules/meteo/temp_tmp102.c @@ -32,7 +32,7 @@ #include "mcu_periph/i2c.h" #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/meteo/wind_gfi.c b/sw/airborne/modules/meteo/wind_gfi.c index 002944ded7..a5240b4b24 100644 --- a/sw/airborne/modules/meteo/wind_gfi.c +++ b/sw/airborne/modules/meteo/wind_gfi.c @@ -32,7 +32,7 @@ #include "mcu_periph/i2c.h" #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" struct i2c_transaction pcf_trans; diff --git a/sw/airborne/modules/meteo/windturbine.c b/sw/airborne/modules/meteo/windturbine.c index 0c28e96fe8..c7d8c7a5a1 100644 --- a/sw/airborne/modules/meteo/windturbine.c +++ b/sw/airborne/modules/meteo/windturbine.c @@ -34,7 +34,7 @@ #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/multi/follow.c b/sw/airborne/modules/multi/follow.c index d92ceee567..9d355083e2 100644 --- a/sw/airborne/modules/multi/follow.c +++ b/sw/airborne/modules/multi/follow.c @@ -32,8 +32,8 @@ #include "subsystems/navigation/waypoints.h" #include "state.h" -#include "messages.h" -#include "dl_protocol.h" +#include "pprzlink/messages.h" +#include "pprzlink/dl_protocol.h" #ifndef FOLLOW_OFFSET_X #define FOLLOW_OFFSET_X 0.0 diff --git a/sw/airborne/modules/multi/formation.c b/sw/airborne/modules/multi/formation.c index 94a3da7841..fdadf30d5b 100644 --- a/sw/airborne/modules/multi/formation.c +++ b/sw/airborne/modules/multi/formation.c @@ -16,7 +16,7 @@ #include "subsystems/gps.h" #include "generated/flight_plan.h" #include "generated/airframe.h" -#include "dl_protocol.h" +#include "pprzlink/dl_protocol.h" #include diff --git a/sw/airborne/modules/multi/potential.c b/sw/airborne/modules/multi/potential.c index f968d1ddc9..de7b15d14e 100644 --- a/sw/airborne/modules/multi/potential.c +++ b/sw/airborne/modules/multi/potential.c @@ -6,7 +6,7 @@ #include #include "subsystems/datalink/downlink.h" -#include "dl_protocol.h" +#include "pprzlink/dl_protocol.h" #include "potential.h" #include "state.h" diff --git a/sw/airborne/modules/multi/tcas.c b/sw/airborne/modules/multi/tcas.c index 4c23707915..36f0890924 100644 --- a/sw/airborne/modules/multi/tcas.c +++ b/sw/airborne/modules/multi/tcas.c @@ -32,7 +32,7 @@ #include "subsystems/gps.h" #include "generated/flight_plan.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" float tcas_alt_setpoint; diff --git a/sw/airborne/modules/nav/nav_catapult.c b/sw/airborne/modules/nav/nav_catapult.c index 3373787f0f..bf01285cd8 100644 --- a/sw/airborne/modules/nav/nav_catapult.c +++ b/sw/airborne/modules/nav/nav_catapult.c @@ -47,7 +47,7 @@ #include "subsystems/imu.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/datalink.h" diff --git a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c index ca18804d9e..301e2b75c1 100644 --- a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c +++ b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c @@ -27,7 +27,7 @@ /* #include #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" */ diff --git a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c index 1745c7ac44..ef47a6823a 100644 --- a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c +++ b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c @@ -39,7 +39,7 @@ #endif #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #if PERIODIC_TELEMETRY diff --git a/sw/airborne/modules/optical_flow/px4flow.c b/sw/airborne/modules/optical_flow/px4flow.c index f50f8e6659..56c863328c 100644 --- a/sw/airborne/modules/optical_flow/px4flow.c +++ b/sw/airborne/modules/optical_flow/px4flow.c @@ -75,7 +75,7 @@ void px4flow_init(void) // Messages #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" /** Downlink message for debug diff --git a/sw/airborne/modules/sensors/airspeed_amsys.c b/sw/airborne/modules/sensors/airspeed_amsys.c index e9dc36b3c2..3782153982 100644 --- a/sw/airborne/modules/sensors/airspeed_amsys.c +++ b/sw/airborne/modules/sensors/airspeed_amsys.c @@ -27,7 +27,7 @@ #include "state.h" #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include //#include diff --git a/sw/airborne/modules/sensors/airspeed_ets.c b/sw/airborne/modules/sensors/airspeed_ets.c index 748fce7df8..0e137a4ddb 100644 --- a/sw/airborne/modules/sensors/airspeed_ets.c +++ b/sw/airborne/modules/sensors/airspeed_ets.c @@ -44,7 +44,7 @@ #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" #include "mcu_periph/sys_time.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include diff --git a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c index 33d756a48b..576c0407fc 100644 --- a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c +++ b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c @@ -32,7 +32,7 @@ #include "subsystems/abi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #if PERIODIC_TELEMETRY diff --git a/sw/airborne/modules/sensors/airspeed_otf.c b/sw/airborne/modules/sensors/airspeed_otf.c index 5888dc7d65..f8ba178356 100644 --- a/sw/airborne/modules/sensors/airspeed_otf.c +++ b/sw/airborne/modules/sensors/airspeed_otf.c @@ -32,7 +32,7 @@ #include #include #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "met_module.h" diff --git a/sw/airborne/modules/sensors/alt_srf08.c b/sw/airborne/modules/sensors/alt_srf08.c index 048043ced1..b950db614c 100644 --- a/sw/airborne/modules/sensors/alt_srf08.c +++ b/sw/airborne/modules/sensors/alt_srf08.c @@ -30,7 +30,7 @@ #include "mcu_periph/i2c.h" #include "alt_srf08.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "led.h" diff --git a/sw/airborne/modules/sensors/aoa_adc.c b/sw/airborne/modules/sensors/aoa_adc.c index f5760ecacb..8f9c75cd45 100644 --- a/sw/airborne/modules/sensors/aoa_adc.c +++ b/sw/airborne/modules/sensors/aoa_adc.c @@ -34,7 +34,7 @@ // Messages #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" /// Default offset value (assuming 0 AOA is in the middle of the range) diff --git a/sw/airborne/modules/sensors/aoa_pwm.c b/sw/airborne/modules/sensors/aoa_pwm.c index 0eb071537d..ae11c4c6c5 100644 --- a/sw/airborne/modules/sensors/aoa_pwm.c +++ b/sw/airborne/modules/sensors/aoa_pwm.c @@ -29,7 +29,7 @@ #include "modules/sensors/aoa_pwm.h" #include "mcu_periph/pwm_input.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "generated/airframe.h" diff --git a/sw/airborne/modules/sensors/baro_amsys.c b/sw/airborne/modules/sensors/baro_amsys.c index 89b65822ef..28e6123990 100644 --- a/sw/airborne/modules/sensors/baro_amsys.c +++ b/sw/airborne/modules/sensors/baro_amsys.c @@ -32,7 +32,7 @@ //Messages #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" //#include "gps.h" diff --git a/sw/airborne/modules/sensors/baro_bmp.c b/sw/airborne/modules/sensors/baro_bmp.c index 844c275099..eaa2d147cd 100644 --- a/sw/airborne/modules/sensors/baro_bmp.c +++ b/sw/airborne/modules/sensors/baro_bmp.c @@ -37,7 +37,7 @@ #include "led.h" #include "mcu_periph/uart.h" #include "subsystems/abi.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/sensors/baro_ets.c b/sw/airborne/modules/sensors/baro_ets.c index d672ac2799..a5d667c2e1 100644 --- a/sw/airborne/modules/sensors/baro_ets.c +++ b/sw/airborne/modules/sensors/baro_ets.c @@ -51,7 +51,7 @@ #ifdef BARO_ETS_SYNC_SEND #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #endif //BARO_ETS_SYNC_SEND diff --git a/sw/airborne/modules/sensors/baro_hca.c b/sw/airborne/modules/sensors/baro_hca.c index d802b257b0..4c36172083 100644 --- a/sw/airborne/modules/sensors/baro_hca.c +++ b/sw/airborne/modules/sensors/baro_hca.c @@ -27,7 +27,7 @@ //Messages #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/sensors/baro_mpl3115.c b/sw/airborne/modules/sensors/baro_mpl3115.c index fd2be6f12d..b8c35c54ec 100644 --- a/sw/airborne/modules/sensors/baro_mpl3115.c +++ b/sw/airborne/modules/sensors/baro_mpl3115.c @@ -32,7 +32,7 @@ //Messages #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.c b/sw/airborne/modules/sensors/baro_ms5611_i2c.c index bc830a9000..2aeca5c956 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.c @@ -33,7 +33,7 @@ #include "mcu_periph/sys_time.h" #include "subsystems/abi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.c b/sw/airborne/modules/sensors/baro_ms5611_spi.c index b043f4d8fb..768c8aa4d9 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.c +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.c @@ -33,7 +33,7 @@ #include "mcu_periph/sys_time.h" #include "subsystems/abi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #ifndef MS5611_SPI_DEV diff --git a/sw/airborne/modules/sensors/baro_scp.c b/sw/airborne/modules/sensors/baro_scp.c index ef00a66a4f..05a819dc52 100644 --- a/sw/airborne/modules/sensors/baro_scp.c +++ b/sw/airborne/modules/sensors/baro_scp.c @@ -5,7 +5,7 @@ #include "subsystems/abi.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "mcu_periph/spi.h" diff --git a/sw/airborne/modules/sensors/baro_scp_i2c.c b/sw/airborne/modules/sensors/baro_scp_i2c.c index 49b5e3397c..520edcb0b9 100644 --- a/sw/airborne/modules/sensors/baro_scp_i2c.c +++ b/sw/airborne/modules/sensors/baro_scp_i2c.c @@ -13,7 +13,7 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #ifndef SENSOR_SYNC_SEND diff --git a/sw/airborne/modules/sensors/imu_aspirin2.c b/sw/airborne/modules/sensors/imu_aspirin2.c index 25fa7ae465..da5d39ddb3 100644 --- a/sw/airborne/modules/sensors/imu_aspirin2.c +++ b/sw/airborne/modules/sensors/imu_aspirin2.c @@ -26,7 +26,7 @@ // Downlink #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/sensors/mag_hmc5843.c b/sw/airborne/modules/sensors/mag_hmc5843.c index 2ed2f7c403..a47f5830b6 100644 --- a/sw/airborne/modules/sensors/mag_hmc5843.c +++ b/sw/airborne/modules/sensors/mag_hmc5843.c @@ -19,7 +19,7 @@ */ #include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include diff --git a/sw/airborne/modules/sensors/mag_hmc58xx.c b/sw/airborne/modules/sensors/mag_hmc58xx.c index 36569b2054..047bbaf972 100644 --- a/sw/airborne/modules/sensors/mag_hmc58xx.c +++ b/sw/airborne/modules/sensors/mag_hmc58xx.c @@ -27,7 +27,7 @@ #include "modules/sensors/mag_hmc58xx.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #if MODULE_HMC58XX_UPDATE_AHRS diff --git a/sw/airborne/modules/sensors/mag_micromag_fw.c b/sw/airborne/modules/sensors/mag_micromag_fw.c index 7492334ec4..f6f6a44387 100644 --- a/sw/airborne/modules/sensors/mag_micromag_fw.c +++ b/sw/airborne/modules/sensors/mag_micromag_fw.c @@ -3,7 +3,7 @@ #include "led.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" volatile uint8_t micromag_status; diff --git a/sw/airborne/modules/sensors/temp_adc.c b/sw/airborne/modules/sensors/temp_adc.c index 67db03d4f7..4b477d5160 100644 --- a/sw/airborne/modules/sensors/temp_adc.c +++ b/sw/airborne/modules/sensors/temp_adc.c @@ -27,7 +27,7 @@ #include "modules/sensors/temp_adc.h" #include "mcu_periph/adc.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include BOARD_CONFIG diff --git a/sw/airborne/modules/sensors/trigger_ext.c b/sw/airborne/modules/sensors/trigger_ext.c index fa9a84535c..b8581429c3 100644 --- a/sw/airborne/modules/sensors/trigger_ext.c +++ b/sw/airborne/modules/sensors/trigger_ext.c @@ -34,7 +34,7 @@ #include "subsystems/gps.h" #include "mcu_periph/sys_time.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" diff --git a/sw/airborne/modules/sonar/sonar_adc.c b/sw/airborne/modules/sonar/sonar_adc.c index 028db175a1..cbb21a0778 100644 --- a/sw/airborne/modules/sonar/sonar_adc.c +++ b/sw/airborne/modules/sonar/sonar_adc.c @@ -29,7 +29,7 @@ #endif #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" /** Sonar offset. diff --git a/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c b/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c index 1196770a3f..c958d71d09 100644 --- a/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c +++ b/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c @@ -56,7 +56,7 @@ struct link_device *xdev = STEREO_PORT; #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE #endif -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "led.h" diff --git a/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c b/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c index 00087a4fab..35104332cf 100644 --- a/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c +++ b/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c @@ -44,7 +44,7 @@ #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE #endif -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "led.h" diff --git a/sw/airborne/modules/stereocam/stereoprotocol.h b/sw/airborne/modules/stereocam/stereoprotocol.h index 588f3ca647..4a75f0406f 100644 --- a/sw/airborne/modules/stereocam/stereoprotocol.h +++ b/sw/airborne/modules/stereocam/stereoprotocol.h @@ -28,7 +28,7 @@ #define SW_AIRBORNE_MODULES_STEREO_CAM_STEREOPROTOCOL_H_ #include -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" struct MsgProperties { uint16_t positionImageStart; diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 49d3217cb4..ef7593bf27 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -31,7 +31,7 @@ #include "subsystems/radio_control.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" /* Static functions used in the different statuses */ diff --git a/sw/airborne/pprz_debug.h b/sw/airborne/pprz_debug.h index a1c2294337..97c04baa7e 100644 --- a/sw/airborne/pprz_debug.h +++ b/sw/airborne/pprz_debug.h @@ -30,7 +30,7 @@ #include "std.h" #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" extern uint8_t pprz_debug_mod; diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c index 72e34b8ea5..1ac9197932 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c @@ -45,7 +45,7 @@ #if FLOAT_DCM_SEND_DEBUG // FIXME Debugging Only #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #endif diff --git a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h index b5b278b740..55808d79cb 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h +++ b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h @@ -30,7 +30,7 @@ #include "ff.h" #include "subsystems/chibios-libopencm3/sdLog.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" /* what to be done : diff --git a/sw/airborne/subsystems/datalink/audio_telemetry.h b/sw/airborne/subsystems/datalink/audio_telemetry.h deleted file mode 100644 index d83ff0f872..0000000000 --- a/sw/airborne/subsystems/datalink/audio_telemetry.h +++ /dev/null @@ -1,75 +0,0 @@ -/* - * Paparazzi telemetry via audio channel modem functions - * - * Copyright (C) 2003 Pascal Brisset, Antoine Drouin - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - * - */ - -#ifndef AUDIO_TELEMETRY_H -#define AUDIO_TELEMETRY_H - -#include "inttypes.h" - -extern uint8_t audio_telemetry_nb_ovrn; - -#include "generated/airframe.h" -#include "audio_telemetry_hw.h" - - -#define TX_BUF_SIZE 255 -extern uint8_t tx_head; -extern volatile uint8_t tx_tail; -extern uint8_t tx_buf[ TX_BUF_SIZE ]; - -extern uint8_t tx_byte; -extern uint8_t tx_byte_idx; - - -#define AudioTelemetrySendMessage() AUDIO_TELEMETRY_CHECK_RUNNING() - -#if TX_BUF_SIZE == 256 -#define UPDATE_HEAD() { \ - tx_head++; \ - } -#else -#define UPDATE_HEAD() { \ - tx_head++; \ - if (tx_head >= TX_BUF_SIZE) tx_head = 0; \ - } -#endif - -#define AudioTelemetryCheckFreeSpace(_space) (tx_head>=tx_tail? _space < (TX_BUF_SIZE - (tx_head - tx_tail)) : _space < (tx_tail - tx_head)) - -#define AudioTelemetryPut1Byte(_byte) { \ - tx_buf[tx_head] = _byte; \ - UPDATE_HEAD(); \ - } - -#define AUDIO_TELEMETRY_LOAD_NEXT_BYTE() { \ - tx_byte = tx_buf[tx_tail]; \ - tx_byte_idx = 0; \ - tx_tail++; \ - if( tx_tail >= TX_BUF_SIZE ) \ - tx_tail = 0; \ - } - -#define AudioTelemetryTransmit(_x) Audio_TelemetryPut1Byte(_x) - -#endif /* AUDIO_TELEMETRY_H */ diff --git a/sw/airborne/subsystems/datalink/bluegiga.h b/sw/airborne/subsystems/datalink/bluegiga.h index f7770abd33..167d1826b8 100644 --- a/sw/airborne/subsystems/datalink/bluegiga.h +++ b/sw/airborne/subsystems/datalink/bluegiga.h @@ -27,7 +27,7 @@ #ifndef BLUEGIGA_DATA_LINK_H #define BLUEGIGA_DATA_LINK_H -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" /* The different statuses the communication can be in */ enum BlueGigaStatus { @@ -80,7 +80,7 @@ void bluegiga_request_all_rssi(struct bluegiga_periph *p); // BLUEGIGA is using pprz_transport // FIXME it should not appear here, this will be fixed with the rx improvements some day... // BLUEGIGA needs a specific read_buffer function -#include "subsystems/datalink/pprz_transport.h" +#include "pprzlink/pprz_transport.h" #include "led.h" static inline void bluegiga_read_buffer(struct bluegiga_periph *p, struct pprz_transport *t) { diff --git a/sw/airborne/subsystems/datalink/datalink.h b/sw/airborne/subsystems/datalink/datalink.h index 23bbbb9171..f000315108 100644 --- a/sw/airborne/subsystems/datalink/datalink.h +++ b/sw/airborne/subsystems/datalink/datalink.h @@ -40,7 +40,7 @@ #endif #include "std.h" -#include "dl_protocol.h" +#include "pprzlink/dl_protocol.h" /** Datalink kinds */ #define PPRZ 1 @@ -89,14 +89,14 @@ static inline void DlCheckAndParse(void) #if defined DATALINK && DATALINK == PPRZ #define DatalinkEvent() { \ - PprzCheckAndParse(PPRZ_UART, pprz_tp); \ + pprz_check_and_parse(&(PPRZ_UART).device, &pprz_tp, dl_buffer, &dl_msg_available); \ DlCheckAndParse(); \ } #elif defined DATALINK && DATALINK == XBEE #define DatalinkEvent() { \ - XBeeCheckAndParse(XBEE_UART, xbee_tp); \ + xbee_check_and_parse(&(XBEE_UART).device, &xbee_tp, dl_buffer, &dl_msg_available); \ DlCheckAndParse(); \ } diff --git a/sw/airborne/subsystems/datalink/downlink.c b/sw/airborne/subsystems/datalink/downlink.c index efcafa3470..b465c01ce7 100644 --- a/sw/airborne/subsystems/datalink/downlink.c +++ b/sw/airborne/subsystems/datalink/downlink.c @@ -27,6 +27,18 @@ #include "subsystems/datalink/downlink.h" +#include "generated/airframe.h" // AC_ID is required + +#if defined SITL && !USE_NPS +struct ivy_transport ivy_tp; +#endif + +#if DATALINK == PPRZ +struct pprz_transport pprz_tp; +#endif +#if DATALINK == XBEE +struct xbee_transport xbee_tp; +#endif #if PERIODIC_TELEMETRY #include "subsystems/datalink/telemetry.h" @@ -76,7 +88,13 @@ void downlink_init(void) pprz_transport_init(&pprz_tp); #endif #if DATALINK == XBEE - xbee_init(); +#ifndef XBEE_TYPE +#define XBEE_TYPE XBEE_24 +#endif +#ifndef XBEE_INIT +#define XBEE_INIT "" +#endif + xbee_transport_init(&xbee_tp, &((DefaultDevice).device), AC_ID, XBEE_TYPE, sys_time_usleep, XBEE_INIT); #endif #if DATALINK == W5100 w5100_init(); @@ -92,7 +110,7 @@ void downlink_init(void) #endif #if SITL && !USE_NPS - ivy_transport_init(); + ivy_transport_init(&ivy_tp); #endif #if PERIODIC_TELEMETRY diff --git a/sw/airborne/subsystems/datalink/downlink.h b/sw/airborne/subsystems/datalink/downlink.h index aeb2044464..cfc0287012 100644 --- a/sw/airborne/subsystems/datalink/downlink.h +++ b/sw/airborne/subsystems/datalink/downlink.h @@ -30,31 +30,52 @@ #include -#ifndef PPRZ_DATALINK_EXPORT - #include "generated/modules.h" -#include "messages.h" -#include "generated/airframe.h" // AC_ID is required +#include "pprzlink/messages.h" + +// FIXME tmp hack +#ifndef PPRZ +#define PPRZ 1 +#endif +#ifndef XBEE +#define XBEE 2 +#endif +#ifndef SUPERBITRF +#define SUPERBITRF 3 +#endif +#ifndef W5100 +#define W5100 4 +#endif +#ifndef BLUEGIGA +#define BLUEGIGA 5 +#endif #if defined SITL && !USE_NPS /** Software In The Loop simulation uses IVY bus directly as the transport layer */ -#include "ivy_transport.h" +#include "pprzlink/ivy_transport.h" +extern struct ivy_transport ivy_tp; #else /** SITL */ -#include "subsystems/datalink/pprz_transport.h" -#include "subsystems/datalink/pprzlog_transport.h" -#include "subsystems/datalink/xbee.h" -#include "subsystems/datalink/w5100.h" +#if DATALINK == PPRZ +#include "pprzlink/pprz_transport.h" +extern struct pprz_transport pprz_tp; +#endif + +#include "pprzlink/pprzlog_transport.h" + +#if DATALINK == XBEE +#include "pprzlink/xbee_transport.h" +extern struct xbee_transport xbee_tp; +#endif + +//#include "subsystems/datalink/w5100.h" #if DATALINK == BLUEGIGA -#include "subsystems/datalink/bluegiga.h" +//#include "subsystems/datalink/bluegiga.h" #endif #if USE_SUPERBITRF #include "subsystems/datalink/superbitrf.h" #endif -#if USE_AUDIO_TELEMETRY -#include "subsystems/datalink/audio_telemetry.h" -#endif #if USE_USB_SERIAL #include "mcu_periph/usb_serial.h" #endif @@ -65,15 +86,6 @@ #endif /** !SITL */ -#else /* PPRZ_DATALINK_EXPORT defined */ - -#include "messages.h" -#include "pprz_transport.h" -#ifndef AC_ID -#define AC_ID 0 -#endif - -#endif #ifndef DefaultChannel #define DefaultChannel DOWNLINK_TRANSPORT diff --git a/sw/airborne/subsystems/datalink/downlink_transport.h b/sw/airborne/subsystems/datalink/downlink_transport.h deleted file mode 100644 index e532af245a..0000000000 --- a/sw/airborne/subsystems/datalink/downlink_transport.h +++ /dev/null @@ -1,63 +0,0 @@ -/* - * Copyright (C) 2003-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 downlink_transport.h - * \brief Interface for downlink transport implementation - * - */ - -#ifndef DOWNLINK_TRANSPORT_H -#define DOWNLINK_TRANSPORT_H - -#include - -enum DownlinkDataType { - DL_TYPE_ARRAY_LENGTH = 1, - DL_TYPE_UINT8, - DL_TYPE_INT8, - DL_TYPE_UINT16, - DL_TYPE_INT16, - DL_TYPE_UINT32, - DL_TYPE_INT32, - DL_TYPE_UINT64, - DL_TYPE_INT64, - DL_TYPE_FLOAT, - DL_TYPE_DOUBLE, - DL_TYPE_TIMESTAMP, -}; - -struct DownlinkTransport { - uint8_t (*SizeOf)(void *impl, uint8_t size); - int (*CheckFreeSpace)(void *impl, uint8_t size); - - void (*PutBytes)(void *impl, enum DownlinkDataType data_type, uint8_t len, const void *bytes); - - void (*StartMessage)(void *impl, char *name, uint8_t msg_id, uint8_t payload_len); - void (*EndMessage)(void *impl); - void (*Overrun)(void *impl); - void (*CountBytes)(void *impl, uint8_t len); - void (*Periodic)(void *impl); - - void *impl; -}; - -#endif /* DOWNLINK_TRANSPORT_H */ diff --git a/sw/airborne/subsystems/datalink/ivy_transport.c b/sw/airborne/subsystems/datalink/ivy_transport.c deleted file mode 100644 index 30931c45d4..0000000000 --- a/sw/airborne/subsystems/datalink/ivy_transport.c +++ /dev/null @@ -1,204 +0,0 @@ -/* - * Copyright (C) 2003 Pascal Brisset, Antoine Drouin - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/ivy_transport.c - * - * Building Paparazzi frames over IVY. - * - */ - -#include "std.h" -#include "subsystems/datalink/ivy_transport.h" -#include "subsystems/datalink/downlink.h" -#include "subsystems/datalink/transport.h" - -#include -#include - -struct ivy_transport ivy_tp; - -static void put_bytes(struct ivy_transport *trans, struct link_device *dev __attribute__((unused)), - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t len, const void *bytes) -{ - const uint8_t *b = (const uint8_t *) bytes; - - // Start delimiter "quote" for char arrays (strings) - if (format == DL_FORMAT_ARRAY && type == DL_TYPE_CHAR) { - trans->ivy_p += sprintf(trans->ivy_p, "\""); - } - - int i = 0; - while (i < len) { - // print data with correct type - switch (type) { - case DL_TYPE_CHAR: - trans->ivy_p += sprintf(trans->ivy_p, "%c", (char)(*((char *)(b + i)))); - i++; - break; - case DL_TYPE_UINT8: - trans->ivy_p += sprintf(trans->ivy_p, "%u", b[i]); - i++; - break; - case DL_TYPE_UINT16: - trans->ivy_p += sprintf(trans->ivy_p, "%u", (uint16_t)(*((uint16_t *)(b + i)))); - i += 2; - break; - case DL_TYPE_UINT32: - case DL_TYPE_TIMESTAMP: - trans->ivy_p += sprintf(trans->ivy_p, "%u", (uint32_t)(*((uint32_t *)(b + i)))); - i += 4; - break; - case DL_TYPE_UINT64: -#if __WORDSIZE == 64 - trans->ivy_p += sprintf(trans->ivy_p, "%lu", (uint64_t)(*((uint64_t *)(b + i)))); -#else - trans->ivy_p += sprintf(trans->ivy_p, "%llu", (uint64_t)(*((uint64_t *)(b + i)))); -#endif - i += 8; - break; - case DL_TYPE_INT8: - trans->ivy_p += sprintf(trans->ivy_p, "%d", (int8_t)(*((int8_t *)(b + i)))); - i++; - break; - case DL_TYPE_INT16: - trans->ivy_p += sprintf(trans->ivy_p, "%d", (int16_t)(*((int16_t *)(b + i)))); - i += 2; - break; - case DL_TYPE_INT32: - trans->ivy_p += sprintf(trans->ivy_p, "%d", (int32_t)(*((int32_t *)(b + i)))); - i += 4; - break; - case DL_TYPE_INT64: -#if __WORDSIZE == 64 - trans->ivy_p += sprintf(trans->ivy_p, "%ld", (uint64_t)(*((uint64_t *)(b + i)))); -#else - trans->ivy_p += sprintf(trans->ivy_p, "%lld", (uint64_t)(*((uint64_t *)(b + i)))); -#endif - i += 8; - break; - case DL_TYPE_FLOAT: - trans->ivy_p += sprintf(trans->ivy_p, "%f", (float)(*((float *)(b + i)))); - i += 4; - break; - case DL_TYPE_DOUBLE: - trans->ivy_p += sprintf(trans->ivy_p, "%f", (double)(*((double *)(b + i)))); - i += 8; - break; - case DL_TYPE_ARRAY_LENGTH: - default: - // Don't print array length but increment index - i++; - break; - } - // Coma delimiter for array, no delimiter for char array (string), space otherwise - if (format == DL_FORMAT_ARRAY) { - if (type != DL_TYPE_CHAR) { - trans->ivy_p += sprintf(trans->ivy_p, ","); - } - } else { - trans->ivy_p += sprintf(trans->ivy_p, " "); - } - } - - // space end delimiter for arrays, additionally un-quote char arrays (strings) - if (format == DL_FORMAT_ARRAY) { - if (type == DL_TYPE_CHAR) { - trans->ivy_p += sprintf(trans->ivy_p, "\" "); - } else { - trans->ivy_p += sprintf(trans->ivy_p, " "); - } - } -} - -static void put_named_byte(struct ivy_transport *trans, struct link_device *dev __attribute__((unused)), - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t byte __attribute__((unused)), const char *name __attribute__((unused))) -{ - trans->ivy_p += sprintf(trans->ivy_p, "%s ", name); -} - -static uint8_t size_of(struct ivy_transport *trans __attribute__((unused)), uint8_t len) -{ - return len; -} - -static void start_message(struct ivy_transport *trans, struct link_device *dev __attribute__((unused)), - uint8_t payload_len __attribute__((unused))) -{ - trans->ivy_p = trans->ivy_buf; -} - -static void end_message(struct ivy_transport *trans, struct link_device *dev) -{ - *(--trans->ivy_p) = '\0'; - if (trans->ivy_dl_enabled) { - IvySendMsg("%s", trans->ivy_buf); - dev->nb_msgs++; - } -} - -static void overrun(struct ivy_transport *trans __attribute__((unused)), - struct link_device *dev) -{ - dev->nb_ovrn++; -} - -static void count_bytes(struct ivy_transport *trans __attribute__((unused)), - struct link_device *dev, uint8_t bytes) -{ - dev->nb_bytes += bytes; -} - -static int check_available_space(struct ivy_transport *trans __attribute__((unused)), - struct link_device *dev __attribute__((unused)), uint8_t bytes __attribute__((unused))) -{ - return TRUE; -} - -static int check_free_space(struct ivy_transport *p __attribute__((unused)), uint8_t len __attribute__((unused))) { return TRUE; } -static void transmit(struct ivy_transport *p __attribute__((unused)), uint8_t byte __attribute__((unused))) {} -static void send_message(struct ivy_transport *p __attribute__((unused))) {} -static int null_function(struct ivy_transport *p __attribute__((unused))) { return 0; } - -void ivy_transport_init(void) -{ - ivy_tp.ivy_p = ivy_tp.ivy_buf; - ivy_tp.ivy_dl_enabled = TRUE; - - ivy_tp.trans_tx.size_of = (size_of_t) size_of; - ivy_tp.trans_tx.check_available_space = (check_available_space_t) check_available_space; - ivy_tp.trans_tx.put_bytes = (put_bytes_t) put_bytes; - ivy_tp.trans_tx.put_named_byte = (put_named_byte_t) put_named_byte; - ivy_tp.trans_tx.start_message = (start_message_t) start_message; - ivy_tp.trans_tx.end_message = (end_message_t) end_message; - ivy_tp.trans_tx.overrun = (overrun_t) overrun; - ivy_tp.trans_tx.count_bytes = (count_bytes_t) count_bytes; - ivy_tp.trans_tx.impl = (void *)(&ivy_tp); - ivy_tp.device.check_free_space = (check_free_space_t) check_free_space; - ivy_tp.device.put_byte = (put_byte_t) transmit; - ivy_tp.device.send_message = (send_message_t) send_message; - ivy_tp.device.char_available = (char_available_t) null_function; - ivy_tp.device.get_byte = (get_byte_t) null_function; - ivy_tp.device.periph = (void *)(&ivy_tp); -} diff --git a/sw/airborne/subsystems/datalink/ivy_transport.h b/sw/airborne/subsystems/datalink/ivy_transport.h deleted file mode 100644 index cc1dd7be8f..0000000000 --- a/sw/airborne/subsystems/datalink/ivy_transport.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * Copyright (C) 2003 Pascal Brisset, Antoine Drouin - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/ivy_transport.h - * - * Building Paparazzi frames over IVY. - * - */ - -#ifndef IVY_TRANSPORT_H -#define IVY_TRANSPORT_H - -#include "subsystems/datalink/transport.h" -#include "mcu_periph/link_device.h" - -// IVY transport -struct ivy_transport { - char ivy_buf[256]; - char *ivy_p; - int ivy_dl_enabled; - // generic transmission interface - struct transport_tx trans_tx; - // generic (dummy) device - struct link_device device; -}; - -extern struct ivy_transport ivy_tp; - -// Init function -extern void ivy_transport_init(void); - -#endif // IVY_TRANSPORT_H - diff --git a/sw/airborne/subsystems/datalink/pprz_transport.c b/sw/airborne/subsystems/datalink/pprz_transport.c deleted file mode 100644 index dc6b7f91bc..0000000000 --- a/sw/airborne/subsystems/datalink/pprz_transport.c +++ /dev/null @@ -1,131 +0,0 @@ -/* - * Copyright (C) 2006 Pascal Brisset, Antoine Drouin - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/pprz_transport.c - * - * Building and parsing Paparazzi frames. - * - * Pprz frame: - * - * |STX|length|... payload=(length-4) bytes ...|Checksum A|Checksum B| - * - * where checksum is computed over length and payload: - * @code - * ck_A = ck_B = length - * for each byte b in payload - * ck_A += b; - * ck_b += ck_A; - * @endcode - */ - -#include -#include "subsystems/datalink/downlink.h" -#ifndef PPRZ_DATALINK_EXPORT -#include "subsystems/datalink/pprz_transport.h" -#else /* PPRZ_DATALINK_EXPORT defined */ -#include "pprz_transport.h" -#endif - -struct pprz_transport pprz_tp; - -static void put_1byte(struct pprz_transport *trans, struct link_device *dev, const uint8_t byte) -{ - trans->ck_a_tx += byte; - trans->ck_b_tx += trans->ck_a_tx; - dev->put_byte(dev->periph, byte); -} - -static void put_bytes(struct pprz_transport *trans, struct link_device *dev, - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t len, const void *bytes) -{ - const uint8_t *b = (const uint8_t *) bytes; - int i; - for (i = 0; i < len; i++) { - put_1byte(trans, dev, b[i]); - } -} - -static void put_named_byte(struct pprz_transport *trans, struct link_device *dev, - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t byte, const char *name __attribute__((unused))) -{ - put_1byte(trans, dev, byte); -} - -static uint8_t size_of(struct pprz_transport *trans __attribute__((unused)), uint8_t len) -{ - // message length: payload + protocol overhead (STX + len + ck_a + ck_b = 4) - return len + 4; -} - -static void start_message(struct pprz_transport *trans, struct link_device *dev, uint8_t payload_len) -{ - dev->put_byte(dev->periph, STX); - const uint8_t msg_len = size_of(trans, payload_len); - dev->put_byte(dev->periph, msg_len); - trans->ck_a_tx = msg_len; - trans->ck_b_tx = msg_len; - dev->nb_msgs++; -} - -static void end_message(struct pprz_transport *trans, struct link_device *dev) -{ - dev->put_byte(dev->periph, trans->ck_a_tx); - dev->put_byte(dev->periph, trans->ck_b_tx); - dev->send_message(dev->periph); -} - -static void overrun(struct pprz_transport *trans __attribute__((unused)), - struct link_device *dev) -{ - dev->nb_ovrn++; -} - -static void count_bytes(struct pprz_transport *trans __attribute__((unused)), - struct link_device *dev, uint8_t bytes) -{ - dev->nb_bytes += bytes; -} - -static int check_available_space(struct pprz_transport *trans __attribute__((unused)), struct link_device *dev, - uint8_t bytes) -{ - return dev->check_free_space(dev->periph, bytes); -} - -void pprz_transport_init(struct pprz_transport *t) -{ - t->status = UNINIT; - t->trans_rx.msg_received = FALSE; - t->trans_tx.size_of = (size_of_t) size_of; - t->trans_tx.check_available_space = (check_available_space_t) check_available_space; - t->trans_tx.put_bytes = (put_bytes_t) put_bytes; - t->trans_tx.put_named_byte = (put_named_byte_t) put_named_byte; - t->trans_tx.start_message = (start_message_t) start_message; - t->trans_tx.end_message = (end_message_t) end_message; - t->trans_tx.overrun = (overrun_t) overrun; - t->trans_tx.count_bytes = (count_bytes_t) count_bytes; - t->trans_tx.impl = (void *)(t); -} - diff --git a/sw/airborne/subsystems/datalink/pprz_transport.h b/sw/airborne/subsystems/datalink/pprz_transport.h deleted file mode 100644 index 1ddb9f7724..0000000000 --- a/sw/airborne/subsystems/datalink/pprz_transport.h +++ /dev/null @@ -1,159 +0,0 @@ -/* - * Copyright (C) 2003 Pascal Brisset, Antoine Drouin - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/pprz_transport.h - * - * Building and parsing Paparazzi frames. - * - * Pprz frame: - * - * |STX|length|... payload=(length-4) bytes ...|Checksum A|Checksum B| - * - * where checksum is computed over length and payload: - * @code - * ck_A = ck_B = length - * for each byte b in payload - * ck_A += b; - * ck_b += ck_A; - * @endcode - */ - -#ifndef PPRZ_TRANSPORT_H -#define PPRZ_TRANSPORT_H - -#include -#include "std.h" -#ifndef PPRZ_DATALINK_EXPORT -#include "subsystems/datalink/datalink.h" -#include "subsystems/datalink/transport.h" -#else /* PPRZ_DATALINK_EXPORT defined */ -#include "datalink.h" -#include "transport.h" -#endif - -/* PPRZ Transport - */ - -#define STX 0x99 - -// PPRZ parsing state machine -#define UNINIT 0 -#define GOT_STX 1 -#define GOT_LENGTH 2 -#define GOT_PAYLOAD 3 -#define GOT_CRC1 4 - -struct pprz_transport { - // generic reception interface - struct transport_rx trans_rx; - // specific pprz transport_rx variables - uint8_t status; - uint8_t payload_idx; - uint8_t ck_a_rx, ck_b_rx; - // generic transmission interface - struct transport_tx trans_tx; - // specific pprz transport_tx variables - uint8_t ck_a_tx, ck_b_tx; -}; - -extern struct pprz_transport pprz_tp; - -// Init function -extern void pprz_transport_init(struct pprz_transport *t); - -static inline void parse_pprz(struct pprz_transport *t, uint8_t c) -{ - switch (t->status) { - case UNINIT: - if (c == STX) { - t->status++; - } - break; - case GOT_STX: - if (t->trans_rx.msg_received) { - t->trans_rx.ovrn++; - goto error; - } - t->trans_rx.payload_len = c - 4; /* Counting STX, LENGTH and CRC1 and CRC2 */ - t->ck_a_rx = t->ck_b_rx = c; - t->status++; - t->payload_idx = 0; - break; - case GOT_LENGTH: - t->trans_rx.payload[t->payload_idx] = c; - t->ck_a_rx += c; t->ck_b_rx += t->ck_a_rx; - t->payload_idx++; - if (t->payload_idx == t->trans_rx.payload_len) { - t->status++; - } - break; - case GOT_PAYLOAD: - if (c != t->ck_a_rx) { - goto error; - } - t->status++; - break; - case GOT_CRC1: - if (c != t->ck_b_rx) { - goto error; - } - t->trans_rx.msg_received = TRUE; - goto restart; - default: - goto error; - } - return; -error: - t->trans_rx.error++; -restart: - t->status = UNINIT; - return; -} - -static inline void pprz_parse_payload(struct pprz_transport *t) -{ - uint8_t i; - for (i = 0; i < t->trans_rx.payload_len; i++) { - dl_buffer[i] = t->trans_rx.payload[i]; - } - dl_msg_available = TRUE; -} - - -#define PprzCheckAndParse(_dev, _trans) pprz_check_and_parse(&(_dev).device, &(_trans)) - -static inline void pprz_check_and_parse(struct link_device *dev, struct pprz_transport *trans) -{ - if (dev->char_available(dev->periph)) { - while (dev->char_available(dev->periph) && !trans->trans_rx.msg_received) { - parse_pprz(trans, dev->get_byte(dev->periph)); - } - if (trans->trans_rx.msg_received) { - pprz_parse_payload(trans); - trans->trans_rx.msg_received = FALSE; - } - } -} - -#endif /* PPRZ_TRANSPORT_H */ - diff --git a/sw/airborne/subsystems/datalink/pprzlog_transport.c b/sw/airborne/subsystems/datalink/pprzlog_transport.c deleted file mode 100644 index 0a47cdff2c..0000000000 --- a/sw/airborne/subsystems/datalink/pprzlog_transport.c +++ /dev/null @@ -1,125 +0,0 @@ -/* - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/pprzlog_transport.c - * - * Building and Paparazzi frames with timestamp for data logger. - * - * LOG-message: ABCDEFGHxxxxxxxI - * A PPRZ_STX (0x99) - * B LENGTH (H->H) - * C SOURCE (0=uart0, 1=uart1, 2=i2c0, ...) - * D TIMESTAMP_LSB (100 microsec raster) - * E TIMESTAMP - * F TIMESTAMP - * G TIMESTAMP_MSB - * H PPRZ_DATA - * 0 SENDER_ID - * 1 MSG_ID - * 2 MSG_PAYLOAD - * . DATA (messages.xml) - * I CHECKSUM (sum[B->H]) - * - */ - -#include -#include "subsystems/datalink/pprzlog_transport.h" - -struct pprzlog_transport pprzlog_tp; - -#define STX_LOG 0x99 - -static void put_1byte(struct pprzlog_transport *trans, struct link_device *dev, const uint8_t byte) -{ - trans->ck += byte; - dev->put_byte(dev->periph, byte); -} - -static void put_bytes(struct pprzlog_transport *trans, struct link_device *dev, - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t len, const void *bytes) -{ - const uint8_t *b = (const uint8_t *) bytes; - int i; - for (i = 0; i < len; i++) { - put_1byte(trans, dev, b[i]); - } -} - -static void put_named_byte(struct pprzlog_transport *trans, struct link_device *dev, - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t byte, const char *name __attribute__((unused))) -{ - put_1byte(trans, dev, byte); -} - -static uint8_t size_of(struct pprzlog_transport *trans __attribute__((unused)), uint8_t len) -{ - return len; -} - -static void start_message(struct pprzlog_transport *trans, struct link_device *dev, uint8_t payload_len) -{ - dev->put_byte(dev->periph, STX_LOG); - const uint8_t msg_len = size_of(trans, payload_len); - trans->ck = 0; - put_1byte(trans, dev, msg_len); - put_1byte(trans, dev, 0); // TODO use correct source ID - uint32_t ts = get_sys_time_usec() / 100; - put_bytes(trans, dev, DL_TYPE_TIMESTAMP, DL_FORMAT_SCALAR, 4, (uint8_t *)(&ts)); -} - -static void end_message(struct pprzlog_transport *trans, struct link_device *dev) -{ - dev->put_byte(dev->periph, trans->ck); - dev->send_message(dev->periph); -} - -static void overrun(struct pprzlog_transport *trans __attribute__((unused)), - struct link_device *dev __attribute__((unused))) -{ -} - -static void count_bytes(struct pprzlog_transport *trans __attribute__((unused)), - struct link_device *dev __attribute__((unused)), uint8_t bytes __attribute__((unused))) -{ -} - -static int check_available_space(struct pprzlog_transport *trans __attribute__((unused)), struct link_device *dev, - uint8_t bytes) -{ - return dev->check_free_space(dev->periph, bytes); -} - -void pprzlog_transport_init(void) -{ - pprzlog_tp.trans_tx.size_of = (size_of_t) size_of; - pprzlog_tp.trans_tx.check_available_space = (check_available_space_t) check_available_space; - pprzlog_tp.trans_tx.put_bytes = (put_bytes_t) put_bytes; - pprzlog_tp.trans_tx.put_named_byte = (put_named_byte_t) put_named_byte; - pprzlog_tp.trans_tx.start_message = (start_message_t) start_message; - pprzlog_tp.trans_tx.end_message = (end_message_t) end_message; - pprzlog_tp.trans_tx.overrun = (overrun_t) overrun; - pprzlog_tp.trans_tx.count_bytes = (count_bytes_t) count_bytes; - pprzlog_tp.trans_tx.impl = (void *)(&pprzlog_tp); -} - diff --git a/sw/airborne/subsystems/datalink/pprzlog_transport.h b/sw/airborne/subsystems/datalink/pprzlog_transport.h deleted file mode 100644 index 31e85c1328..0000000000 --- a/sw/airborne/subsystems/datalink/pprzlog_transport.h +++ /dev/null @@ -1,48 +0,0 @@ -/* - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/pprzlog_transport.h - * - * Protocol for on-board data logger with timestamp - * - */ - -#ifndef PPRZLOG_TRANSPORT_H -#define PPRZLOG_TRANSPORT_H - -#include "mcu_periph/sys_time.h" -#include "subsystems/datalink/transport.h" - -struct pprzlog_transport { - // generic transmission interface - struct transport_tx trans_tx; - // specific pprz transport_tx variables - uint8_t ck; -}; - -extern struct pprzlog_transport pprzlog_tp; - -// Init function -extern void pprzlog_transport_init(void); - -#endif - diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index fd99e325a4..9d194a6497 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -29,9 +29,9 @@ #include "mcu_periph/gpio.h" #include "peripherals/cyrf6936.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #include "subsystems/datalink/datalink.h" -#include "subsystems/datalink/pprz_transport.h" +#include "pprzlink/pprz_transport.h" /* The timings in microseconds */ #define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ diff --git a/sw/airborne/subsystems/datalink/telemetry_common.h b/sw/airborne/subsystems/datalink/telemetry_common.h index ce0d1aba1a..3b6a01189e 100644 --- a/sw/airborne/subsystems/datalink/telemetry_common.h +++ b/sw/airborne/subsystems/datalink/telemetry_common.h @@ -31,9 +31,9 @@ #include #include "std.h" -#include "mcu_periph/link_device.h" -#include "subsystems/datalink/transport.h" -#include "messages.h" +#include "pprzlink/pprzlink_device.h" +#include "pprzlink/pprzlink_transport.h" +#include "pprzlink/messages.h" /** Telemetry callback definition */ diff --git a/sw/airborne/subsystems/datalink/transport.h b/sw/airborne/subsystems/datalink/transport.h deleted file mode 100644 index a1701954a2..0000000000 --- a/sw/airborne/subsystems/datalink/transport.h +++ /dev/null @@ -1,102 +0,0 @@ -/* - * Copyright (C) 2011-2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** \file subsystems/datalink/transport.h - * generic transport header - */ - -#ifndef TRANSPORT_H -#define TRANSPORT_H - -#include -#include "mcu_periph/link_device.h" -#include "std.h" - -#ifndef TRANSPORT_PAYLOAD_LEN -#define TRANSPORT_PAYLOAD_LEN 256 -#endif - -/** Generic reception transport header - */ -struct transport_rx { - uint8_t payload[TRANSPORT_PAYLOAD_LEN]; ///< payload buffer - volatile uint8_t payload_len; ///< payload buffer length - volatile bool_t msg_received; ///< message received flag - uint8_t ovrn, error; ///< overrun and error flags -}; - -/** Data type - */ -enum TransportDataType { - DL_TYPE_ARRAY_LENGTH, - DL_TYPE_CHAR, - DL_TYPE_UINT8, - DL_TYPE_INT8, - DL_TYPE_UINT16, - DL_TYPE_INT16, - DL_TYPE_UINT32, - DL_TYPE_INT32, - DL_TYPE_UINT64, - DL_TYPE_INT64, - DL_TYPE_FLOAT, - DL_TYPE_DOUBLE, - DL_TYPE_TIMESTAMP -}; - -/** Data format (scalar or array) - */ -enum TransportDataFormat { - DL_FORMAT_SCALAR, - DL_FORMAT_ARRAY -}; - -/** Function pointers definition - * - * they are used to cast the real functions with the correct type - * to store in the transport structure - */ -typedef uint8_t (*size_of_t)(void *, uint8_t); -typedef int (*check_available_space_t)(void *, struct link_device *, uint8_t); -typedef void (*put_bytes_t)(void *, struct link_device *, enum TransportDataType, enum TransportDataFormat, uint8_t, - const void *); -typedef void (*put_named_byte_t)(void *, struct link_device *, enum TransportDataType, enum TransportDataFormat, - uint8_t, const char *); -typedef void (*start_message_t)(void *, struct link_device *, uint8_t); -typedef void (*end_message_t)(void *, struct link_device *); -typedef void (*overrun_t)(void *, struct link_device *); -typedef void (*count_bytes_t)(void *, struct link_device *, uint8_t); - -/** Generic transmission transport header - */ -struct transport_tx { - size_of_t size_of; ///< get size of payload with transport header and trailer - check_available_space_t check_available_space; ///< check if transmit buffer is not full - put_bytes_t put_bytes; ///< send bytes - put_named_byte_t put_named_byte; ///< send a single byte or its name - start_message_t start_message; ///< transport header - end_message_t end_message; ///< transport trailer - overrun_t overrun; ///< overrun - count_bytes_t count_bytes; ///< count bytes to send - void *impl; ///< pointer to parent implementation -}; - -#endif /* TRANSPORT_H */ - diff --git a/sw/airborne/subsystems/datalink/uart_print.h b/sw/airborne/subsystems/datalink/uart_print.h index 97f16513dd..23ba84823f 100644 --- a/sw/airborne/subsystems/datalink/uart_print.h +++ b/sw/airborne/subsystems/datalink/uart_print.h @@ -25,7 +25,7 @@ #include "mcu_periph/uart.h" #include "mcu_periph/usb_serial.h" -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #define _PrintString(out_fun, s) { \ uint8_t i = 0; \ diff --git a/sw/airborne/subsystems/datalink/w5100.h b/sw/airborne/subsystems/datalink/w5100.h index e5b3cbc87d..c98ad9cbea 100644 --- a/sw/airborne/subsystems/datalink/w5100.h +++ b/sw/airborne/subsystems/datalink/w5100.h @@ -28,7 +28,7 @@ #ifndef W5100_H #define W5100_H -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #include "generated/airframe.h" #define W5100_RX_BUFFER_SIZE 80 @@ -74,7 +74,7 @@ bool_t w5100_ch_available(void); // W5100 is using pprz_transport // FIXME it should not appear here, this will be fixed with the rx improvements some day... // W5100 needs a specific read_buffer function -#include "subsystems/datalink/pprz_transport.h" +#include "pprzlink/pprz_transport.h" static inline void w5100_read_buffer(struct pprz_transport *t) { diff --git a/sw/airborne/subsystems/datalink/xbee.c b/sw/airborne/subsystems/datalink/xbee.c deleted file mode 100644 index 66aae3e0d4..0000000000 --- a/sw/airborne/subsystems/datalink/xbee.c +++ /dev/null @@ -1,230 +0,0 @@ -/* - * Copyright (C) 2006 Pascal Brisset, Antoine Drouin - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/xbee.c - * Maxstream XBee serial input and output - */ - -#include "mcu_periph/sys_time.h" -#include "subsystems/datalink/uart_print.h" -#include "subsystems/datalink/xbee.h" -#include "subsystems/datalink/downlink.h" - -/** Ground station address */ -#define GROUND_STATION_ADDR 0x100 -/** Aircraft address */ -#define XBEE_MY_ADDR AC_ID - -/** Constants for the API protocol */ -#define TX_OPTIONS 0x00 -#define NO_FRAME_ID 0 -#define XBEE_API_OVERHEAD 5 /* start + len_msb + len_lsb + API_id + checksum */ - -struct xbee_transport xbee_tp; - -#define AT_COMMAND_SEQUENCE "+++" -#define AT_SET_MY "ATMY" -#define AT_AP_MODE "ATAP1\r" -#define AT_EXIT "ATCN\r" - -/** Xbee protocol implementation */ - -static void put_1byte(struct xbee_transport *trans, struct link_device *dev, const uint8_t byte) -{ - trans->cs_tx += byte; - dev->put_byte(dev->periph, byte); -} - -static void put_bytes(struct xbee_transport *trans, struct link_device *dev, - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t len, const void *bytes) -{ - const uint8_t *b = (const uint8_t *) bytes; - int i; - for (i = 0; i < len; i++) { - put_1byte(trans, dev, b[i]); - } -} - -static void put_named_byte(struct xbee_transport *trans, struct link_device *dev, - enum TransportDataType type __attribute__((unused)), enum TransportDataFormat format __attribute__((unused)), - uint8_t byte, const char *name __attribute__((unused))) -{ - put_1byte(trans, dev, byte); -} - -static uint8_t size_of(struct xbee_transport *trans __attribute__((unused)), uint8_t len) -{ - // message length: payload + API overhead + XBEE TX overhead (868 or 2.4) - return len + XBEE_API_OVERHEAD + XBEE_TX_OVERHEAD; -} - -static void start_message(struct xbee_transport *trans, struct link_device *dev, uint8_t payload_len) -{ - dev->put_byte(dev->periph, XBEE_START); - const uint16_t len = payload_len + XBEE_API_OVERHEAD; - dev->put_byte(dev->periph, (len >> 8)); - dev->put_byte(dev->periph, (len & 0xff)); - trans->cs_tx = 0; - const uint8_t header[] = XBEE_TX_HEADER; - put_bytes(trans, dev, DL_TYPE_UINT8, DL_FORMAT_SCALAR, XBEE_TX_OVERHEAD + 1, header); - dev->nb_msgs++; -} - -static void end_message(struct xbee_transport *trans, struct link_device *dev) -{ - trans->cs_tx = 0xff - trans->cs_tx; - dev->put_byte(dev->periph, trans->cs_tx); - dev->send_message(dev->periph); -} - -static void overrun(struct xbee_transport *trans __attribute__((unused)), - struct link_device *dev) -{ - dev->nb_ovrn++; -} - -static void count_bytes(struct xbee_transport *trans __attribute__((unused)), - struct link_device *dev, uint8_t bytes) -{ - dev->nb_bytes += bytes; -} - -static int check_available_space(struct xbee_transport *trans __attribute__((unused)), struct link_device *dev, - uint8_t bytes) -{ - return dev->check_free_space(dev->periph, bytes); -} - -static uint8_t xbee_text_reply_is_ok(struct link_device *dev) -{ - char c[2]; - int count = 0; - - while (dev->char_available(dev->periph)) { - char cc = dev->get_byte(dev->periph); - if (count < 2) { - c[count] = cc; - } - count++; - } - - if ((count > 2) && (c[0] == 'O') && (c[1] == 'K')) { - return TRUE; - } - - return FALSE; -} - -static uint8_t xbee_try_to_enter_api(struct link_device *dev) -{ - - /** Switching to AT mode (FIXME: busy waiting) */ - print_string(dev, AT_COMMAND_SEQUENCE); - - /** - busy wait 1.25s */ - sys_time_usleep(1250000); - - return xbee_text_reply_is_ok(dev); -} - - -#if XBEE_BAUD == B9600 -#define XBEE_BAUD_ALTERNATE B57600 -#define XBEE_ATBD_CODE "ATBD3\rATWR\r" -#pragma message "Experimental: XBEE-API@9k6 auto-baudrate 57k6 -> 9k6 (stop ground link for correct operation)" -#elif XBEE_BAUD == B57600 -#define XBEE_BAUD_ALTERNATE B9600 -#define XBEE_ATBD_CODE "ATBD6\rATWR\r" -#pragma message "Experimental: XBEE-API@57k6 auto-baudrate 9k6 -> 57k6 (stop ground link for correct operation)" -#else -#pragma message "XBEE-API Non default baudrate: auto-baud disabled." -#endif - - -void xbee_init(void) -{ - xbee_tp.status = XBEE_UNINIT; - xbee_tp.trans_rx.msg_received = FALSE; - xbee_tp.trans_tx.size_of = (size_of_t) size_of; - xbee_tp.trans_tx.check_available_space = (check_available_space_t) check_available_space; - xbee_tp.trans_tx.put_bytes = (put_bytes_t) put_bytes; - xbee_tp.trans_tx.put_named_byte = (put_named_byte_t) put_named_byte; - xbee_tp.trans_tx.start_message = (start_message_t) start_message; - xbee_tp.trans_tx.end_message = (end_message_t) end_message; - xbee_tp.trans_tx.overrun = (overrun_t) overrun; - xbee_tp.trans_tx.count_bytes = (count_bytes_t) count_bytes; - xbee_tp.trans_tx.impl = (void *)(&xbee_tp); - - struct link_device *dev = &((XBEE_UART).device); - - // Empty buffer before init process - while (dev->char_available(dev->periph)) { - dev->get_byte(dev->periph); - } - -#ifndef NO_XBEE_API_INIT - /** - busy wait 1.25s */ - sys_time_usleep(1250000); - - if (! xbee_try_to_enter_api(dev)) { -#ifdef XBEE_BAUD_ALTERNATE - - // Badly configured... try the alternate baudrate: - uart_periph_set_baudrate(&(XBEE_UART), - XBEE_BAUD_ALTERNATE); // FIXME add set_baudrate to generic device, assuming uart for now - if (xbee_try_to_enter_api(dev)) { - // The alternate baudrate worked, - print_string(dev, XBEE_ATBD_CODE); - } else { - // Complete failure, none of the 2 baudrates result in any reply - // TODO: set LED? - - // Set the default baudrate, just in case everything is right - uart_periph_set_baudrate(&(XBEE_UART), XBEE_BAUD); // FIXME add set_baudrate to generic device, assuming uart for now - print_string(dev, "\r"); - } - -#endif - // Continue changing settings until the EXIT is issued. - } - - /** Setting my address */ - print_string(dev, AT_SET_MY); - uint16_t addr = XBEE_MY_ADDR; - print_hex16(dev, addr); - print_string(dev, "\r"); - - print_string(dev, AT_AP_MODE); - -#ifdef XBEE_INIT - print_string(dev, XBEE_INIT); -#endif - - /** Switching back to normal mode */ - print_string(dev, AT_EXIT); - - uart_periph_set_baudrate(&(XBEE_UART), XBEE_BAUD); // FIXME add set_baudrate to generic device, assuming uart for now - -#endif -} diff --git a/sw/airborne/subsystems/datalink/xbee.h b/sw/airborne/subsystems/datalink/xbee.h deleted file mode 100644 index 7b35568b40..0000000000 --- a/sw/airborne/subsystems/datalink/xbee.h +++ /dev/null @@ -1,152 +0,0 @@ -/* - * Copyright (C) 2006 Pascal Brisset, Antoine Drouin - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/xbee.h - * Maxstream XBee serial input and output - */ - -#ifndef XBEE_H -#define XBEE_H - -#include "subsystems/datalink/datalink.h" -#include "generated/airframe.h" -#include "subsystems/datalink/transport.h" - -#ifdef XBEE868 -#include "subsystems/datalink/xbee868.h" -#else /* Not 868 */ -#include "subsystems/datalink/xbee24.h" -#endif - -#define XBEE_START 0x7e - -/** Initialisation in API mode and setting of the local address - * FIXME: busy wait */ -void xbee_init(void); - -/** Status of the API packet receiver automata */ -#define XBEE_UNINIT 0 -#define XBEE_GOT_START 1 -#define XBEE_GOT_LENGTH_MSB 2 -#define XBEE_GOT_LENGTH_LSB 3 -#define XBEE_GOT_PAYLOAD 4 - -struct xbee_transport { - // generic reception interface - struct transport_rx trans_rx; - // specific xbee transport variables - uint8_t status; - uint8_t payload_idx; - uint8_t cs_rx; - uint8_t rssi; - // generic transmission interface - struct transport_tx trans_tx; - // specific pprz transport_tx variables - uint8_t cs_tx; -}; - -extern struct xbee_transport xbee_tp; - -/** Parsing a XBee API frame */ -static inline void parse_xbee(struct xbee_transport *t, uint8_t c) -{ - switch (t->status) { - case XBEE_UNINIT: - if (c == XBEE_START) { - t->status++; - } - break; - case XBEE_GOT_START: - if (t->trans_rx.msg_received) { - t->trans_rx.ovrn++; - goto error; - } - t->trans_rx.payload_len = c << 8; - t->status++; - break; - case XBEE_GOT_LENGTH_MSB: - t->trans_rx.payload_len |= c; - t->status++; - t->payload_idx = 0; - t->cs_rx = 0; - break; - case XBEE_GOT_LENGTH_LSB: - t->trans_rx.payload[t->payload_idx] = c; - t->cs_rx += c; - t->payload_idx++; - if (t->payload_idx == t->trans_rx.payload_len) { - t->status++; - } - break; - case XBEE_GOT_PAYLOAD: - if (c + t->cs_rx != 0xff) { - goto error; - } - t->trans_rx.msg_received = TRUE; - goto restart; - break; - default: - goto error; - } - return; -error: - t->trans_rx.error++; -restart: - t->status = XBEE_UNINIT; - return; -} - -/** Parsing a frame data and copy the payload to the datalink buffer */ -static inline void xbee_parse_payload(struct xbee_transport *t) -{ - switch (t->trans_rx.payload[0]) { - case XBEE_RX_ID: - case XBEE_TX_ID: /* Useful if A/C is connected to the PC with a cable */ - XbeeGetRSSI(t->trans_rx.payload); - uint8_t i; - for (i = XBEE_RFDATA_OFFSET; i < t->trans_rx.payload_len; i++) { - dl_buffer[i - XBEE_RFDATA_OFFSET] = t->trans_rx.payload[i]; - } - dl_msg_available = TRUE; - break; - default: - return; - } -} - -#define XBeeCheckAndParse(_dev, _trans) xbee_check_and_parse(&(_dev).device, &(_trans)) - -static inline void xbee_check_and_parse(struct link_device *dev, struct xbee_transport *trans) -{ - if (dev->char_available(dev->periph)) { - while (dev->char_available(dev->periph) && !trans->trans_rx.msg_received) { - parse_xbee(trans, dev->get_byte(dev->periph)); - } - if (trans->trans_rx.msg_received) { - xbee_parse_payload(trans); - trans->trans_rx.msg_received = FALSE; - } - } -} - -#endif /* XBEE_H */ diff --git a/sw/airborne/subsystems/datalink/xbee24.h b/sw/airborne/subsystems/datalink/xbee24.h deleted file mode 100644 index dbe947f5b6..0000000000 --- a/sw/airborne/subsystems/datalink/xbee24.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * Copyright (C) 2009 ENAC, Pascal Brisset - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/xbee24.h - * Configuration for 2.4GHz "series 1" and 900MHz modules - */ - -#ifndef XBEE24_H -#define XBEE24_H - -#define XBEE_TX_ID 0x01 /* 16 bits address */ -#define XBEE_RX_ID 0x81 /* 16 bits address */ -#define XBEE_RFDATA_OFFSET 5 - -#define XBEE_TX_OVERHEAD 4 -#define XBEE_TX_HEADER { \ - XBEE_TX_ID, \ - NO_FRAME_ID, \ - (GROUND_STATION_ADDR >> 8), \ - (GROUND_STATION_ADDR & 0xff), \ - TX_OPTIONS \ - } - -#define XbeeGetRSSI(_payload) { xbee_tp.rssi = _payload[3]; } - -#endif // XBEE24_H diff --git a/sw/airborne/subsystems/datalink/xbee868.h b/sw/airborne/subsystems/datalink/xbee868.h deleted file mode 100644 index d77ef559c0..0000000000 --- a/sw/airborne/subsystems/datalink/xbee868.h +++ /dev/null @@ -1,55 +0,0 @@ -/* - * Copyright (C) 2009 ENAC, Pascal Brisset - * Copyright (C) 2014 Gautier Hattenberger - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, see - * . - * - */ - -/** - * @file subsystems/datalink/xbee868.h - * Configuration for 868MHz modules - */ - -#ifndef XBEE868_H -#define XBEE868_H - -#define XBEE_TX_ID 0x10 -#define XBEE_RX_ID 0x90 -#define XBEE_RFDATA_OFFSET 12 - -#define XBEE_TX_OVERHEAD 13 -#define XBEE_TX_HEADER { \ - XBEE_TX_ID, \ - NO_FRAME_ID, \ - 0x00, \ - 0x00, \ - 0x00, \ - 0x00, \ - 0x00, \ - 0x00, \ - (GROUND_STATION_ADDR >> 8), \ - (GROUND_STATION_ADDR & 0xff), \ - 0xff, \ - 0xfe, \ - 0x00, \ - TX_OPTIONS \ - } - -#define XbeeGetRSSI(_payload) {} - -#endif // XBEE868_H diff --git a/sw/airborne/subsystems/gps/gps_mtk.c b/sw/airborne/subsystems/gps/gps_mtk.c index 1ff03545d6..d5b35dc5bf 100644 --- a/sw/airborne/subsystems/gps/gps_mtk.c +++ b/sw/airborne/subsystems/gps/gps_mtk.c @@ -397,7 +397,7 @@ restart: */ #ifdef GPS_CONFIGURE -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" static void MtkSend_CFG(char *dat) { diff --git a/sw/airborne/subsystems/gps/gps_mtk.h b/sw/airborne/subsystems/gps/gps_mtk.h index dd78486d42..26163c94b4 100644 --- a/sw/airborne/subsystems/gps/gps_mtk.h +++ b/sw/airborne/subsystems/gps/gps_mtk.h @@ -54,7 +54,7 @@ extern struct GpsMtk gps_mtk; /* * This part is used by the autopilot to read data from a uart */ -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #ifdef GPS_CONFIGURE extern bool_t gps_configuring; diff --git a/sw/airborne/subsystems/gps/gps_nmea.h b/sw/airborne/subsystems/gps/gps_nmea.h index 34426d3b70..9e9003a558 100644 --- a/sw/airborne/subsystems/gps/gps_nmea.h +++ b/sw/airborne/subsystems/gps/gps_nmea.h @@ -55,7 +55,7 @@ extern struct GpsNmea gps_nmea; */ /** The function to be called when a characted from the device is available */ -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" extern void nmea_configure(void); extern void nmea_parse_char(uint8_t c); diff --git a/sw/airborne/subsystems/gps/gps_sirf.h b/sw/airborne/subsystems/gps/gps_sirf.h index 575ff5fd7a..d8929120e9 100644 --- a/sw/airborne/subsystems/gps/gps_sirf.h +++ b/sw/airborne/subsystems/gps/gps_sirf.h @@ -127,7 +127,7 @@ struct sirf_msg_41 { /* * This part is used by the autopilot to read data from a uart */ -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" #include "mcu_periph/uart.h" extern void sirf_parse_char(uint8_t c); diff --git a/sw/airborne/subsystems/gps/gps_skytraq.h b/sw/airborne/subsystems/gps/gps_skytraq.h index 5895cf58e4..8e51e2da13 100644 --- a/sw/airborne/subsystems/gps/gps_skytraq.h +++ b/sw/airborne/subsystems/gps/gps_skytraq.h @@ -58,7 +58,7 @@ extern struct GpsSkytraq gps_skytraq; /* * This part is used by the autopilot to read data from a uart */ -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" extern void gps_skytraq_read_message(void); extern void gps_skytraq_parse(uint8_t c); diff --git a/sw/airborne/subsystems/gps/gps_ubx.h b/sw/airborne/subsystems/gps/gps_ubx.h index 8be5296f00..27cc9a8ea2 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.h +++ b/sw/airborne/subsystems/gps/gps_ubx.h @@ -80,7 +80,7 @@ extern struct GpsUbxRaw gps_ubx_raw; /* * This part is used by the autopilot to read data from a uart */ -#include "mcu_periph/link_device.h" +#include "pprzlink/pprzlink_device.h" extern void ubx_header(struct link_device *dev, uint8_t nav_id, uint8_t msg_id, uint16_t len); extern void ubx_trailer(struct link_device *dev); diff --git a/sw/airborne/subsystems/ins/vf_extended_float.c b/sw/airborne/subsystems/ins/vf_extended_float.c index efc600c159..bcc271d3f2 100644 --- a/sw/airborne/subsystems/ins/vf_extended_float.c +++ b/sw/airborne/subsystems/ins/vf_extended_float.c @@ -43,7 +43,7 @@ PRINT_CONFIG_VAR(DEBUG_VFF_EXTENDED) #if DEBUG_VFF_EXTENDED #include "mcu_periph/uart.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #endif diff --git a/sw/airborne/subsystems/intermcu/intermcu_ap.c b/sw/airborne/subsystems/intermcu/intermcu_ap.c index 59b83ea1b5..68a9161674 100644 --- a/sw/airborne/subsystems/intermcu/intermcu_ap.c +++ b/sw/airborne/subsystems/intermcu/intermcu_ap.c @@ -27,7 +27,7 @@ #include "intermcu_ap.h" #include "intermcu_msg.h" #include "subsystems/radio_control.h" -#include "subsystems/datalink/pprz_transport.h" +#include "pprzlink/pprz_transport.h" #include "mcu_periph/uart.h" #if COMMANDS_NB > 8 diff --git a/sw/airborne/subsystems/intermcu/intermcu_fbw.c b/sw/airborne/subsystems/intermcu/intermcu_fbw.c index ee2747b49c..eb25a153fe 100644 --- a/sw/airborne/subsystems/intermcu/intermcu_fbw.c +++ b/sw/airborne/subsystems/intermcu/intermcu_fbw.c @@ -28,7 +28,7 @@ #include "intermcu_msg.h" #include "subsystems/radio_control.h" #include "mcu_periph/uart.h" -#include "subsystems/datalink/pprz_transport.h" +#include "pprzlink/pprz_transport.h" #if RADIO_CONTROL_NB_CHANNEL > 8 #undef RADIO_CONTROL_NB_CHANNEL diff --git a/sw/airborne/test/subsystems/test_ahrs.c b/sw/airborne/test/subsystems/test_ahrs.c index a8a433fcf8..80c6fca42b 100644 --- a/sw/airborne/test/subsystems/test_ahrs.c +++ b/sw/airborne/test/subsystems/test_ahrs.c @@ -38,7 +38,7 @@ #include "mcu_periph/sys_time.h" #include "led.h" #include "mcu_periph/i2c.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "subsystems/datalink/telemetry.h" diff --git a/sw/airborne/test/subsystems/test_imu.c b/sw/airborne/test/subsystems/test_imu.c index a3bcada60f..e4a33c5b93 100644 --- a/sw/airborne/test/subsystems/test_imu.c +++ b/sw/airborne/test/subsystems/test_imu.c @@ -32,7 +32,7 @@ #include "mcu_periph/sys_time.h" #include "led.h" #include "mcu_periph/i2c.h" -#include "messages.h" +#include "pprzlink/messages.h" #include "subsystems/datalink/downlink.h" #include "subsystems/imu.h" diff --git a/sw/ext/pprzlink b/sw/ext/pprzlink new file mode 160000 index 0000000000..4cf2e8c9d7 --- /dev/null +++ b/sw/ext/pprzlink @@ -0,0 +1 @@ +Subproject commit 4cf2e8c9d73e90c56b5bdfb6b1ba7cb6d9a88910 diff --git a/sw/tools/generators/gen_modules.ml b/sw/tools/generators/gen_modules.ml index 0df7b88bc0..17c02951a5 100644 --- a/sw/tools/generators/gen_modules.ml +++ b/sw/tools/generators/gen_modules.ml @@ -261,7 +261,7 @@ let print_event_functions = fun modules -> lprintf out_h "}\n" let print_datalink_functions = fun modules -> - lprintf out_h "\n#include \"messages.h\"\n"; + lprintf out_h "\n#include \"pprzlink/messages.h\"\n"; lprintf out_h "#include \"generated/airframe.h\"\n"; lprintf out_h "static inline void modules_parse_datalink(uint8_t msg_id __attribute__ ((unused))) {\n"; right (); diff --git a/sw/tools/generators/gen_ubx.ml b/sw/tools/generators/gen_ubx.ml index 51a01df2ef..3eebb21dfc 100644 --- a/sw/tools/generators/gen_ubx.ml +++ b/sw/tools/generators/gen_ubx.ml @@ -159,7 +159,7 @@ let _ = fprintf out "/* Generated by gen_ubx from %s */\n" xml_file; fprintf out "/* Please DO NOT EDIT */\n\n"; - fprintf out "#include \"mcu_periph/link_device.h\"\n\n"; + fprintf out "#include \"pprzlink/pprzlink_device.h\"\n\n"; fprintf out "#include \"subsystems/gps/gps_ubx.h\"\n\n"; define "UBX_SYNC1" "0xB5";