mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-24 05:45:59 +08:00
put generated headers in a seperate generated dir and specifically include generated/xxx.h
This commit is contained in:
+15
-7
@@ -31,27 +31,28 @@ AIRBORNE=sw/airborne
|
||||
MESSAGES_XML = $(CONF)/messages.xml
|
||||
ACINCLUDE = $(PAPARAZZI_HOME)/var/$(AIRCRAFT)
|
||||
AIRCRAFT_CONF_DIR = $(ACINCLUDE)/conf
|
||||
AIRFRAME_H=$(ACINCLUDE)/airframe.h
|
||||
AC_GENERATED = $(ACINCLUDE)/generated
|
||||
|
||||
ifndef PERIODIC_FREQ
|
||||
PERIODIC_FREQ = 60
|
||||
endif
|
||||
|
||||
PERIODIC_H=$(ACINCLUDE)/periodic.h
|
||||
RADIO_H=$(ACINCLUDE)/radio.h
|
||||
FLIGHT_PLAN_H=$(ACINCLUDE)/flight_plan.h
|
||||
AIRFRAME_H=$(AC_GENERATED)/airframe.h
|
||||
PERIODIC_H=$(AC_GENERATED)/periodic.h
|
||||
RADIO_H=$(AC_GENERATED)/radio.h
|
||||
FLIGHT_PLAN_H=$(AC_GENERATED)/flight_plan.h
|
||||
FLIGHT_PLAN_XML=$(ACINCLUDE)/flight_plan.xml
|
||||
SETTINGS_H=$(ACINCLUDE)/settings.h
|
||||
SETTINGS_H=$(AC_GENERATED)/settings.h
|
||||
SETTINGS_XMLS=$(patsubst %,$(CONF)/%,$(SETTINGS))
|
||||
SETTINGS_XML=$(ACINCLUDE)/settings.xml
|
||||
SETTINGS_MODULES=$(ACINCLUDE)/settings_modules.xml
|
||||
MAKEFILE_AC=$(ACINCLUDE)/Makefile.ac
|
||||
SETTINGS_FILE=$(SETTINGS:settings%=%)
|
||||
#TUNING_FILE=$(subst ,_,$(SETTINGS:settings/%.xml=%)).h
|
||||
TUNING_H=$(ACINCLUDE)/tuning.h
|
||||
TUNING_H=$(AC_GENERATED)/tuning.h
|
||||
SUPERVISION=./paparazzi
|
||||
MAKE=make PAPARAZZI_SRC=$(PAPARAZZI_SRC) PAPARAZZI_HOME=$(PAPARAZZI_HOME)
|
||||
MODULES_H=$(ACINCLUDE)/modules.h
|
||||
MODULES_H=$(AC_GENERATED)/modules.h
|
||||
MODULES_DIR=$(PAPARAZZI_HOME)/conf/modules/
|
||||
AIRCRAFT_MD5=$(AIRCRAFT_CONF_DIR)/aircraft.md5
|
||||
|
||||
@@ -82,18 +83,21 @@ flight_plan_ac_h : $(FLIGHT_PLAN_H) $(FLIGHT_PLAN_XML)
|
||||
makefile_ac: $(MAKEFILE_AC)
|
||||
|
||||
$(AIRFRAME_H) : $(CONF)/$(AIRFRAME_XML) $(CONF_XML) $(AIRCRAFT_MD5)
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_airframe.out $(AC_ID) $(AIRCRAFT) $(MD5SUM) $< > /tmp/airframe.h
|
||||
$(Q)mv /tmp/airframe.h $@
|
||||
$(Q)cp $(CONF)/airframes/airframe.dtd $(AIRCRAFT_CONF_DIR)/airframes
|
||||
|
||||
$(RADIO_H) : $(CONF)/$(RADIO) $(CONF_XML) $(TOOLS)/gen_radio.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_radio.out $< > /tmp/radio.h
|
||||
$(Q)mv /tmp/radio.h $@
|
||||
$(Q)cp $< $(AIRCRAFT_CONF_DIR)/radios
|
||||
|
||||
$(PERIODIC_H) : $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TELEMETRY) $(MAKEFILE_AC)
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_periodic.out $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF)/$(TELEMETRY) $(PERIODIC_FREQ) > $@
|
||||
$(Q)chmod a+r $@
|
||||
@@ -101,6 +105,7 @@ $(PERIODIC_H) : $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TE
|
||||
$(Q)cp $(CONF)/$(TELEMETRY) $(AIRCRAFT_CONF_DIR)/telemetry
|
||||
|
||||
$(FLIGHT_PLAN_H) : $(CONF)/$(FLIGHT_PLAN) $(CONF_XML) $(TOOLS)/gen_flight_plan.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_flight_plan.out $< > /tmp/$(AC_ID)_fp.h
|
||||
$(Q)mv /tmp/$(AC_ID)_fp.h $@
|
||||
@@ -113,16 +118,19 @@ $(FLIGHT_PLAN_XML) : $(CONF)/$(FLIGHT_PLAN) $(CONF_XML) $(TOOLS)/gen_flight_plan
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
$(SETTINGS_H) : $(SETTINGS_XMLS) $(CONF_XML) $(SETTINGS_MODULES) $(TOOLS)/gen_settings.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_settings.out $(SETTINGS_XML) $(SETTINGS_XMLS) $(SETTINGS_MODULES) > $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $(SETTINGS_XMLS) $(AIRCRAFT_CONF_DIR)/settings
|
||||
|
||||
$(TUNING_H) : $(SETTINGS_XMLS) $(CONF_XML) $(TOOLS)/gen_tuning.out
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_tuning.out $(SETTINGS_XMLS) > $@
|
||||
|
||||
$(MODULES_H) : $(CONF)/$(AIRFRAME_XML) $(TOOLS)/gen_modules.out $(CONF)/modules/*.xml
|
||||
$(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_modules.out $(MODULES_DIR) $(SETTINGS_MODULES) $< > $@
|
||||
$(Q)chmod a+r $@
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
|
||||
<flight_plan alt="75" ground_alt="0" lat0="43.46223" lon0="1.27289" max_dist_from_home="1500" name="Demo module" security_height="25">
|
||||
<header>
|
||||
#include "modules.h"
|
||||
#include "generated/modules.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
<waypoint name="HOME" x="0" y="0"/>
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
#ifndef NPS_SENSORS_PARAMS_H
|
||||
#define NPS_SENSORS_PARAMS_H
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#if 1
|
||||
#define NPS_BODY_TO_IMU_PHI IMU_BODY_TO_IMU_PHI
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
#ifndef NPS_SENSORS_PARAMS_H
|
||||
#define NPS_SENSORS_PARAMS_H
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#if 1
|
||||
#define NPS_BODY_TO_IMU_PHI IMU_BODY_TO_IMU_PHI
|
||||
|
||||
+1
-1
@@ -22,7 +22,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#include "std.h"
|
||||
#include "3dmg.h"
|
||||
|
||||
@@ -28,8 +28,6 @@ ACINCLUDE = $(PAPARAZZI_HOME)/var/$(AIRCRAFT)
|
||||
|
||||
INCLUDES = -I $(PAPARAZZI_SRC)/sw/include -I $(PAPARAZZI_SRC)/sw/airborne -I $(PAPARAZZI_SRC)/conf/autopilot -I $(PAPARAZZI_SRC)/sw/airborne/arch/$($(TARGET).ARCHDIR) -I $(VARINCLUDE) -I $(ACINCLUDE)
|
||||
|
||||
# doesn't seem to be used/needed
|
||||
#SRC_ARCH = $(PAPARAZZI_SRC)/sw/airborne/$(ARCHDIR)
|
||||
|
||||
ifneq ($(MAKECMDGOALS),clean)
|
||||
include $(PAPARAZZI_HOME)/var/$(AIRCRAFT)/Makefile.ac
|
||||
@@ -49,9 +47,9 @@ $(TARGET).install : warn_conf
|
||||
warn_conf :
|
||||
@echo
|
||||
@echo '###########################################################'
|
||||
@grep AIRFRAME_NAME $(ACINCLUDE)/airframe.h
|
||||
@grep RADIO_NAME $(ACINCLUDE)/radio.h
|
||||
@grep FLIGHT_PLAN_NAME $(ACINCLUDE)/flight_plan.h
|
||||
@grep AIRFRAME_NAME $(ACINCLUDE)/generated/airframe.h
|
||||
@grep RADIO_NAME $(ACINCLUDE)/generated/radio.h
|
||||
@grep FLIGHT_PLAN_NAME $(ACINCLUDE)/generated/flight_plan.h
|
||||
@echo '###########################################################'
|
||||
@echo
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#include "nav.h"
|
||||
#include "estimator.h"
|
||||
#include "autopilot.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/flight_plan.h"
|
||||
|
||||
struct Point2D {float x; float y;};
|
||||
struct Line {float m;float b;float x;};
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#include "agl_vfilter.h"
|
||||
|
||||
#include BOARD_CONFIG
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "std.h"
|
||||
|
||||
/*
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
#include "anemotaxis.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "estimator.h"
|
||||
#include "std.h"
|
||||
#include "nav.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "ap_downlink.h"
|
||||
#include "chemo_detect.h"
|
||||
|
||||
|
||||
@@ -37,15 +37,15 @@
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE
|
||||
#include "downlink.h"
|
||||
|
||||
#include "messages.h"
|
||||
#include "periodic.h"
|
||||
#include "generated/periodic.h"
|
||||
|
||||
//#include "modules.h"
|
||||
//#include "generated/modules.h"
|
||||
|
||||
#if defined DOWNLINK
|
||||
#define Downlink(x) x
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include "servos_direct_hw.h"
|
||||
#include "std.h"
|
||||
#include "actuators.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
void actuators_init ( void ) {
|
||||
/* OC3A, OC3B, OC3C outputs */
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "ssp_hw.h"
|
||||
#include BOARD_CONFIG
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#define MM_DIVISOR_128 2
|
||||
#define MM_DIVISOR_256 3
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#include "LPC21xx.h"
|
||||
#include "interrupt_hw.h"
|
||||
#include "ssp_hw.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include BOARD_CONFIG
|
||||
|
||||
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "spi_hw.h"
|
||||
#include BOARD_CONFIG
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#define MM_DIVISOR_128 2
|
||||
#define MM_DIVISOR_256 3
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "ssp_hw.h"
|
||||
#include BOARD_CONFIG
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -29,7 +29,7 @@
|
||||
|
||||
#include "actuators.h"
|
||||
#include "paparazzi.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
uint8_t servos_4015_idx;
|
||||
uint32_t servos_delay = SERVO_REFRESH_TICS;
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#include "actuators.h"
|
||||
#include "armVIC.h"
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "sys_time.h"
|
||||
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#include "actuators.h"
|
||||
#include "armVIC.h"
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "sys_time.h"
|
||||
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#include "actuators.h"
|
||||
|
||||
#include "paparazzi.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
uint8_t servos_4017_idx;
|
||||
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
#define SERVOS_CSC_H
|
||||
|
||||
#include "LPC21xx.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "actuators.h"
|
||||
#include "sys_time.h"
|
||||
|
||||
|
||||
@@ -28,7 +28,7 @@
|
||||
*/
|
||||
#include "actuators.h"
|
||||
#include "paparazzi.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
uint8_t servos_PPM_idx;
|
||||
uint8_t ppm_pulse;
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
#include <inttypes.h>
|
||||
|
||||
/** From airborne/autopilot/ */
|
||||
#include "airframe.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "autopilot.h"
|
||||
#include "gps.h"
|
||||
#include "estimator.h"
|
||||
|
||||
@@ -34,9 +34,9 @@
|
||||
#include "estimator.h"
|
||||
#include "gps.h"
|
||||
#include "traffic_info.h"
|
||||
#include "flight_plan.h"
|
||||
#include "airframe.h"
|
||||
#include "settings.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "generated/settings.h"
|
||||
#include "nav.h"
|
||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||
#include "firmwares/fixedwing/guidance/guidance_v.h"
|
||||
|
||||
@@ -13,8 +13,8 @@
|
||||
#include "estimator.h"
|
||||
#include "gps.h"
|
||||
#include "traffic_info.h"
|
||||
#include "flight_plan.h"
|
||||
#include "settings.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "generated/settings.h"
|
||||
#include "nav.h"
|
||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||
#include "firmwares/fixedwing/guidance/guidance_v.h"
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
#include <inttypes.h>
|
||||
|
||||
/** From airborne/autopilot/ */
|
||||
#include "airframe.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "autopilot.h"
|
||||
#include "gps.h"
|
||||
#include "estimator.h"
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "infrared.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#include <caml/mlvalues.h>
|
||||
|
||||
|
||||
@@ -13,8 +13,8 @@
|
||||
#include "estimator.h"
|
||||
#include "gps.h"
|
||||
#include "traffic_info.h"
|
||||
#include "flight_plan.h"
|
||||
#include "settings.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "generated/settings.h"
|
||||
#include "nav.h"
|
||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||
#include "ffirmwares/fixedwing/guidance/guidance_v.h"
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
|
||||
#include "subsystems/imu.h"
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
void imu_b2_arch_init(void) {
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include "subsystems/imu.h"
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
void imu_crista_arch_init(void) {
|
||||
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
|
||||
#include "firmwares/rotorcraft/baro.h"
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "led.h"
|
||||
|
||||
/* threshold >0 && <1023 */
|
||||
|
||||
+2
-2
@@ -25,8 +25,8 @@
|
||||
#include "estimator.h"
|
||||
#include "nav.h"
|
||||
#include "bomb.h"
|
||||
#include "flight_plan.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "inter_mcu.h"
|
||||
|
||||
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
#define BOOZ2_COMMANDS_H
|
||||
|
||||
#include "paparazzi.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
extern int32_t booz2_commands[COMMANDS_NB];
|
||||
extern const int32_t booz2_commands_failsafe[COMMANDS_NB];
|
||||
|
||||
@@ -26,9 +26,9 @@
|
||||
|
||||
#include "datalink.h"
|
||||
|
||||
#include "modules.h"
|
||||
#include "generated/modules.h"
|
||||
|
||||
#include "settings.h"
|
||||
#include "generated/settings.h"
|
||||
#include "downlink.h"
|
||||
#include "messages.h"
|
||||
#include "dl_protocol.h"
|
||||
|
||||
@@ -74,7 +74,7 @@ extern bool_t booz_gps_available;
|
||||
#define GPS_LINKChAvailable() (FALSE)
|
||||
#define GPS_LINKGetch() (TRUE)
|
||||
#include "nps_sensors.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/flight_plan.h"
|
||||
|
||||
static inline void booz_gps_feed_value() {
|
||||
booz_gps_state.ecef_pos.x = sensors.gps.ecef_pos.x * 100.;
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
#include "chemotaxis.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "estimator.h"
|
||||
#include "std.h"
|
||||
#include "nav.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "ap_downlink.h"
|
||||
#include "chemo_detect.h"
|
||||
|
||||
|
||||
@@ -30,7 +30,7 @@
|
||||
#define COMMANDS_H
|
||||
|
||||
#include "paparazzi.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
|
||||
extern pprz_t commands[COMMANDS_NB];
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#include "common_nav.h"
|
||||
#include "estimator.h"
|
||||
#include "flight_plan.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "gps.h"
|
||||
|
||||
float dist2_to_home;
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#include "std.h"
|
||||
#include "i2c.h"
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#define BUSS_TWI_BLMC_STATUS_IDLE 0
|
||||
#define BUSS_TWI_BLMC_STATUS_BUSY 1
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
#include "props_csc.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "csc_ap_link.h"
|
||||
#include "csc_msg_def.h"
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#ifndef PROPS_CSC_H
|
||||
#define PROPS_CSC_H
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "firmwares/rotorcraft/actuators.h"
|
||||
#include "sys_time.h"
|
||||
#include "csc_ap_link.h"
|
||||
|
||||
@@ -34,8 +34,8 @@
|
||||
#include "interrupt_hw.h"
|
||||
#include "uart.h"
|
||||
#include "downlink.h"
|
||||
#include "periodic.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/periodic.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "commands.h"
|
||||
#include "subsystems/radio_control.h"
|
||||
#include "booz/booz2_gps.h"
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#define DATALINK_C
|
||||
#include "datalink.h"
|
||||
|
||||
#include "settings.h"
|
||||
#include "generated/settings.h"
|
||||
#include "downlink.h"
|
||||
#include "messages.h"
|
||||
#include "dl_protocol.h"
|
||||
|
||||
@@ -34,7 +34,7 @@
|
||||
#include "interrupt_hw.h"
|
||||
#include "uart.h"
|
||||
#include "csc_telemetry.h"
|
||||
#include "periodic.h"
|
||||
#include "generated/periodic.h"
|
||||
#include "downlink.h"
|
||||
#include "i2c.h"
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
#include "std.h"
|
||||
#include "sys_time.h"
|
||||
#include "firmwares/rotorcraft/actuators.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
#include ACTUATORS
|
||||
|
||||
#define CSC_SERVOS_NB 4
|
||||
|
||||
@@ -31,7 +31,7 @@
|
||||
extern uint8_t telemetry_mode_Ap_DefaultChannel;
|
||||
|
||||
#include "downlink.h"
|
||||
#include "settings.h"
|
||||
#include "generated/settings.h"
|
||||
|
||||
|
||||
#define PERIODIC_SEND_DL_VALUE(_chan) PeriodicSendDlValue(_chan)
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
#ifndef __MERCURY_AP_H__
|
||||
#define __MERCURY_AP_H__
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
extern pprz_t mixed_commands[PROPS_NB];
|
||||
extern uint8_t props_enable[PROPS_NB];
|
||||
|
||||
@@ -50,7 +50,7 @@
|
||||
#include "uart.h"
|
||||
#include "csc_telemetry.h"
|
||||
|
||||
#include "periodic.h"
|
||||
#include "generated/periodic.h"
|
||||
#include "downlink.h"
|
||||
|
||||
#include "pwm_input.h"
|
||||
|
||||
@@ -34,8 +34,8 @@
|
||||
#include "interrupt_hw.h"
|
||||
#include "uart.h"
|
||||
#include "downlink.h"
|
||||
#include "periodic.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/periodic.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "commands.h"
|
||||
|
||||
#include "csc_msg_def.h"
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#ifndef BOOZ2_SUPERVISION_H
|
||||
#define BOOZ2_SUPERVISION_H
|
||||
|
||||
#include "airframe.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
extern pprz_t mercury_supervision_yaw_servo_gain;
|
||||
extern pprz_t mercury_supervision_pitch_servo_gain;
|
||||
|
||||
@@ -34,8 +34,8 @@
|
||||
#include "interrupt_hw.h"
|
||||
#include "uart.h"
|
||||
#include "downlink.h"
|
||||
#include "periodic.h"
|
||||
#include "airframe.h"
|
||||
#include "generated/periodic.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "commands.h"
|
||||
#include "subsystems/radio_control.h"
|
||||
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user