From a77df87b01e053b52a2de297e01d5c2462a62e9e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 13:50:43 +1100 Subject: [PATCH] Tools: rename sim_periph_gps to sim_gps_universal, recreate sim_periph_gps --- Tools/AP_Periph/can.cpp | 1 + Tools/ardupilotwaf/boards.py | 106 ++++++++++++++++++---------- Tools/autotest/autotest.py | 12 ++-- Tools/autotest/pysim/vehicleinfo.py | 6 +- Tools/autotest/sim_vehicle.py | 8 +-- Tools/scripts/build_ci.sh | 2 +- Tools/scripts/run_coverage.py | 4 +- 7 files changed, 84 insertions(+), 55 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 9000ab4e33..e60d112951 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -34,6 +34,7 @@ #include #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL #include +#include #endif #define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 9330bb6e02..35f3ec24b8 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -837,14 +837,65 @@ class sitl(Board): return self.__class__.__name__ -class sitl_periph_gps(sitl): +class sitl_periph(sitl): def configure_env(self, cfg, env): cfg.env.AP_PERIPH = 1 - super(sitl_periph_gps, self).configure_env(cfg, env) + super(sitl_periph, self).configure_env(cfg, env) env.DEFINES.update( HAL_BUILD_AP_PERIPH = 1, PERIPH_FW = 1, - CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph"', + HAL_RAM_RESERVE_START = 0, + + CANARD_ENABLE_CANFD = 1, + CANARD_ENABLE_TAO_OPTION = 1, + CANARD_MULTI_IFACE = 1, + + # FIXME: SITL library should not be using AP_AHRS: + AP_AHRS_ENABLED = 1, + AP_AHRS_BACKEND_DEFAULT_ENABLED = 0, + AP_AHRS_DCM_ENABLED = 1, # need a default backend + HAL_EXTERNAL_AHRS_ENABLED = 0, + + HAL_MAVLINK_BINDINGS_ENABLED = 1, + + AP_AIRSPEED_AUTOCAL_ENABLE = 0, + AP_CAN_SLCAN_ENABLED = 0, + AP_ICENGINE_ENABLED = 0, + AP_MISSION_ENABLED = 0, + AP_RCPROTOCOL_ENABLED = 0, + AP_RTC_ENABLED = 0, + AP_SCHEDULER_ENABLED = 0, + AP_SCRIPTING_ENABLED = 0, + AP_STATS_ENABLED = 0, + AP_UART_MONITOR_ENABLED = 1, + COMPASS_CAL_ENABLED = 0, + COMPASS_LEARN_ENABLED = 0, + COMPASS_MOT_ENABLED = 0, + HAL_CAN_DEFAULT_NODE_ID = 0, + HAL_CANMANAGER_ENABLED = 0, + HAL_GCS_ENABLED = 0, + HAL_GENERATOR_ENABLED = 0, + HAL_LOGGING_ENABLED = 0, + HAL_LOGGING_MAVLINK_ENABLED = 0, + HAL_PROXIMITY_ENABLED = 0, + HAL_RALLY_ENABLED = 0, + HAL_SUPPORT_RCOUT_SERIAL = 0, + AP_TERRAIN_AVAILABLE = 0, + ) + + try: + env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=1') + except ValueError: + pass + env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0'] + +class sitl_periph_universal(sitl_periph): + def configure_env(self, cfg, env): + super(sitl_periph_universal, self).configure_env(cfg, env) + env.DEFINES.update( + CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_universal"', + APJ_BOARD_ID = 100, + HAL_PERIPH_ENABLE_GPS = 1, HAL_PERIPH_ENABLE_AIRSPEED = 1, HAL_PERIPH_ENABLE_MAG = 1, @@ -856,48 +907,25 @@ class sitl_periph_gps(sitl): HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1, - AP_ICENGINE_ENABLED = 0, AP_AIRSPEED_ENABLED = 1, - AP_AIRSPEED_AUTOCAL_ENABLE = 0, - AP_AHRS_ENABLED = 1, - AP_UART_MONITOR_ENABLED = 1, - HAL_CAN_DEFAULT_NODE_ID = 0, - HAL_RAM_RESERVE_START = 0, - APJ_BOARD_ID = 100, - HAL_GCS_ENABLED = 0, - HAL_MAVLINK_BINDINGS_ENABLED = 1, - HAL_LOGGING_ENABLED = 0, - HAL_LOGGING_MAVLINK_ENABLED = 0, - AP_MISSION_ENABLED = 0, - HAL_RALLY_ENABLED = 0, - AP_SCHEDULER_ENABLED = 0, - CANARD_ENABLE_TAO_OPTION = 1, - AP_RCPROTOCOL_ENABLED = 0, - CANARD_ENABLE_CANFD = 1, - CANARD_MULTI_IFACE = 1, - HAL_CANMANAGER_ENABLED = 0, - COMPASS_CAL_ENABLED = 0, - COMPASS_MOT_ENABLED = 0, - COMPASS_LEARN_ENABLED = 0, AP_BATTERY_ESC_ENABLED = 1, - HAL_EXTERNAL_AHRS_ENABLED = 0, - HAL_GENERATOR_ENABLED = 0, - AP_STATS_ENABLED = 0, - HAL_SUPPORT_RCOUT_SERIAL = 0, - AP_CAN_SLCAN_ENABLED = 0, - HAL_PROXIMITY_ENABLED = 0, - AP_SCRIPTING_ENABLED = 0, - HAL_NAVEKF3_AVAILABLE = 0, HAL_PWM_COUNT = 32, HAL_WITH_ESC_TELEM = 1, - AP_RTC_ENABLED = 0, + AP_TERRAIN_AVAILABLE = 1, ) - try: - env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=1') - except ValueError: - pass - env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0'] +class sitl_periph_gps(sitl_periph): + def configure_env(self, cfg, env): + cfg.env.AP_PERIPH = 1 + super(sitl_periph_gps, self).configure_env(cfg, env) + env.DEFINES.update( + HAL_BUILD_AP_PERIPH = 1, + PERIPH_FW = 1, + CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_gps"', + APJ_BOARD_ID = 101, + + HAL_PERIPH_ENABLE_GPS = 1, + ) class esp32(Board): abstract = True diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 616411b716..970dc3bde0 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -286,7 +286,7 @@ __bin_names = { "Blimp": "blimp", "BalanceBot": "ardurover", "Sailboat": "ardurover", - "SITLPeriphGPS": "sitl_periph_gp.AP_Periph", + "SITLPeriphUniversal": "sitl_periph_universal.AP_Periph", "CAN": "arducopter", } @@ -362,8 +362,8 @@ tester_class_map = { } supplementary_test_binary_map = { - "test.CAN": ["sitl_periph_gps:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 - "sitl_periph_gps:AP_Periph:1:Tools/autotest/default_params/periph.parm"], + "test.CAN": ["sitl_periph_universal:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 + "sitl_periph_universal:AP_Periph:1:Tools/autotest/default_params/periph.parm"], } @@ -441,8 +441,8 @@ def run_step(step): if step == 'build.Sub': vehicle_binary = 'bin/ardusub' - if step == 'build.SITLPeriphGPS': - vehicle_binary = 'sitl_periph_gps.bin/AP_Periph' + if step == 'build.SITLPeriphUniversal': + vehicle_binary = 'sitl_periph_universal.bin/AP_Periph' if step == 'build.Replay': return util.build_replay(board='SITL') @@ -1085,7 +1085,7 @@ if __name__ == "__main__": 'build.Blimp', 'test.Blimp', - 'build.SITLPeriphGPS', + 'build.SITLPeriphUniversal', 'test.CAN', # convertgps disabled as it takes 5 hours diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 9709dcd917..0bba801933 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -424,10 +424,10 @@ class VehicleInfo(object): }, }, }, - "sitl_periph_gps": { + "sitl_periph_universal": { "frames": { - "gps": { - "configure_target": "sitl_periph_gps", + "universal": { + "configure_target": "sitl_periph_universal", "waf_target": "bin/AP_Periph", "default_params_filename": "default_params/periph.parm", }, diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 1b46b85a87..80e19d40ae 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -672,8 +672,8 @@ def start_antenna_tracker(opts): def start_CAN_Periph(opts, frame_info): """Compile and run the sitl_periph""" - progress("Preparing sitl_periph_gps") - options = vinfo.options["sitl_periph_gps"]['frames']['gps'] + progress("Preparing sitl_periph_universal") + options = vinfo.options["sitl_periph_universal"]['frames']['universal'] defaults_path = frame_info.get('periph_params_filename', None) if defaults_path is None: defaults_path = options.get('default_params_filename', None) @@ -686,9 +686,9 @@ def start_CAN_Periph(opts, frame_info): if not cmd_opts.no_rebuild: do_build(opts, options) - exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph') + exe = os.path.join(root_dir, 'build/sitl_periph_universal', 'bin/AP_Periph') cmd = ["nice"] - cmd_name = "sitl_periph_gps" + cmd_name = "sitl_periph_universal" if opts.valgrind: cmd_name += " (valgrind)" cmd.append("valgrind") diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 84bb812a73..57e9082911 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -132,7 +132,7 @@ for t in $CI_BUILD_TARGET; do echo "Building SITL Periph GPS" $waf configure --board sitl $waf copter - run_autotest "Copter" "build.SITLPeriphGPS" "test.CAN" + run_autotest "Copter" "build.SITLPeriphUniversal" "test.CAN" continue fi if [ "$t" == "sitltest-plane" ]; then diff --git a/Tools/scripts/run_coverage.py b/Tools/scripts/run_coverage.py index ee6e4c24a3..0003698212 100755 --- a/Tools/scripts/run_coverage.py +++ b/Tools/scripts/run_coverage.py @@ -238,8 +238,8 @@ class CoverageRunner(object): root_dir + "/build/linux/modules/*", root_dir + "/build/sitl/libraries/*", root_dir + "/build/sitl/modules/*", - root_dir + "/build/sitl_periph_gps/libraries/*", - root_dir + "/build/sitl_periph_gps/modules/*", + root_dir + "/build/sitl_periph_universal/libraries/*", + root_dir + "/build/sitl_periph_universal/modules/*", root_dir + "/libraries/*/examples/*", root_dir + "/libraries/*/tests/*", "-o", self.INFO_FILE