mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 14:18:00 +08:00
[modules] clean some remaining traces of subsystems
This commit is contained in:
@@ -66,7 +66,7 @@
|
||||
|
||||
|
||||
<!-- Navigation -->
|
||||
<define name="USE_GPS_UBX_RTCM" value="TRUE"/> <!-- required so that RTCM messages are decoded in /subsystems/gps/gps_ubx.c -->
|
||||
<define name="USE_GPS_UBX_RTCM" value="TRUE"/> <!-- required so that RTCM messages are decoded in /modules/gps/gps_ubx.c -->
|
||||
<define name="GPS_UBX_UCENTER_RATE" value="0x00FA"/> <!-- Ucenter rate for RTCM messsage.. In milliseconds. 0x00FA = 250ms = 4Hz-->
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
|
||||
@@ -30,10 +30,9 @@
|
||||
|
||||
SRC_ARCH=arch/$(ARCH)
|
||||
SRC_BOARD=boards/$(BOARD)
|
||||
SRC_SUBSYSTEMS=subsystems
|
||||
SRC_MODULES=modules
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
VPATH += $(PAPARAZZI_HOME)/var/share
|
||||
|
||||
@@ -77,7 +76,7 @@ endif
|
||||
#
|
||||
# Demo AHRS and actuators
|
||||
#
|
||||
# required subsystems:
|
||||
# required:
|
||||
# - telemetry
|
||||
# - imu
|
||||
# - ahrs
|
||||
@@ -92,8 +91,8 @@ demo_ahrs_actuators.ARCHDIR = $(ARCH)
|
||||
demo_ahrs_actuators.CFLAGS += $(COMMON_DEMO_CFLAGS)
|
||||
demo_ahrs_actuators.srcs += $(COMMON_DEMO_SRCS)
|
||||
demo_ahrs_actuators.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c
|
||||
demo_ahrs_actuators.srcs += subsystems/settings.c $(SRC_ARCH)/subsystems/settings_arch.c
|
||||
demo_ahrs_actuators.srcs += subsystems/commands.c modules/actuators/actuators.c
|
||||
demo_ahrs_actuators.srcs += modules/core/settings.c $(SRC_ARCH)/modules/core/settings_arch.c
|
||||
demo_ahrs_actuators.srcs += modules/core/commands.c modules/actuators/actuators.c
|
||||
demo_ahrs_actuators.srcs += state.c
|
||||
demo_ahrs_actuators.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
|
||||
demo_ahrs_actuators.srcs += firmwares/demo/demo_ahrs_actuators.c
|
||||
|
||||
@@ -5,12 +5,7 @@
|
||||
#
|
||||
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_FIXEDWING=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/fixedwing
|
||||
|
||||
|
||||
# Standard Fixed Wing Code
|
||||
include $(CFG_FIXEDWING)/autopilot.makefile
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
# automatically include correct actuators for the ap target
|
||||
ACTUATOR_TARGET = ap
|
||||
|
||||
@@ -21,7 +21,6 @@
|
||||
#
|
||||
#
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_ROTORCRAFT=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/rotorcraft
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
|
||||
|
||||
@@ -21,5 +21,5 @@
|
||||
#
|
||||
#
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
|
||||
@@ -5,10 +5,9 @@
|
||||
|
||||
SRC_ARCH=arch/$(ARCH)
|
||||
SRC_BOARD=boards/$(BOARD)
|
||||
SRC_SUBSYSTEMS=subsystems
|
||||
SRC_MODULES=modules
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
SRC_FIRMWARE=firmwares/setup
|
||||
|
||||
|
||||
@@ -1,23 +0,0 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# Copyright (C) 2008 Antoine Drouin
|
||||
#
|
||||
# This file is part of paparazzi.
|
||||
#tin
|
||||
# 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.
|
||||
#
|
||||
#
|
||||
|
||||
@@ -35,10 +35,9 @@
|
||||
################################################################################
|
||||
SRC_ARCH=arch/$(ARCH)
|
||||
SRC_BOARD=boards/$(BOARD)
|
||||
SRC_SUBSYSTEMS=subsystems
|
||||
SRC_MODULES=modules
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
# Enable debug mode by default for test programs
|
||||
RTOS_DEBUG ?= 1
|
||||
|
||||
@@ -30,10 +30,9 @@
|
||||
|
||||
SRC_ARCH=arch/$(ARCH)
|
||||
SRC_BOARD=boards/$(BOARD)
|
||||
SRC_SUBSYSTEMS=subsystems
|
||||
SRC_MODULES=modules
|
||||
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares/subsystems/shared
|
||||
CFG_SHARED=$(PAPARAZZI_SRC)/conf/firmwares
|
||||
|
||||
VPATH += $(PAPARAZZI_HOME)/var/share
|
||||
|
||||
@@ -338,7 +337,7 @@ test_actuators_pwm.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_actuators_pwm.srcs += test/test_actuators_pwm.c
|
||||
test_actuators_pwm.srcs += $(SRC_ARCH)/modules/actuators/actuators_pwm_arch.c $(SRC_ARCH)/modules/actuators/actuators_shared_arch.c
|
||||
# only add this so it doesn't fail to build if you also have setup_actuators.xml settings file loaded
|
||||
# remove me again when we have auto loading of settings according to subsystem/module/target...
|
||||
# remove me again when we have auto loading of settings according to module/target...
|
||||
test_actuators_pwm.srcs += modules/actuators/actuators.c
|
||||
|
||||
|
||||
@@ -354,7 +353,7 @@ test_actuators_pwm_sin.srcs += $(SRC_ARCH)/modules/actuators/actuators_pwm_arc
|
||||
|
||||
#
|
||||
# Test manual : a simple test with rc and servos
|
||||
# add the desired actuators and radio_control subsystem to this target
|
||||
# add the desired actuators and radio_control modules to this target
|
||||
#
|
||||
test_manual.ARCHDIR = $(ARCH)
|
||||
test_manual.CFLAGS += $(COMMON_TEST_CFLAGS)
|
||||
@@ -362,7 +361,7 @@ test_manual.srcs += $(COMMON_TEST_SRCS)
|
||||
test_manual.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
||||
test_manual.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
|
||||
test_manual.srcs += subsystems/commands.c
|
||||
test_manual.srcs += modules/core/commands.c
|
||||
test_manual.srcs += modules/actuators/actuators.c
|
||||
test_manual.srcs += test/test_manual.c
|
||||
|
||||
@@ -420,7 +419,7 @@ test_adc.srcs += test/mcu_periph/test_adc.c
|
||||
#
|
||||
# test_imu
|
||||
#
|
||||
# add imu subsystem to test_imu target!
|
||||
# add imu module to test_imu target!
|
||||
#
|
||||
# configuration
|
||||
# SYS_TIME_LED
|
||||
@@ -434,14 +433,14 @@ test_imu.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
||||
test_imu.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_imu.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c
|
||||
test_imu.srcs += state.c
|
||||
test_imu.srcs += test/subsystems/test_imu.c
|
||||
test_imu.srcs += test/modules/test_imu.c
|
||||
test_imu.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
|
||||
|
||||
|
||||
#
|
||||
# test_ahrs
|
||||
#
|
||||
# add imu and ahrs subsystems to test_ahrs target!
|
||||
# add imu and ahrs modules to test_ahrs target!
|
||||
#
|
||||
# configuration
|
||||
# SYS_TIME_LED
|
||||
@@ -456,7 +455,7 @@ test_ahrs.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_ahrs.srcs += modules/datalink/telemetry.c
|
||||
test_ahrs.CFLAGS += -DPERIODIC_TELEMETRY
|
||||
test_ahrs.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c
|
||||
test_ahrs.srcs += test/subsystems/test_ahrs.c
|
||||
test_ahrs.srcs += test/modules/test_ahrs.c
|
||||
test_ahrs.srcs += state.c
|
||||
test_ahrs.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
|
||||
|
||||
@@ -471,7 +470,7 @@ test_radio_control.CFLAGS += $(COMMON_TEST_CFLAGS)
|
||||
test_radio_control.srcs += $(COMMON_TEST_SRCS)
|
||||
test_radio_control.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
||||
test_radio_control.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_radio_control.srcs += test/subsystems/test_radio_control.c
|
||||
test_radio_control.srcs += test/modules/test_radio_control.c
|
||||
|
||||
|
||||
#
|
||||
@@ -486,9 +485,9 @@ test_settings.CFLAGS += $(COMMON_TEST_CFLAGS)
|
||||
test_settings.srcs += $(COMMON_TEST_SRCS)
|
||||
test_settings.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
||||
test_settings.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_settings.srcs += subsystems/settings.c
|
||||
test_settings.srcs += $(SRC_ARCH)/subsystems/settings_arch.c
|
||||
test_settings.srcs += test/subsystems/test_settings.c
|
||||
test_settings.srcs += modules/core/settings.c
|
||||
test_settings.srcs += $(SRC_ARCH)/modules/core/settings_arch.c
|
||||
test_settings.srcs += test/modules/test_settings.c
|
||||
test_settings.CFLAGS += -DUSE_PERSISTENT_SETTINGS
|
||||
|
||||
|
||||
|
||||
@@ -53,9 +53,9 @@ TESTS:
|
||||
//Set Generic options
|
||||
#include "autopilot.h"
|
||||
//Enable AHRS Health test functions
|
||||
#include "subsystems/ahrs/ahrs_aligner.h"
|
||||
#include "modules/ahrs/ahrs_aligner.h"
|
||||
//Enable advanced electrical power functions
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
//Enable datalink tests
|
||||
#include "modules/datalink/datalink.h"
|
||||
//For interaction with the Flight termination Device (FTD)
|
||||
|
||||
@@ -14,9 +14,9 @@ Your safe aircraft operation is *your* responsibility
|
||||
//Set Generic options
|
||||
#include "autopilot.h"
|
||||
//Enable AHRS Health test functions
|
||||
#include "subsystems/ahrs/ahrs_aligner.h"
|
||||
#include "modules/ahrs/ahrs_aligner.h"
|
||||
//Enable advanced electrical power functions
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
//Enable datalink tests
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "firmwares/rotorcraft/guidance/guidance_v.h"
|
||||
|
||||
@@ -19,9 +19,9 @@ Should be unified for Hybrid, FW and rotorcraft
|
||||
//Set Generic options
|
||||
#include "autopilot.h"
|
||||
//Enable AHRS Health test functions
|
||||
#include "subsystems/ahrs/ahrs_aligner.h"
|
||||
#include "modules/ahrs/ahrs_aligner.h"
|
||||
//Enable advanced electrical power functions
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
//Enable datalink tests
|
||||
#include "modules/datalink/datalink.h"
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/actuators/actuators.h"
|
||||
#include "firmwares/rotorcraft/guidance/guidance_h.h"
|
||||
#include "firmwares/rotorcraft/guidance/guidance_hybrid.h"
|
||||
|
||||
@@ -6,8 +6,8 @@ The goal of this flightplan is to have a safe, simple no-brainer flightplan for
|
||||
<header>
|
||||
|
||||
#include "autopilot.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/datalink/datalink.h"
|
||||
|
||||
</header>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<flight_plan alt="1" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="20" name="Rotorcraft Optitrack (Delft)" security_height="2">
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/stereocam/nav_line_avoid/avoid_navigation.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
|
||||
@@ -3,9 +3,9 @@
|
||||
<flight_plan alt="1.0" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="60" name="Bebop avoid orange TU Delft Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
#define NPS_GAZEBO_WORLD "cyberzoo_orange_poles.world"
|
||||
</header>
|
||||
<waypoints>
|
||||
|
||||
@@ -3,9 +3,9 @@
|
||||
<flight_plan alt="1.0" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="60" name="Bebop avoid orange TU Delft Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
#define NPS_GAZEBO_WORLD "cyberzoo_orange_poles.world"
|
||||
#include "autopilot.h"
|
||||
inline void setNav(void){
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#ifdef dc_Survey
|
||||
#define LINE_START_FUNCTION dc_Survey(dc_distance_interval);
|
||||
#define LINE_STOP_FUNCTION {dc_autoshoot = DC_AUTOSHOOT_STOP;}
|
||||
|
||||
@@ -3,9 +3,9 @@
|
||||
<flight_plan alt="1.0" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="60" name="Nederdrone Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
#include "firmwares/rotorcraft/guidance/guidance_indi_hybrid.h"
|
||||
#include "firmwares/rotorcraft/navigation.h"
|
||||
</header>
|
||||
|
||||
@@ -3,9 +3,9 @@
|
||||
<flight_plan alt="1.0" ground_alt ="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="20" name="Bebop with stereo cam and Wedgebug TU Delft Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
#define NPS_GAZEBO_WORLD "cyberzoo2019_ralphthesis2020.world" <!-- Current world is based on "cyberzoo2019_orange_poles_panels_mats.world" and replaced the original "cyberzoo_orange_poles.world" that was used here -->
|
||||
|
||||
#include "autopilot.h"
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/datalink/datalink.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
|
||||
@@ -3,9 +3,9 @@
|
||||
<flight_plan alt="1.0" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="60" name="Safe TU Delft Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "modules/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "modules/ahrs/ahrs.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
<waypoint lat="51.990631" lon="4.376796" name="HOME"/>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<module name="board_matek_f405_wing" dir="boards">
|
||||
<doc>
|
||||
<description>
|
||||
Autoload several onboard sensors and subsystems
|
||||
Autoload several onboard sensors and modules
|
||||
for the Matek F405 Wing board with proper configuration.
|
||||
IMU MPU6000
|
||||
Baro (BMP280)
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<module name="board_matek_f765_wing" dir="boards">
|
||||
<doc>
|
||||
<description>
|
||||
Autoload several onboard sensors and subsystems
|
||||
Autoload several onboard sensors and modules
|
||||
for the Matek F765 Wing board with proper configuration.
|
||||
IMU ICM20602 (auto-detected from MPU6000 driver)
|
||||
Baro (BMP280)
|
||||
|
||||
@@ -14,7 +14,6 @@
|
||||
</dep>
|
||||
<makefile>
|
||||
<configure name="SRC_BOARD" value="boards/$(BOARD)"/>
|
||||
<configure name="SRC_SUBSYSTEMS" value="subsystems"/>
|
||||
<configure name="SRC_MODULES" value="modules"/>
|
||||
<configure name="SRC_ARCH" value="arch/$(ARCH)"/>
|
||||
<define name="BOARD_CONFIG" value="$(BOARD_CFG)"/>
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
<dl_settings NAME="flight params">
|
||||
<dl_setting MAX="1000" MIN="0" STEP="10" VAR="flight_altitude" shortname="altitude"/>
|
||||
<dl_setting MAX="360" MIN="0" STEP="1" VAR="nav_course"/>
|
||||
<dl_setting MAX="10" MIN="-10" STEP="5" VAR="nav_shift" module="subsystems/nav" handler="IncreaseShift" shortname="inc. shift"/>
|
||||
<dl_setting MAX="10" MIN="-10" STEP="5" VAR="nav_shift" module="firmwares/fixedwing/nav" handler="IncreaseShift" shortname="inc. shift"/>
|
||||
<dl_setting MAX="0" MIN="0" STEP="1" VAR="autopilot.flight_time" shortname="flight time" module="autopilot" handler="ResetFlightTimeAndLaunch"/>
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="firmwares/fixedwing/nav" handler="SetNavRadius">
|
||||
<strip_button icon="circle-right.png" name="Circle right" value="1" group="circle"/>
|
||||
<strip_button icon="circle-left.png" name="Circle left" value="-1" group="circle"/>
|
||||
<key_press key="greater" value="1"/>
|
||||
|
||||
@@ -20,7 +20,7 @@
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/>
|
||||
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="firmwares/fixedwing/nav" handler="SetNavRadius">
|
||||
<strip_button icon="circle-right.png" name="Circle right" value="1"/>
|
||||
<strip_button icon="circle-left.png" name="Circle left" value="-1"/>
|
||||
<key_press key="greater" value="1"/>
|
||||
@@ -31,7 +31,7 @@
|
||||
<dl_settings NAME="control">
|
||||
|
||||
<dl_settings NAME="ins">
|
||||
<dl_setting MAX="0.3" MIN="-0.3" STEP="0.01" VAR="ins_roll_neutral" shortname="roll_neutral" module="subsystems/ahrs" param="INS_ROLL_NEUTRAL_DEFAULT" unit="rad"/>
|
||||
<dl_setting MAX="0.3" MIN="-0.3" STEP="0.01" VAR="ins_roll_neutral" shortname="roll_neutral" module="modules/ahrs/ahrs" param="INS_ROLL_NEUTRAL_DEFAULT" unit="rad"/>
|
||||
<dl_setting MAX="0.6" MIN="-0.6" STEP="0.01" VAR="ins_pitch_neutral" shortname="pitch_neutral" param="INS_PITCH_NEUTRAL_DEFAULT" unit="rad"/>
|
||||
</dl_settings>
|
||||
|
||||
@@ -89,7 +89,7 @@
|
||||
<dl_setting MAX="2" MIN="1" STEP="1" VAR="nav_mode"/>
|
||||
<dl_setting MAX="5" MIN="-5" STEP="0.5" VAR="nav_climb"/>
|
||||
<dl_setting MAX="15" MIN="-15" STEP="1" VAR="fp_pitch"/>
|
||||
<dl_setting MAX="50" MIN="-50" STEP="5" VAR="nav_shift" module="subsystems/nav" handler="IncreaseShift" shortname="inc. shift"/>
|
||||
<dl_setting MAX="50" MIN="-50" STEP="5" VAR="nav_shift" module="firmwares/fixedwing/nav" handler="IncreaseShift" shortname="inc. shift"/>
|
||||
<dl_setting MAX="50" MIN="5" STEP="0.5" VAR="nav_ground_speed_setpoint" shortname="ground speed"/>
|
||||
<dl_setting MAX="0." MIN="-0.2" STEP="0.01" VAR="nav_ground_speed_pgain" shortname="ground speed pgain"/>
|
||||
<dl_setting MAX="500" MIN="50" STEP="5" VAR="nav_survey_shift"/>
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<dl_settings>
|
||||
|
||||
<dl_settings NAME="AHRS">
|
||||
<dl_setting var="ahrs_output_idx" min="0" step="1" max="1" values="PRIMARY|SECONDARY" module="subsystems/ahrs" shortname="ahrs output" handler="switch"/>
|
||||
<dl_setting var="ahrs_output_idx" min="0" step="1" max="1" values="PRIMARY|SECONDARY" module="modules/ahrs/ahrs" shortname="ahrs output" handler="switch"/>
|
||||
</dl_settings>
|
||||
|
||||
</dl_settings>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings NAME="ins">
|
||||
<dl_setting MAX="15" MIN="-15" STEP="0.5" VAR="ins_roll_neutral" shortname="roll_neutral" module="subsystems/ahrs" param="INS_ROLL_NEUTRAL_DEFAULT" unit="rad" alt_unit="deg" type="float" persistent="true"/>
|
||||
<dl_setting MAX="15" MIN="-15" STEP="0.5" VAR="ins_roll_neutral" shortname="roll_neutral" module="modules/ahrs/ahrs" param="INS_ROLL_NEUTRAL_DEFAULT" unit="rad" alt_unit="deg" type="float" persistent="true"/>
|
||||
<dl_setting MAX="15" MIN="-15" STEP="0.5" VAR="ins_pitch_neutral" shortname="pitch_neutral" param="INS_PITCH_NEUTRAL_DEFAULT" unit="rad" alt_unit="deg" type="float" persistent="true"/>
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings NAME="sonar">
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="ins_int.update_on_agl" shortname="use_sonar" values="FALSE|TRUE" module="subsystems/ins/vf_extended_float"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="ins_int.update_on_agl" shortname="use_sonar" values="FALSE|TRUE" module="modules/ins/vf_extended_float"/>
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
</settings>
|
||||
|
||||
@@ -3,8 +3,8 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings NAME="Persistence">
|
||||
<dl_setting var="settings_store_flag" min="1" step="1" max="1" shortname="store" handler="StoreSettings" module="subsystems/settings" values="Stored"/>
|
||||
<dl_setting var="settings_clear_flag" min="1" step="1" max="1" shortname="clear" handler="ClearSettings" module="subsystems/settings" values="Cleared"/>
|
||||
<dl_setting var="settings_store_flag" min="1" step="1" max="1" shortname="store" handler="StoreSettings" module="modules/core/settings" values="Stored"/>
|
||||
<dl_setting var="settings_clear_flag" min="1" step="1" max="1" shortname="clear" handler="ClearSettings" module="modules/core/settings" values="Cleared"/>
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
</settings>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<settings target="!sim|nps">
|
||||
<dl_settings>
|
||||
<dl_settings NAME="Superbit">
|
||||
<dl_setting var="settings_store_flag" min="1" step="1" max="1" shortname="store" handler="StoreSettings" module="subsystems/settings" values="Store"/>
|
||||
<dl_setting var="settings_store_flag" min="1" step="1" max="1" shortname="store" handler="StoreSettings" module="modules/core/settings" values="Store"/>
|
||||
<dl_setting var="superbitrf.bind_mfg_id32" type="uint32" min="0" step="1" max="4294967295" shortname ="mfg_id" persistent="true" module="modules/datalink/superbitrf" handler="set_mfg_id"/>
|
||||
<dl_setting var="superbitrf.num_channels" type="uint8" min="0" step="1" max="14" shortname ="#chan" persistent="true" module="modules/datalink/superbitrf"/>
|
||||
<dl_setting var="superbitrf.protocol" type="uint8" min="0" step="1" max="32" shortname ="prot" persistent="true" module="modules/datalink/superbitrf" handler="set_protocol"/>
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
<dl_settings>
|
||||
<dl_settings NAME="Group1">
|
||||
|
||||
<dl_setting var="setting_f" min="0" step="0.1" max="42" shortname ="f" persistent="true" type="float" module="test/subsystems/test_settings"/>
|
||||
<dl_setting var="setting_f" min="0" step="0.1" max="42" shortname ="f" persistent="true" type="float" module="test/modules/test_settings"/>
|
||||
<dl_setting var="setting_u8" min="0" step="1" max="42" shortname ="u8" persistent="true" type="uint8"/>
|
||||
<dl_setting var="setting_d" min="-42" step="0.1" max="42" shortname ="d" persistent="true" type="double"/>
|
||||
<dl_setting var="setting_i32" min="0" step="1" max="4242" shortname ="i32" persistent="true" type="int32"/>
|
||||
<dl_setting var="settings_store_flag" min="0" step="1" max="1" shortname="store" handler="StoreSettings" module="subsystems/settings"/>
|
||||
<dl_setting var="settings_store_flag" min="0" step="1" max="1" shortname="store" handler="StoreSettings" module="modules/core/settings"/>
|
||||
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
|
||||
@@ -41,7 +41,7 @@ Include header and declare an ``abi_event`` as a global ``static`` variable (but
|
||||
|
||||
.. code-block:: C
|
||||
|
||||
#include "subsystems/abi.h"
|
||||
#include "modules/core/abi.h"
|
||||
|
||||
static abi_event ev;
|
||||
|
||||
@@ -60,7 +60,7 @@ The first parameter is the sender ID you want to receive the message from.
|
||||
|
||||
* ``ABI_BROADCAST`` is used to receive messages from all senders.
|
||||
* ``ABI_DISABLE`` disable the callback (it will never be called).
|
||||
* Senders IDs can be found in the file ``sw/airborne/subsystems/abi_sender_ids.h``
|
||||
* Senders IDs can be found in the file ``sw/airborne/modules/core/abi_sender_ids.h``
|
||||
|
||||
The second parameter is a pointer to the global ``abi_event`` you declared. This variable **can't** be reused for another bind. You must declare one abi_event per bind.
|
||||
|
||||
@@ -80,7 +80,7 @@ Include header, then call the send function with the appropriate parameters
|
||||
struct foo f;
|
||||
AbiSendMsgDATA(SENDER_ID, var, s, &f);
|
||||
|
||||
Replace ``SENDER_ID`` by your sender ID defined in ``sw/airborne/subsystems/abi_sender_ids.h``.
|
||||
Replace ``SENDER_ID`` by your sender ID defined in ``sw/airborne/modules/core/abi_sender_ids.h``.
|
||||
|
||||
Your sender ID identifier should be constructed as the concatenation of the name of the message and the name of your module, suffixed with ``_ID``.
|
||||
|
||||
@@ -98,7 +98,7 @@ Your sender ID identifier should be constructed as the concatenation of the name
|
||||
Code generation
|
||||
---------------
|
||||
|
||||
The generated code will be in ``var/include/abi_messages.h`` and include some structure definition from ``sw/airborne/subsystems/abi_common.h`` (``sw/airborne/subsystems/abi.h`` is a convenience header that only includes ``var/include/abi_messages.h``).
|
||||
The generated code will be in ``var/include/abi_messages.h`` and include some structure definition from ``sw/airborne/modules/core/abi_common.h`` (``sw/airborne/modules/core/abi.h`` is a convenience header that only includes ``var/include/abi_messages.h``).
|
||||
|
||||
Bind and Send functions are generated, as well as callback type definition. A linked list is used to store the binded callbacks for each message. The head of the list is in an array to allow a fast access.
|
||||
|
||||
@@ -110,16 +110,16 @@ In depth
|
||||
Generated code
|
||||
______________
|
||||
|
||||
Here is the code of ``sw/airborne/subsystems/abi_common.h``:
|
||||
Here is the code of ``sw/airborne/modules/core/abi_common.h``:
|
||||
|
||||
.. code-block:: C
|
||||
|
||||
/* Include here headers with structure definition you may want to use with ABI
|
||||
* Ex: '#include "subsystems/gps.h"' in order to use the GpsState structure
|
||||
* Ex: '#include "modules/gps/gps.h"' in order to use the GpsState structure
|
||||
*/
|
||||
#include "subsystems/gps.h"
|
||||
#include "modules/gps/gps.h"
|
||||
|
||||
#include "subsystems/abi_sender_ids.h"
|
||||
#include "modules/core/abi_sender_ids.h"
|
||||
|
||||
#ifdef ABI_C
|
||||
#define ABI_EXTERN
|
||||
@@ -156,7 +156,7 @@ The generated code in ``var/include/abi_messages.h`` for the message defined abo
|
||||
.. code-block:: C
|
||||
|
||||
// Code generated in var/include/abi_messages.h
|
||||
#include "subsystems/abi_common.h
|
||||
#include "modules/core/abi_common.h
|
||||
// Message IDs
|
||||
#define ABI_DATA_ID 0
|
||||
|
||||
@@ -195,5 +195,5 @@ If you want to use ABI outside of one of the Paparazzi firmwares (``rotorcraft``
|
||||
.. code-block:: C
|
||||
|
||||
#define ABI_C 1
|
||||
#include "subsystems/abi.h"
|
||||
#include "modules/core/abi.h"
|
||||
|
||||
|
||||
@@ -216,7 +216,7 @@ static void adc_sample_time_on_all_channels(uint32_t *smpr1, uint32_t *smpr2, ui
|
||||
* is collected). Since we are assuming continuous ADC conversion, the ADC state is
|
||||
* never equal to ADC_COMPLETE.
|
||||
*
|
||||
* @note Averaging is done when the subsystems ask for ADC values
|
||||
* @note Averaging is done when the modules ask for ADC values
|
||||
* @param[in] adcp pointer to a @p ADCDriver object
|
||||
* @param[in] buffer pointer to a @p buffer with samples
|
||||
* @param[in] n number of samples
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
/*
|
||||
* board specific interface for the KroozSD board
|
||||
*
|
||||
* It uses the subsystems/sensors/baro_ms5611_i2c.c driver
|
||||
* It uses the modules/sensors/baro_ms5611_i2c.c driver
|
||||
*/
|
||||
|
||||
#ifndef BOARDS_KROOZ_BARO_H
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
/**
|
||||
* @file modules/imu/imu_vectornav.c
|
||||
*
|
||||
* Vectornav VN-200 IMU subsystems, to be used with other AHRS/INS algorithms.
|
||||
* Vectornav VN-200 IMU module, to be used with other AHRS/INS algorithms.
|
||||
*/
|
||||
|
||||
#include "modules/imu/imu_vectornav.h"
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
/**
|
||||
* @file modules/imu/imu_vectornav.h
|
||||
*
|
||||
* Vectornav VN-200 IMU subsystems, to be used with other AHRS/INS algorithms.
|
||||
* Vectornav VN-200 IMU module, to be used with other AHRS/INS algorithms.
|
||||
*/
|
||||
|
||||
#ifndef IMU_VECTORNAV_H
|
||||
|
||||
@@ -22,14 +22,14 @@
|
||||
/**
|
||||
* @file ins_vectornav.h
|
||||
*
|
||||
* Vectornav VN-200 INS subsystem
|
||||
* Vectornav VN-200 INS module
|
||||
*
|
||||
* @author Michal Podhradsky <michal.podhradsky@aggiemail.usu.edu>
|
||||
*/
|
||||
#ifndef INS_VECTORNAV_H
|
||||
#define INS_VECTORNAV_H
|
||||
|
||||
// Subsystems
|
||||
// Modules
|
||||
#include "modules/gps/gps.h"
|
||||
#include "modules/ins/ins.h"
|
||||
|
||||
|
||||
@@ -28,8 +28,8 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef SUBSYSTEMS_SENSORS_BARO_H
|
||||
#define SUBSYSTEMS_SENSORS_BARO_H
|
||||
#ifndef SENSORS_BARO_H
|
||||
#define SENSORS_BARO_H
|
||||
|
||||
#include BOARD_CONFIG
|
||||
|
||||
@@ -43,4 +43,4 @@
|
||||
extern void baro_init(void);
|
||||
extern void baro_periodic(void);
|
||||
|
||||
#endif /* SUBSYSTEMS_SENSORS_BARO_H */
|
||||
#endif /* SENSORS_BARO_H */
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user