Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rename sim_periph_gps to sim_gps_universal, recreate sim_periph_gps #25961

Merged
merged 6 commits into from
Jan 16, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/test_coverage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ jobs:
Tools/scripts/run_coverage.py -f
else
Tools/scripts/run_coverage.py -i
./waf configure --board sitl_periph_gps --debug --coverage
./waf configure --board sitl_periph_universal --debug --coverage
./waf build --target bin/AP_Periph
Tools/scripts/run_coverage.py -i
Tools/autotest/autotest.py test.CAN --debug --coverage
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -187,12 +187,12 @@ jobs:
PATH="/github/home/.local/bin:$PATH"
python modules/DroneCAN/dronecan_dsdlc/dronecan_dsdlc.py -O dsdlc_generated modules/DroneCAN/DSDL/uavcan modules/DroneCAN/DSDL/dronecan modules/DroneCAN/DSDL/com --run-test

- name: build sitl_periph_gps
- name: build sitl_periph_universal
shell: bash
run: |
git config --global --add safe.directory ${GITHUB_WORKSPACE}
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl_periph_gps
./waf configure --board sitl_periph_universal
./waf build --target bin/AP_Periph
ccache -s
ccache -z
Expand Down
1 change: 1 addition & 0 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_SITL/CANSocketIface.h>
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#endif

#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U)
Expand Down
106 changes: 67 additions & 39 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -837,14 +837,65 @@ def get_name(self):
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,
Expand All @@ -856,48 +907,25 @@ def configure_env(self, cfg, env):
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
Expand Down
12 changes: 6 additions & 6 deletions Tools/autotest/autotest.py
Original file line number Diff line number Diff line change
Expand Up @@ -286,7 +286,7 @@ def should_run_step(step):
"Blimp": "blimp",
"BalanceBot": "ardurover",
"Sailboat": "ardurover",
"SITLPeriphGPS": "sitl_periph_gp.AP_Periph",
"SITLPeriphUniversal": "sitl_periph_universal.AP_Periph",
"CAN": "arducopter",
}

Expand Down Expand Up @@ -362,8 +362,8 @@ def find_specific_test_to_run(step):
}

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"],
}


Expand Down Expand Up @@ -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')
Expand Down Expand Up @@ -1085,7 +1085,7 @@ def format_epilog(self, formatter):
'build.Blimp',
'test.Blimp',

'build.SITLPeriphGPS',
'build.SITLPeriphUniversal',
'test.CAN',

# convertgps disabled as it takes 5 hours
Expand Down
6 changes: 3 additions & 3 deletions Tools/autotest/pysim/vehicleinfo.py
Original file line number Diff line number Diff line change
Expand Up @@ -424,10 +424,10 @@ def __init__(self):
},
},
},
"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",
},
Expand Down
8 changes: 4 additions & 4 deletions Tools/autotest/sim_vehicle.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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")
Expand Down
2 changes: 1 addition & 1 deletion Tools/scripts/build_ci.sh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions Tools/scripts/run_coverage.py
Original file line number Diff line number Diff line change
Expand Up @@ -238,8 +238,8 @@ def update_stats(self) -> None:
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
Expand Down
29 changes: 16 additions & 13 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1932,35 +1932,38 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const

#if AP_AHRS_DCM_ENABLED
// Handle fallback for fixed wing planes (including VTOL's) and ground vehicles.
if (ret != EKFType::DCM &&
(_vehicle_class == VehicleClass::FIXED_WING ||
_vehicle_class == VehicleClass::GROUND)) {

if (_vehicle_class == VehicleClass::FIXED_WING ||
_vehicle_class == VehicleClass::GROUND) {
bool should_use_gps = true;
nav_filter_status filt_state;
nav_filter_status filt_state {};
switch (ret) {
case EKFType::DCM:
// already using DCM
break;
#if HAL_NAVEKF2_AVAILABLE
if (ret == EKFType::TWO) {
case EKFType::TWO:
EKF2.getFilterStatus(filt_state);
should_use_gps = EKF2.configuredToUseGPSForPosXY();
}
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
if (ret == EKFType::THREE) {
case EKFType::THREE:
EKF3.getFilterStatus(filt_state);
should_use_gps = EKF3.configuredToUseGPSForPosXY();
}
break;
#endif
#if AP_AHRS_SIM_ENABLED
if (ret == EKFType::SIM) {
case EKFType::SIM:
get_filter_status(filt_state);
}
break;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
if (ret == EKFType::EXTERNAL) {
case EKFType::EXTERNAL:
get_filter_status(filt_state);
should_use_gps = true;
}
break;
#endif
}

// Handle fallback for the case where the DCM or EKF is unable to provide attitude or height data.
const bool can_use_dcm = dcm.yaw_source_available() || fly_forward;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@
#endif

#ifndef HAL_NAVEKF3_AVAILABLE
#define HAL_NAVEKF3_AVAILABLE AP_INERTIALSENSOR_ENABLED
#define HAL_NAVEKF3_AVAILABLE AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED
#endif

#ifndef AP_AHRS_SIM_ENABLED
#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED && AP_INERTIALSENSOR_ENABLED
#define AP_AHRS_SIM_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED && AP_INERTIALSENSOR_ENABLED
#endif

#ifndef AP_AHRS_POSITION_RESET_ENABLED
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_CheckFirmware/AP_CheckFirmware.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ enum class check_fw_result_t : uint8_t {
#endif

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(APJ_BOARD_ID)
// this allows for sitl_periph_gps to build
// this allows for sitl_periph to build
#define APJ_BOARD_ID 0
#endif

Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Relay/AP_Relay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@
#include <AP_CANManager/AP_CANManager.h>
#endif

#if AP_SIM_ENABLED
#include <SITL/SITL.h>
#endif

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define RELAY1_PIN_DEFAULT 13

Expand Down