Merge pull request #2721 from paparazzi/autopilot_reorg

Autopilot reorg
This commit is contained in:
Gautier Hattenberger
2021-08-27 10:23:32 +02:00
committed by GitHub
414 changed files with 3538 additions and 2624 deletions
@@ -17,12 +17,6 @@
<module name="radio_control" type="ppm"/>
</target>
<define name="USE_I2C1"/>
<!--define name="USE_I2C2"/-->
<!--define name="AGR_CLIMB"/-->
<!--define name="LOITER_TRIM"/-->
<!--define name="PITCH_TRIM"/-->
<!-- Communication -->
<module name="telemetry" type="xbee_api"/>
<module name="tlsf"/>
+1 -3
View File
@@ -41,6 +41,7 @@
<module name="board" type="tawaki">
<configure name="BOARD_TAWAKI_ROTATED" value="TRUE"/>
</module>
<module name="actuators" type="pwm"/>
<module name="gps" type="ublox">
<configure name="GPS_BAUD" value="B115200"/>
@@ -55,9 +56,6 @@
</module>
<!--configure name="SDLOG_USE_RTC" value="FALSE"/-->
<!--module name="tlsf"/>
<module name="pprzlog"/>
<module name="logger" type="sd_chibios"/-->
<module name="flight_recorder"/>
</firmware>
@@ -9,7 +9,7 @@
<configure name="RTOS_DEBUG" value="0"/>
<target name="ap" board="crazyflie_2.1">
<!--module name="gps" type="datalink"/-->
<module name="gps" type="datalink"/>
<module name="cf_deck" type="multi_ranger"/>
<module name="range_forcefield">
<define name="RANGE_FORCEFIELD_MAX_VEL" value="0.1"/>
+4 -8
View File
@@ -186,14 +186,6 @@ B2L -> CW
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
@@ -217,12 +209,16 @@ B2L -> CW
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v2.1"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</firmware>
</airframe>
@@ -173,16 +173,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<!--//////////////INCLUDE THE GAIN SCHEDULING MODULE\\\\\\\\\\\\\\\\-->
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</module>
<!-- FIXME <module name="gain_scheduling"/>-->
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="ppm">
@@ -206,7 +196,9 @@
<module name="imu" type="aspirin_v2.1"/>
<!--module name="imu" type="aspirin_v1.0"/-->
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<!-- FIXME <module name="gain_scheduling"/>-->
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="0"/>
<define name="AHRS_USE_GPS_HEADING" value="1"/>
@@ -215,5 +207,9 @@
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</module>
</firmware>
</airframe>
@@ -183,13 +183,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1">
<module name="radio_control" type="spektrum">
@@ -213,12 +206,16 @@
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v2.1"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</firmware>
</airframe>
+1 -4
View File
@@ -144,10 +144,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
@@ -172,6 +168,7 @@
<module name="imu" type="aspirin_v2.1"/>
<define name="LISA_M_LONGITUDINAL_X"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
+5 -8
View File
@@ -158,14 +158,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="ppm">
@@ -188,6 +180,7 @@
<module name="imu" type="aspirin_v2.1"/>
<define name="LISA_M_LONGITUDINAL_X"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="0"/>
@@ -196,6 +189,10 @@
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</firmware>
</airframe>
+6 -9
View File
@@ -183,15 +183,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</module>
<!--module name="gain_scheduling"/-->
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="ppm">
@@ -215,7 +206,9 @@
<module name="imu" type="aspirin_v2.2"/>
<!-- <module name="imu" type="aspirin_v1.5"/> -->
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<!--module name="gain_scheduling"/-->
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="0"/>
<define name="AHRS_USE_GPS_HEADING" value="0"/>
@@ -224,5 +217,9 @@
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</module>
</firmware>
</airframe>
@@ -179,10 +179,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1">
<module name="radio_control" type="spektrum">
@@ -206,6 +202,7 @@
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v2.1"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
+28 -31
View File
@@ -140,38 +140,35 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_1.0">
<module name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</module>
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</module>
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v1.0"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_1.0">
<module name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</module>
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</module>
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v1.0"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
</firmware>
@@ -143,14 +143,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
@@ -175,12 +167,16 @@
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v2.1"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</firmware>
</airframe>
@@ -140,14 +140,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="ppm">
@@ -169,12 +161,16 @@
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v2.1"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
<!--define name="USE_INS_NAV_INIT"/-->
<!--module name="stabilization" type="int_euler"/>
<module name="ahrs" type="int_cmpl_euler"/-->
<module name="led_safety_status">
<define name="SAFETY_WARNING_LED" value="5"/>
</module>
</firmware>
</airframe>
+1 -4
View File
@@ -143,10 +143,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_s_1.0">
<module name="radio_control" type="superbitrf_rc">
@@ -172,6 +168,7 @@
<module name="telemetry" type="transparent"/>
<module name="imu" type="lisa_s_v1.0"/>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
+1 -3
View File
@@ -29,9 +29,7 @@
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="float_mlkf"/>
<module name="ins" type="extended"/>
</firmware>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="air_data"/>
<module name="send_imu_mag_current"/>
@@ -56,7 +54,7 @@
<!--module name="ir_mlx">
<define name="MLX_I2C_DEV" value="i2c3"/>
</module-->
</modules>
</firmware>
<commands>
<axis name="PITCH" failsafe_value="0"/>
+1 -3
View File
@@ -35,9 +35,7 @@
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module>
<module name="ins" type="extended"/>
</firmware>
<modules main_freq="512">
<!--module name="wind_estimator"/-->
<module name="geo_mag"/>
<module name="air_data"/>
@@ -50,7 +48,7 @@
<configure name="SHT_UART" value="UART5"/>
</module>
<module name="imu_temp_ctrl"/>
</modules>
</firmware>
<commands>
<axis name="PITCH" failsafe_value="0"/>
+5 -8
View File
@@ -188,14 +188,6 @@
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<modules main_freq="512">
<module name="gps" type="ubx_ucenter"/>
<module name="geo_mag"/>
<module name="air_data"/>
<!-- below temporary until tsted then remove it-->
<module name="send_imu_mag_current"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_s_1.0">
<module name="radio_control" type="superbitrf_rc"> <!-- type="ppm" -->
@@ -240,10 +232,15 @@
<define name="LISA_S_UPSIDE_DOWN"/> <!-- Upside down is a relative term. :) -->
</module>
<module name="gps" type="ublox"/>
<module name="gps" type="ubx_ucenter"/>
<module name="geo_mag"/>
<module name="air_data"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<!-- <configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>-->
<module name="ins"/>
<!-- below temporary until tsted then remove it-->
<module name="send_imu_mag_current"/>
</firmware>
</airframe>
+8 -13
View File
@@ -29,18 +29,6 @@
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="float_mlkf"/>
<module name="ins" type="hff"/>
</firmware>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<!-- ************************* MODULES ************************* -->
<modules main_freq="512">
<!-- <module name="logger_spi_link"/>
<module name="imu_quality_assessment"/> -->
<module name="switch" type="servo"/>
@@ -49,7 +37,14 @@
<module name="nav" type="survey_rectangle_rotorcraft"/>
<module name="nav" type="survey_poly_rotorcraft"/>
<module name="geo_mag"/>
</modules>
</firmware>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<!-- ************************* ACTUATORS ************************* -->
@@ -28,8 +28,9 @@
<module name="control"/>
<module name="navigation"/>
<module name="sys_mon"/>
<module name="nav" type="line"/>
<module name="sys_mon"/>
</firmware>
<servos>
+1 -3
View File
@@ -65,9 +65,7 @@
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_1"/>
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_2"/>
</module>
</firmware>
<modules>
<module name="sys_mon"/>
<module name="baro_sim"/>
<module name="air_data">
@@ -77,7 +75,7 @@
<module name="digital_cam_servo">
<define name="DC_SHUTTER_SERVO" value="COMMAND_SHUTTER"/>
</module>
</modules>
</firmware>
<servos>
-14
View File
@@ -9,20 +9,6 @@ CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
CFG_FIXEDWING=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/fixedwing
SRC_FIXEDWING=.
SRC_ARCH=arch/$(ARCH)
SRC_FIXEDWING_TEST=$(SRC_FIXEDWING)/
SRC_BOARD=boards/$(BOARD)
SRC_FIRMWARE=firmwares/fixedwing
SRC_SUBSYSTEMS=subsystems
SRC_MODULES=modules
FIXEDWING_INC = -DFIXEDWING_FIRMWARE -I$(SRC_FIRMWARE) -I$(SRC_FIXEDWING) -I$(SRC_BOARD)
VPATH += $(PAPARAZZI_HOME)/var/share
VPATH += $(PAPARAZZI_HOME)/sw/ext
# Standard Fixed Wing Code
include $(CFG_FIXEDWING)/autopilot.makefile
-192
View File
@@ -24,196 +24,4 @@
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
CFG_ROTORCRAFT=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/rotorcraft
SRC_BOARD=boards/$(BOARD)
SRC_FIRMWARE=firmwares/rotorcraft
SRC_SUBSYSTEMS=subsystems
SRC_MODULES=modules
SRC_ARCH=arch/$(ARCH)
ROTORCRAFT_INC = -DROTORCRAFT_FIRMWARE -I$(SRC_FIRMWARE) -I$(SRC_BOARD)
ap.ARCHDIR = $(ARCH)
VPATH += $(PAPARAZZI_HOME)/var/share
VPATH += $(PAPARAZZI_HOME)/sw/ext
######################################################################
##
## COMMON ROTORCRAFT ALL TARGETS (AP + NPS)
##
$(TARGET).CFLAGS += $(ROTORCRAFT_INC)
$(TARGET).CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG)
$(TARGET).CFLAGS += -DPERIPHERALS_AUTO_INIT
$(TARGET).srcs += mcu.c
$(TARGET).srcs += $(SRC_ARCH)/mcu_arch.c
# frequency of main periodic
PERIODIC_FREQUENCY ?= 512
$(TARGET).CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY)
ifdef AHRS_PROPAGATE_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_PROPAGATE_FREQUENCY=$(AHRS_PROPAGATE_FREQUENCY)
endif
ifdef AHRS_CORRECT_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY)
endif
ifdef AHRS_MAG_CORRECT_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_MAG_CORRECT_FREQUENCY=$(AHRS_MAG_CORRECT_FREQUENCY)
endif
#
# Systime
#
$(TARGET).srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
ifeq ($(ARCH), linux)
# seems that we need to link against librt for glibc < 2.17
$(TARGET).LDFLAGS += -lrt
endif
#
# Math functions
#
ifneq ($(TARGET), fbw)
$(TARGET).srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c math/pprz_trig_int.c math/pprz_orientation_conversion.c math/pprz_algebra_int.c math/pprz_algebra_float.c math/pprz_algebra_double.c math/pprz_stat.c
$(TARGET).srcs += subsystems/settings.c
$(TARGET).srcs += $(SRC_ARCH)/subsystems/settings_arch.c
endif
$(TARGET).srcs += subsystems/actuators.c
$(TARGET).srcs += subsystems/commands.c
ifneq ($(TARGET), fbw)
$(TARGET).srcs += state.c
#
# BARO_BOARD (if existing/configured)
#
include $(CFG_SHARED)/baro_board.makefile
else
$(TARGET).CFLAGS += -DFBW=1
endif
#
# Main
#
ifeq ($(RTOS), chibios)
$(TARGET).srcs += $(SRC_FIRMWARE)/main_chibios.c
else # No RTOS
$(TARGET).srcs += $(SRC_FIRMWARE)/main.c
endif # RTOS
ifneq ($(TARGET), fbw)
$(TARGET).srcs += $(SRC_FIRMWARE)/main_ap.c
$(TARGET).srcs += autopilot.c
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_firmware.c
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_utils.c
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_guided.c
ifeq ($(USE_GENERATED_AUTOPILOT), TRUE)
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_generated.c
$(TARGET).CFLAGS += -DUSE_GENERATED_AUTOPILOT=1
else
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_static.c
endif
else
$(TARGET).srcs += $(SRC_FIRMWARE)/main_fbw.c
endif # TARGET == fbw
######################################################################
##
## COMMON HARDWARE SUPPORT FOR ALL TARGETS
##
ifneq ($(TARGET), fbw)
$(TARGET).srcs += mcu_periph/i2c.c
$(TARGET).srcs += mcu_periph/softi2c.c
$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
endif
include $(CFG_SHARED)/uart.makefile
#
# Electrical subsystem / Analog Backend
#
$(TARGET).CFLAGS += -DUSE_ADC
$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c
$(TARGET).srcs += subsystems/electrical.c
######################################################################
##
## HARDWARE SUPPORT FOR ALL NON-SIMULATION TARGETS (ap)
##
#
# Interrupts
#
ifeq ($(ARCH), stm32)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
ifeq ($(ARCH), chibios)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
#
# LEDs
#
ns_CFLAGS += -DUSE_LED
ifneq ($(SYS_TIME_LED),none)
ns_CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED)
endif
ifeq ($(ARCH), stm32)
ns_srcs += $(SRC_ARCH)/led_hw.c
endif
ifeq ($(BOARD), ardrone)
ns_srcs += $(SRC_BOARD)/gpio_ardrone.c
endif
#
# add other subsystems to rotorcraft firmware in airframe file:
#
# telemetry
# radio_control
# actuators
# imu
# gps
# ahrs
# ins
#
######################################################################
##
## Final Target Allocations
##
ap.CFLAGS += $(ns_CFLAGS)
ap.srcs += $(ns_srcs)
fbw.CFLAGS += $(ns_CFLAGS)
fbw.srcs += $(ns_srcs)
######################################################################
##
## include firmware independent nps makefile and add rotorcraft specifics
##
ifneq ($(TARGET), hitl)
include $(CFG_SHARED)/nps.makefile
else
include $(CFG_SHARED)/hitl.makefile
endif
nps.srcs += nps/nps_autopilot_rotorcraft.c
-143
View File
@@ -23,146 +23,3 @@
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
SRC_BOARD=boards/$(BOARD)
SRC_FIRMWARE=firmwares/rover
SRC_SUBSYSTEMS=subsystems
SRC_MODULES=modules
SRC_ARCH=arch/$(ARCH)
ROTORCRAFT_INC = -DROVER_FIRMWARE -I$(SRC_FIRMWARE) -I$(SRC_BOARD)
ap.ARCHDIR = $(ARCH)
VPATH += $(PAPARAZZI_HOME)/var/share
######################################################################
##
## COMMON ROVER ALL TARGETS (AP)
##
$(TARGET).CFLAGS += $(ROTORCRAFT_INC)
$(TARGET).CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG)
$(TARGET).CFLAGS += -DPERIPHERALS_AUTO_INIT
$(TARGET).srcs += mcu.c
$(TARGET).srcs += $(SRC_ARCH)/mcu_arch.c
# frequency of main periodic
PERIODIC_FREQUENCY ?= 100
$(TARGET).CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY)
ifdef AHRS_PROPAGATE_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_PROPAGATE_FREQUENCY=$(AHRS_PROPAGATE_FREQUENCY)
endif
ifdef AHRS_CORRECT_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY)
endif
ifdef AHRS_MAG_CORRECT_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_MAG_CORRECT_FREQUENCY=$(AHRS_MAG_CORRECT_FREQUENCY)
endif
#
# Systime
#
$(TARGET).srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
ifeq ($(ARCH), linux)
# seems that we need to link against librt for glibc < 2.17
$(TARGET).LDFLAGS += -lrt
endif
#
# Math functions
#
$(TARGET).srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c math/pprz_trig_int.c math/pprz_orientation_conversion.c math/pprz_algebra_int.c math/pprz_algebra_float.c math/pprz_algebra_double.c math/pprz_stat.c
$(TARGET).srcs += subsystems/settings.c
$(TARGET).srcs += $(SRC_ARCH)/subsystems/settings_arch.c
$(TARGET).srcs += subsystems/actuators.c
$(TARGET).srcs += subsystems/commands.c
$(TARGET).srcs += state.c
#
# BARO_BOARD (if existing/configured)
#
include $(CFG_SHARED)/baro_board.makefile
#
# Main
#
# based on ChibiOS
#
ifeq ($(RTOS), chibios)
$(TARGET).srcs += $(SRC_FIRMWARE)/main_chibios.c
endif # RTOS
$(TARGET).srcs += $(SRC_FIRMWARE)/main_ap.c
$(TARGET).srcs += autopilot.c
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_firmware.c
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_utils.c
ifeq ($(USE_GENERATED_AUTOPILOT), TRUE)
$(TARGET).srcs += $(SRC_FIRMWARE)/autopilot_generated.c
$(TARGET).CFLAGS += -DUSE_GENERATED_AUTOPILOT=1
else
$(error "Rover firmware should use generated autopilot")
endif
######################################################################
##
## COMMON HARDWARE SUPPORT FOR ALL TARGETS
##
$(TARGET).srcs += mcu_periph/i2c.c
$(TARGET).srcs += mcu_periph/softi2c.c
$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
include $(CFG_SHARED)/uart.makefile
#
# Electrical subsystem / Analog Backend
#
$(TARGET).CFLAGS += -DUSE_ADC
$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c
$(TARGET).srcs += subsystems/electrical.c
######################################################################
##
## HARDWARE SUPPORT FOR ALL NON-SIMULATION TARGETS (ap)
##
ifeq ($(ARCH), stm32)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
ifeq ($(ARCH), chibios)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
#
# LEDs
#
ns_CFLAGS += -DUSE_LED
ifneq ($(SYS_TIME_LED),none)
ns_CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED)
endif
ifeq ($(ARCH), stm32)
ns_srcs += $(SRC_ARCH)/led_hw.c
endif
######################################################################
##
## Final Target Allocations
##
ap.CFLAGS += $(ns_CFLAGS)
ap.srcs += $(ns_srcs)
@@ -21,238 +21,3 @@
#
#
######################################################################
##
## COMMON FIXEDWING ALL TARGETS (SIM + AP + FBW ...)
##
#
# Board config + Include paths
#
$(TARGET).CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG)
$(TARGET).CFLAGS += -DPERIPHERALS_AUTO_INIT
$(TARGET).CFLAGS += $(FIXEDWING_INC)
$(TARGET).srcs += mcu.c
$(TARGET).srcs += $(SRC_ARCH)/mcu_arch.c
#
# Common Options
#
ifeq ($(OPTIONS), minimal)
else
$(TARGET).CFLAGS += -DWIND_INFO
endif
#
# frequencies
#
PERIODIC_FREQUENCY ?= 60
$(TARGET).CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY)
ifdef AHRS_PROPAGATE_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_PROPAGATE_FREQUENCY=$(AHRS_PROPAGATE_FREQUENCY)
endif
ifdef AHRS_CORRECT_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY)
endif
ifdef AHRS_MAG_CORRECT_FREQUENCY
$(TARGET).CFLAGS += -DAHRS_MAG_CORRECT_FREQUENCY=$(AHRS_MAG_CORRECT_FREQUENCY)
endif
#
# Sys-time
#
$(TARGET).srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c
ifeq ($(ARCH), linux)
# seems that we need to link against librt for glibc < 2.17
$(TARGET).LDFLAGS += -lrt
endif
#
# InterMCU & Commands
#
$(TARGET).CFLAGS += -DINTER_MCU
$(TARGET).srcs += $(SRC_FIXEDWING)/inter_mcu.c
#
# Math functions
#
ifneq ($(TARGET),fbw)
$(TARGET).srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c math/pprz_trig_int.c math/pprz_orientation_conversion.c math/pprz_algebra_int.c math/pprz_algebra_float.c math/pprz_algebra_double.c math/pprz_stat.c
endif
#
# I2C
#
ifneq ($(TARGET),fbw)
$(TARGET).srcs += mcu_periph/i2c.c
$(TARGET).srcs += mcu_periph/softi2c.c
$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
endif
######################################################################
##
## COMMON FOR ALL NON-SIMULATION TARGETS
##
#
# Interrupt Vectors
#
ifeq ($(ARCH), stm32)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
ifeq ($(ARCH), chibios)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
ifeq ($(ARCH), linux)
ns_srcs += $(SRC_ARCH)/mcu_periph/gpio_arch.c
endif
#
# Main
#
ifeq ($(RTOS), chibios)
ns_srcs += $(SRC_FIRMWARE)/main_chibios.c
else
ns_srcs += $(SRC_FIRMWARE)/main.c
endif
#
# LEDs
#
SYS_TIME_LED ?= none
ns_CFLAGS += -DUSE_LED
ifneq ($(SYS_TIME_LED),none)
ns_CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED)
endif
ifeq ($(ARCH), $(filter $(ARCH), stm32 sim))
ns_srcs += $(SRC_ARCH)/led_hw.c
endif
#
# UARTS
#
ns_srcs += mcu_periph/uart.c
ns_srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
ifeq ($(ARCH), linux)
ns_srcs += $(SRC_ARCH)/serial_port.c
endif
#
# ANALOG
#
ns_CFLAGS += -DUSE_ADC
ns_srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c
######################################################################
##
## FLY BY WIRE THREAD SPECIFIC
##
fbw_CFLAGS += -DFBW
fbw_srcs += $(SRC_FIRMWARE)/main_fbw.c
fbw_srcs += subsystems/electrical.c
fbw_srcs += subsystems/commands.c
fbw_srcs += subsystems/actuators.c
######################################################################
##
## AUTOPILOT THREAD SPECIFIC
##
ap_CFLAGS += -DAP
ap_srcs += $(SRC_FIRMWARE)/main_ap.c
ap_srcs += autopilot.c
ap_srcs += $(SRC_FIRMWARE)/autopilot_firmware.c
ifeq ($(USE_GENERATED_AUTOPILOT), TRUE)
ap_srcs += $(SRC_FIRMWARE)/autopilot_generated.c
ap_CFLAGS += -DUSE_GENERATED_AUTOPILOT=1
else
ap_srcs += $(SRC_FIRMWARE)/autopilot_static.c
endif
ap_srcs += state.c
ap_srcs += subsystems/settings.c
ap_srcs += $(SRC_ARCH)/subsystems/settings_arch.c
# BARO
include $(CFG_SHARED)/baro_board.makefile
######################################################################
##
## SIMULATOR THREAD SPECIFIC
##
UNAME = $(shell uname -s)
ifeq ("$(UNAME)","Darwin")
sim.CFLAGS += $(shell if test -d /opt/paparazzi/include; then echo "-I/opt/paparazzi/include"; elif test -d /opt/local/include; then echo "-I/opt/local/include"; fi)
endif
sim.CFLAGS += $(CPPFLAGS)
sim.CFLAGS += $(fbw_CFLAGS) $(ap_CFLAGS)
sim.srcs += $(fbw_srcs) $(ap_srcs)
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 subsystems/datalink/datalink.c $(SRC_FIRMWARE)/fixedwing_datalink.c pprzlink/src/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
sim.srcs += $(SRC_ARCH)/subsystems/actuators/actuators_pwm_arch.c
# hack: always compile some of the sim functions, so ocaml sim does not complain about no-existing functions
sim.srcs += $(SRC_ARCH)/sim_ahrs.c $(SRC_ARCH)/sim_airspeed.c
######################################################################
##
## Final Target Allocations
##
#
# SINGLE MCU / DUAL MCU
#
# Single MCU's run both
ifeq ($(SEPARATE_FBW),)
ap.CFLAGS += $(fbw_CFLAGS)
ap.srcs += $(fbw_srcs)
endif
#
# No-Sim parameters
#
fbw.CFLAGS += $(fbw_CFLAGS) $(ns_CFLAGS)
fbw.srcs += $(fbw_srcs) $(ns_srcs)
ap.CFLAGS += $(ap_CFLAGS) $(ns_CFLAGS)
ap.srcs += $(ap_srcs) $(ns_srcs)
######################################################################
##
## include firmware independent nps makefile and add fixedwing specifics
##
ifneq ($(TARGET), hitl)
include $(CFG_SHARED)/nps.makefile
else
include $(CFG_SHARED)/hitl.makefile
endif
nps.srcs += nps/nps_autopilot_fixedwing.c
nps.srcs += $(SRC_ARCH)/subsystems/actuators/actuators_pwm_arch.c
# add normal ap and fbw sources
nps.CFLAGS += $(fbw_CFLAGS) $(ap_CFLAGS)
nps.srcs += $(fbw_srcs) $(ap_srcs)
@@ -1,29 +0,0 @@
# Hey Emacs, this is a -*- makefile -*-
#
# NPS HITL Simulator
#
# HITL specific makefile
#
# include Makefile.nps instead of Makefile.sim
hitl.MAKEFILE = hitl
include $(CFG_SHARED)/nps_common.makefile
nps.srcs += $(NPSDIR)/nps_main_hitl.c
# TODO: have this in ins_vectornav.xml
# will hopefully work better once nps and HITL are separate targets
nps.srcs += $(NPSDIR)/nps_ins_vectornav.c
INS_DEV ?= \"/dev/ttyUSB1\"
INS_BAUD ?= B921600
AP_DEV ?= \"/dev/ttyUSB2\"
AP_BAUD ?= B921600
nps.CFLAGS += -DAP_DEV=\"$(AP_DEV)\"
nps.CFLAGS += -DAP_BAUD=$(AP_BAUD)
nps.CFLAGS += -DINS_DEV=\"$(INS_DEV)\"
nps.CFLAGS += -DINS_BAUD=$(INS_BAUD)
@@ -1,11 +0,0 @@
# Hey Emacs, this is a -*- makefile -*-
#
# NPS SITL Simulator
#
# SITL specific makefile
#
# include Makefile.nps instead of Makefile.sim
nps.MAKEFILE = nps
include $(CFG_SHARED)/nps_common.makefile
nps.srcs += $(NPSDIR)/nps_main_sitl.c
@@ -1,66 +0,0 @@
# Hey Emacs, this is a -*- makefile -*-
#
# NPS Simulator
#
# Common makefile for both SITL/HITL simulation
#
# still needs a FDM backend to be specified, e.g.
# <subsystem name="fdm" type="jsbsim"/>
#
nps.ARCHDIR = sim
nps.CFLAGS += -DSITL -DUSE_NPS
nps.LDFLAGS += -lm -livy $(shell pcre-config --libs) -lgsl -lgslcblas
# detect system arch and include rt and pthread library only on linux
UNAME_S := $(shell uname -s)
ifeq ($(UNAME_S),Linux)
nps.LDFLAGS += -lrt -pthread
endif
nps.CFLAGS += -I$(SRC_FIRMWARE) -I$(SRC_BOARD) -I$(PAPARAZZI_SRC)/sw/simulator -I$(PAPARAZZI_SRC)/sw/simulator/nps -I$(PAPARAZZI_HOME)/conf/simulator/nps
# sdl needed for joystick input
nps.LDFLAGS += $(shell sdl-config --libs)
# glib is still needed for some components (such as radio input)
nps.CFLAGS += $(shell pkg-config glib-2.0 --cflags)
nps.LDFLAGS += $(shell pkg-config glib-2.0 --libs)
#
# add the simulator directory to the make searchpath
#
VPATH += $(PAPARAZZI_SRC)/sw/simulator
NPSDIR = nps
nps.srcs += \
$(NPSDIR)/nps_random.c \
$(NPSDIR)/nps_sensors.c \
$(NPSDIR)/nps_sensors_utils.c \
$(NPSDIR)/nps_sensor_gyro.c \
$(NPSDIR)/nps_sensor_accel.c \
$(NPSDIR)/nps_sensor_mag.c \
$(NPSDIR)/nps_sensor_baro.c \
$(NPSDIR)/nps_sensor_sonar.c \
$(NPSDIR)/nps_sensor_gps.c \
$(NPSDIR)/nps_sensor_airspeed.c \
$(NPSDIR)/nps_sensor_temperature.c \
$(NPSDIR)/nps_sensor_aoa.c \
$(NPSDIR)/nps_sensor_sideslip.c \
$(NPSDIR)/nps_electrical.c \
$(NPSDIR)/nps_atmosphere.c \
$(NPSDIR)/nps_ivy.c \
$(NPSDIR)/nps_flightgear.c \
$(NPSDIR)/nps_radio_control.c \
$(NPSDIR)/nps_radio_control_joystick.c \
$(NPSDIR)/nps_radio_control_spektrum.c \
$(NPSDIR)/nps_main_common.c
# for geo mag calculation
nps.srcs += math/pprz_geodetic_wmm2020.c
BARO_PERIODIC_FREQUENCY ?= 50
BARO_BOARD_CFLAGS += -DBARO_PERIODIC_FREQUENCY=$(BARO_PERIODIC_FREQUENCY)
+1 -1
View File
@@ -1,6 +1,6 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="AOA_adc" dir="sensors">
<module name="AOA_adc" dir="sensors" task="sensors">
<doc>
<description>Angle of Attack using internal ADC</description>
<configure name="ADC_AOA" value="ADC_X" description="select the ADC channel to use"/>
+1 -1
View File
@@ -1,6 +1,6 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="AOA_pwm" dir="sensors">
<module name="AOA_pwm" dir="sensors" task="sensors">
<doc>
<description>
Angle of Attack sensor using PWM input
+23
View File
@@ -0,0 +1,23 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="actuators" dir="actuators" task="actuators">
<doc>
<description>
Common actuators interface
</description>
</doc>
<dep>
</dep>
<header>
<file name="actuators.h" dir="subsystems"/>
</header>
<init fun="actuators_init()"/>
<makefile>
<define name="ACTUATORS"/>
<file name="actuators.c" dir="subsystems"/>
<test/>
</makefile>
</module>
+4 -1
View File
@@ -6,12 +6,15 @@
Actuators Driver for ARDrone2
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<autoload name="actuators" type="nps"/>
<header>
<file name="actuators.h" dir="boards/ardrone"/>
</header>
<makefile target="ap">
<define name="ACTUATORS"/>
<file name="actuators.c" dir="$(SRC_BOARD)"/>
<test firmware="rotorcraft">
<configure name="SRC_BOARD" value="boards/ardrone"/>
+4 -1
View File
@@ -11,13 +11,16 @@
</description>
<configure name="ACTUATORS_ASCTEC_V2_I2C_DEV" value="i2cX" description="I2C port (default i2c1)"/>
</doc>
<dep>
<depends>i2c,actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_asctec_v2.h" dir="subsystems/actuators"/>
</header>
<makefile target="!sim|nps">
<configure name="ACTUATORS_ASCTEC_V2_I2C_DEV" default="i2c1" case="upper|lower"/>
<configure name="ACTUATORS_ASCTEC_V2_I2C_SCL_TIME" default="150"/>
<define name="ACTUATORS"/>
<define name="ACTUATORS_ASCTEC_V2_I2C_DEV" value="$(ACTUATORS_ASCTEC_V2_I2C_DEV_LOWER)"/>
<define name="USE_$(ACTUATORS_ASCTEC_V2_I2C_DEV_UPPER)"/>
<file name="actuators_asctec_v2.c" dir="subsystems/actuators"/>
+4 -1
View File
@@ -7,13 +7,16 @@
</description>
<configure name="BEBOP_ACTUATORS_I2C_DEV" value="i2cX" description="I2C port (default i2c1)"/>
</doc>
<dep>
<depends>i2c,actuators</depends>
<provides>actuators</provides>
</dep>
<autoload name="actuators" type="nps"/>
<header>
<file name="actuators.h" dir="boards/bebop"/>
</header>
<makefile target="ap">
<configure name="BEBOP_ACTUATORS_I2C_DEV" default="i2c1" case="upper|lower"/>
<define name="ACTUATORS"/>
<define name="BEBOP_ACTUATORS_I2C_DEV" value="$(BEBOP_ACTUATORS_I2C_DEV_LOWER)"/>
<define name="USE_$(BEBOP_ACTUATORS_I2C_DEV_UPPER)"/>
<file name="actuators.c" dir="$(SRC_BOARD)"/>
+4 -1
View File
@@ -6,11 +6,14 @@
Actuators Driver for Disco plane
</description>
</doc>
<dep>
<depends>i2c,actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators.h" dir="boards/disco"/>
</header>
<makefile target="ap">
<define name="ACTUATORS"/>
<define name="USE_I2C1"/>
<file name="actuators.c" dir="$(SRC_BOARD)"/>
<file_arch name="pwm_sysfs.c" dir="mcu_periph"/>
+4 -1
View File
@@ -11,11 +11,14 @@
</description>
<define name="DSHOT_SPEED" value="600" description="DSHOT speed (150,300,600,1200)"/>
</doc>
<dep>
<depends>actuators,@commands</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_dshot.h"/>
</header>
<makefile>
<define name="ACTUATORS"/>
<file_arch name="actuators_dshot_arch.c"/>
<file_arch name="esc_dshot.c" cond="ifeq ($(RTOS),chibios)"/>
<file_arch name="hal_stm32_dma.c" dir="mcu_periph" cond="ifeq ($(RTOS),chibios)"/>
+4 -2
View File
@@ -4,14 +4,16 @@
<doc>
<description>
Actuators Driver for dual PWM output
Only with stm32
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_dualpwm.h" dir="subsystems/actuators"/>
</header>
<makefile target="!sim|nps">
<define name="ACTUATORS"/>
<file_arch name="actuators_dualpwm_arch.c" dir="subsystems/actuators"/>
<file_arch name="actuators_shared_arch.c" dir="subsystems/actuators"/>
</makefile>
+5
View File
@@ -5,8 +5,13 @@
<description>
Dummy actuators driver
This module prevents autoloading of actuators by fixedwing firmware
FIXME: this as no effect anymore
</description>
</doc>
<dep>
<provides>actuators</provides>
</dep>
<header/>
<makefile>
<configure name="ACTUATORS" value="none"/>
+4 -1
View File
@@ -11,11 +11,14 @@
- command_laws section to map motor_mixing commands to servos
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_esc32.h" dir="subsystems/actuators"/>
</header>
<makefile target="ap">
<define name="ACTUATORS"/>
<define name="USE_CAN_EXT_ID"/>
<file name="can.c" dir="mcu_periph"/>
<file_arch name="can_arch.c" dir="mcu_periph"/>
+4 -1
View File
@@ -7,6 +7,10 @@
</description>
<configure name="ACTUATORS_MD25_DEV" value="i2cX" description="I2C port (default i2c2)"/>
</doc>
<dep>
<depends>i2c,actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_md25.h"/>
</header>
@@ -14,7 +18,6 @@
<event fun="actuators_md25_event()"/>
<makefile>
<configure name="ACTUATORS_MD25_DEV" default="i2c2" case="upper|lower"/>
<define name="ACTUATORS"/>
<define name="ACTUATORS_MD25_DEV" value="$(ACTUATORS_MD25_DEV_LOWER)"/>
<define name="USE_$(ACTUATORS_MD25_DEV_UPPER)"/>
<define name="$(ACTUATORS_MD25_DEV_UPPER)_CLOCK_SPEED" value="100000"/>
+4 -1
View File
@@ -6,8 +6,11 @@
Actuators for NPS (dummy pwm)
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<makefile target="nps">
<define name="ACTUATORS"/>
<file_arch name="actuators_pwm_arch.c" dir="subsystems/actuators"/>
</makefile>
</module>
+4
View File
@@ -6,6 +6,10 @@
<configure name="ACTUATORS_OSTRICH_PORT" value="UARTx" description="UART port (default UART6)"/>
<configure name="ACTUATORS_OSTRICH_BAUD" value="B115200" description="UART baudrate (default 115200)"/>
</doc>
<dep>
<depends>uart,actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_ostrich.h"/>
</header>
+4 -1
View File
@@ -11,11 +11,14 @@
Can be adjusted in the "servos_ppm_hw.h" file to suit your particular receiver.
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_ppm.h" dir="subsystems/actuators"/>
</header>
<makefile target="!sim">
<define name="ACTUATORS"/>
<define name="SERVOS_PPM_MAT"/>
<file_arch name="actuators_ppm_hw.c" dir="subsystems/actuators"/>
</makefile>
+4 -1
View File
@@ -6,11 +6,14 @@
Actuators Driver using direct PWM output
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_pwm.h" dir="subsystems/actuators"/>
</header>
<makefile target="!sim">
<define name="ACTUATORS"/>
<file_arch name="actuators_pwm_arch.c" dir="subsystems/actuators"/>
<file_arch name="actuators_shared_arch.c" dir="subsystems/actuators" cond="ifeq ($(ARCH), stm32)"/>
</makefile>
+4 -1
View File
@@ -9,12 +9,15 @@
</description>
<configure name="ACTUATORS_SBUS_DEV" value="UARTX" description="UART port (default uart4)"/>
</doc>
<dep>
<depends>uart,actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_sbus.h" dir="subsystems/actuators"/>
</header>
<makefile target="!sim">
<configure name="ACTUATORS_SBUS_DEV" default="uart4" case="upper|lower"/>
<define name="ACTUATORS"/>
<define name="ACTUATORS_SBUS_DEV" value="$(ACTUATORS_SBUS_DEV_LOWER)"/>
<define name="USE_$(ACTUATORS_SBUS_DEV_UPPER)"/>
<define name="$(ACTUATORS_SBUS_DEV_UPPER)_BAUD" value="100000"/>
+4 -1
View File
@@ -12,13 +12,16 @@
<configure name="ACTUATORS_SPEKTRUM_DEV" value="UARTX" description="UART port (default uart4)"/>
<configure name="ACTUATORS_SPEKTRUM_DEV2" value="UARTX" description="UART port for optional secondary output"/>
</doc>
<dep>
<depends>uart,actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators_spektrum.h" dir="subsystems/actuators"/>
</header>
<makefile target="!sim">
<configure name="ACTUATORS_SPEKTRUM_DEV" default="uart4" case="upper|lower"/>
<configure name="ACTUATORS_SPEKTRUM_DEV2" case="upper|lower"/>
<define name="ACTUATORS"/>
<define name="ACTUATORS_SPEKTRUM_DEV" value="$(ACTUATORS_SPEKTRUM_DEV_LOWER)"/>
<define name="USE_$(ACTUATORS_SPEKTRUM_DEV_UPPER)"/>
<define name="$(ACTUATORS_SPEKTRUM_DEV_UPPER)_BAUD" value="115200"/>
+4 -1
View File
@@ -6,11 +6,14 @@
Actuators Driver for Swing
</description>
</doc>
<dep>
<depends>actuators</depends>
<provides>actuators</provides>
</dep>
<header>
<file name="actuators.h" dir="boards/swing"/>
</header>
<makefile target="ap">
<define name="ACTUATORS"/>
<file name="actuators.c" dir="$(SRC_BOARD)"/>
</makefile>
</module>
+3 -1
View File
@@ -8,8 +8,10 @@
<define name="UAVCAN_ACTUATORS_USE_CURRENT" value="TRUE" description="Enable the usage of the current sensing in the ESC telemetry"/>
</doc>
<dep>
<depends>uavcan</depends>
<depends>uavcan,actuators</depends>
<provides>actuators</provides>
</dep>
<autoload name="actuators" type="nps"/>
<header>
<file name="actuators_uavcan.h" dir="subsystems/actuators"/>
</header>
+3
View File
@@ -7,6 +7,9 @@
To activate a specific ADC input, define flag USE_ADC_X where X is your ADC input number
</description>
</doc>
<dep>
<depends>mcu</depends>
</dep>
<header>
<file name="adc.h" dir="mcu_periph"/>
</header>
+6 -2
View File
@@ -1,15 +1,19 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="ahrs_chimu_spi" dir="ins">
<module name="ahrs_chimu_spi" dir="ins" task="estimation">
<doc>
<description>CHimu (SPI)</description>
<define name="CHIMU_BIG_ENDIAN" value="TRUE" description="For older CHIMU v1.0 you should define CHIMU_BIG_ENDIAN"/>
</doc>
<dep>
<depends>spi_slave_hs</depends>
<provides>ahrs,imu</provides>
</dep>
<autoload name="ahrs_sim"/>
<autoload name="spi" type="slave_hs"/>
<header>
<file name="ins_module.h"/>
</header>
<init fun="ahrs_init()"/>
<event fun="parse_ins_msg()"/>
<makefile target="ap">
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
+6 -1
View File
@@ -1,14 +1,19 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="ahrs_chimu_uart" dir="ins">
<module name="ahrs_chimu_uart" dir="ins" task="estimation">
<doc>
<description>CHimu (UART)</description>
<configure name="CHIMU_UART_NR" value="3" description="UART"/>
<define name="CHIMU_BIG_ENDIAN" value="TRUE" description="For older CHIMU v1.0 you should define CHIMU_BIG_ENDIAN"/>
</doc>
<dep>
<depends>uart</depends>
<provides>ahrs,imu</provides>
</dep>
<header>
<file name="ins_module.h"/>
</header>
<init fun="ahrs_init()"/>
<event fun="parse_ins_msg()"/>
<makefile target="ap">
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>

Some files were not shown because too many files have changed in this diff Show More