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

Correct compilation when most features out, one in #21878

Merged
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
73 changes: 66 additions & 7 deletions Tools/autotest/test_build_options.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3

"""
Contains functions used to test the ArduPilot build_options.py structures
Expand All @@ -22,6 +22,7 @@ def __init__(self,
do_step_disable_none=False,
do_step_disable_defaults=True,
do_step_disable_in_turn=True,
do_step_enable_in_turn=True,
build_targets=None,
board="DevEBoxH7v2",
extra_hwdef=None):
Expand All @@ -32,6 +33,7 @@ def __init__(self,
self.do_step_disable_none = do_step_disable_none
self.do_step_run_with_defaults = do_step_disable_defaults
self.do_step_disable_in_turn = do_step_disable_in_turn
self.do_step_enable_in_turn = do_step_enable_in_turn
self.build_targets = build_targets
if self.build_targets is None:
self.build_targets = self.all_targets()
Expand Down Expand Up @@ -64,7 +66,7 @@ def write_defines_to_file(self, defines, filepath):
with open(filepath, "w") as f:
f.write(content)

def get_defines(self, feature, options):
def get_disable_defines(self, feature, options):
'''returns a hash of (name, value) defines to turn feature off -
recursively gets dependencies'''
ret = {
Expand All @@ -89,8 +91,30 @@ def get_defines(self, feature, options):
break
return ret

def test_feature(self, feature, options):
defines = self.get_defines(feature, options)
def update_get_enable_defines_for_feature(self, ret, feature, options):
'''recursive function to turn on required feature and what it depends
on'''
ret[feature.define] = 1
if feature.dependency is None:
return
for depname in feature.dependency.split(','):
dep = None
for f in options:
if f.label == depname:
dep = f
if dep is None:
raise ValueError("Invalid dep (%s) for feature (%s)" %
(depname, feature.label))
self.update_get_enable_defines_for_feature(ret, dep, options)

def get_enable_defines(self, feature, options):
'''returns a hash of (name, value) defines to turn all features *but* feature (and whatever it depends on) on'''
ret = self.get_disable_all_defines()
self.update_get_enable_defines_for_feature(ret, feature, options)
return ret

def test_disable_feature(self, feature, options):
defines = self.get_disable_defines(feature, options)

if len(defines.keys()) > 1:
self.progress("Disabling %s disables (%s)" % (
Expand All @@ -99,6 +123,18 @@ def test_feature(self, feature, options):

self.test_compile_with_defines(defines)

def test_enable_feature(self, feature, options):
defines = self.get_enable_defines(feature, options)

enabled = list(filter(lambda x : bool(defines[x]), defines.keys()))

if len(enabled) > 1:
self.progress("Enabling %s enables (%s)" % (
feature.define,
",".join(enabled)))

self.test_compile_with_defines(defines)

def board(self):
'''returns board to build for'''
return self._board
Expand Down Expand Up @@ -156,24 +192,40 @@ def run_disable_in_turn(self):
for feature in options:
self.progress("Disabling feature %s(%s) (%u/%u)" %
(feature.label, feature.define, count, len(options)))
self.test_feature(feature, options)
self.test_disable_feature(feature, options)
count += 1
self.disable_in_turn_check_sizes(feature, self.sizes_nothing_disabled)

def run_enable_in_turn(self):
options = self.get_build_options_from_ardupilot_tree()
if self.match_glob is not None:
options = list(filter(lambda x : fnmatch.fnmatch(x.define, self.match_glob), options))
count = 1
for feature in options:
self.progress("Enabling feature %s(%s) (%u/%u)" %
(feature.label, feature.define, count, len(options)))
self.test_enable_feature(feature, options)
count += 1

def get_option_by_label(self, label, options):
for x in options:
if x.label == label:
return x
raise ValueError("No such option (%s)" % label)

def run_disable_all(self):
def get_disable_all_defines(self):
'''returns a hash of defines which turns all features off'''
options = self.get_build_options_from_ardupilot_tree()
defines = {}
for feature in options:
if self.match_glob is not None:
if not fnmatch.fnmatch(feature.define, self.match_glob):
continue
defines[feature.define] = 0
return defines

def run_disable_all(self):
defines = self.get_disable_all_defines()
self.test_compile_with_defines(defines)

def run_disable_none(self):
Expand All @@ -191,7 +243,7 @@ def check_deps_consistency(self):
# self.progress("Checking deps consistency")
options = self.get_build_options_from_ardupilot_tree()
for feature in options:
self.get_defines(feature, options)
self.get_disable_defines(feature, options)

def run(self):
self.check_deps_consistency()
Expand All @@ -207,6 +259,9 @@ def run(self):
if self.do_step_disable_in_turn:
self.progress("Running disable-in-turn step")
self.run_disable_in_turn()
if self.do_step_enable_in_turn:
self.progress("Running enable-in-turn step")
self.run_enable_in_turn()


if __name__ == '__main__':
Expand All @@ -228,6 +283,9 @@ def run(self):
parser.add_option("--no-disable-in-turn",
action='store_true',
help='Do not run the disable-in-turn step')
parser.add_option("--no-enable-in-turn",
action='store_true',
help='Do not run the enable-in-turn step')
parser.add_option("--build-targets",
type='choice',
choices=TestBuildOptions.all_targets(),
Expand All @@ -250,6 +308,7 @@ def run(self):
do_step_disable_none=not opts.no_disable_none,
do_step_disable_defaults=not opts.no_run_with_defaults,
do_step_disable_in_turn=not opts.no_disable_in_turn,
do_step_enable_in_turn=not opts.no_enable_in_turn,
build_targets=opts.build_targets,
board=opts.board,
extra_hwdef=opts.extra_hwdef,
Expand Down
2 changes: 2 additions & 0 deletions Tools/scripts/build_ci.sh
Original file line number Diff line number Diff line change
Expand Up @@ -373,12 +373,14 @@ for t in $CI_BUILD_TARGET; do
--no-disable-all \
--no-disable-none \
--no-disable-in-turn \
--no-enable-in-turn \
--board=CubeOrange \
--build-targets=copter \
--build-targets=plane
echo "Checking all/none options in build_options.py work"
time ./Tools/autotest/test_build_options.py \
--no-disable-in-turn \
--no-enable-in-turn \
--build-targets=copter \
--build-targets=plane
continue
Expand Down
16 changes: 9 additions & 7 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ def __init__(self,
Feature('Ident', 'AIS', 'AP_AIS_ENABLED', 'Enable AIS', 0, None),

Feature('Telemetry', 'CRSF', 'HAL_CRSF_TELEM_ENABLED', 'Enable CRSF Telemetry', 0, None),
Feature('Telemetry', 'CRSFText', 'HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'Enable CRSF Text Param Selection', 0, 'CRSF'),
Feature('Telemetry', 'CRSFText', 'HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'Enable CRSF Text Param Selection', 0, 'CRSF,OSD_PARAM'), # NOQA: E501
Feature('Telemetry', 'HIGHLAT2', 'HAL_HIGH_LATENCY2_ENABLED', 'Enable HighLatency2 Support', 0, None),
Feature('Telemetry', 'HOTT', 'HAL_HOTT_TELEM_ENABLED', 'Enable HOTT Telemetry', 0, None),
Feature('Telemetry', 'SPEKTRUM', 'HAL_SPEKTRUM_TELEM_ENABLED', 'Enable Spektrum Telemetry', 0, None),
Expand All @@ -71,7 +71,9 @@ def __init__(self,

Feature('ICE', 'ICE Engine', 'AP_ICENGINE_ENABLED', 'Enable Internal Combustion Engine support', 0, 'RPM'),
Feature('ICE', 'EFI', 'HAL_EFI_ENABLED', 'Enable EFI Monitoring', 0, None),
Feature('ICE', 'EFI_NMPWU', 'HAL_EFI_NWPWU_ENABLED', 'Enable EFI NMPMU', 0, None),
Feature('ICE', 'EFI_NMPWU', 'HAL_EFI_NWPWU_ENABLED', 'Enable EFI NMPMU', 0, 'EFI'),
Feature('ICE', 'EFI_CURRAWONGECU', 'HAL_EFI_CURRAWONG_ECU_ENABLED', 'Enable EFI Currawong ECU', 0, 'EFI'),
Feature('ICE', 'EFI_DRONECAN', 'HAL_EFI_DRONECAN_ENABLED', 'Enable EFI DroneCAN', 0, 'EFI'),
Feature('ICE', 'GENERATOR', 'HAL_GENERATOR_ENABLED', 'Enable Generator', 0, None),

Feature('OSD', 'OSD', 'OSD_ENABLED', 'Enable OSD', 0, None),
Expand Down Expand Up @@ -124,8 +126,8 @@ def __init__(self,

Feature('Rangefinder', 'RANGEFINDER', 'AP_RANGEFINDER_ENABLED', "Enable Rangefinders", 0, None), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_ANALOG', 'AP_RANGEFINDER_ANALOG_ENABLED', "Enable Rangefinder - Analog", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_BBB_PRU', 'AP_RANGEFINDER_BBB_PRU_ENABLED', "Enable Rangefinder - BBB PRU", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_BEBOP', 'AP_RANGEFINDER_BEBOP_ENABLED', "Enable Rangefinder - Bebop", 0, "RANGEFINDER"), # NOQA: E501
# Feature('Rangefinder', 'RANGEFINDER_BBB_PRU', 'AP_RANGEFINDER_BBB_PRU_ENABLED', "Enable Rangefinder - BBB PRU", 0, "RANGEFINDER"), # NOQA: E501
# Feature('Rangefinder', 'RANGEFINDER_BEBOP', 'AP_RANGEFINDER_BEBOP_ENABLED', "Enable Rangefinder - Bebop", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_CAN', 'AP_RANGEFINDER_BENEWAKE_CAN_ENABLED', "Enable Rangefinder - Benewake (CAN)", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_TF02', 'AP_RANGEFINDER_BENEWAKE_TF02_ENABLED', "Enable Rangefinder - Benewake -TF02", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_TF03', 'AP_RANGEFINDER_BENEWAKE_TF03_ENABLED', "Enable Rangefinder - Benewake - TF03", 0, "RANGEFINDER"), # NOQA: E501
Expand All @@ -145,7 +147,7 @@ def __init__(self,
Feature('Rangefinder', 'RANGEFINDER_NMEA', 'AP_RANGEFINDER_NMEA_ENABLED', "Enable Rangefinder - NMEA", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_PULSEDLIGHTLRF', 'AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED', "Enable Rangefinder - PulsedLightLRF", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_PWM', 'AP_RANGEFINDER_PWM_ENABLED', "Enable Rangefinder - PWM", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_SIM', 'AP_RANGEFINDER_SIM_ENABLED', "Enable Rangefinder - SIM", 0, "RANGEFINDER"), # NOQA: E501
# Feature('Rangefinder', 'RANGEFINDER_SIM', 'AP_RANGEFINDER_SIM_ENABLED', "Enable Rangefinder - SIM", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_TRI2C', 'AP_RANGEFINDER_TRI2C_ENABLED', "Enable Rangefinder - TeraRangerI2C", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_TR_SERIAL', 'AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED', "Enable Rangefinder - TeraRanger Serial", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_UAVCAN', 'AP_RANGEFINDER_UAVCAN_ENABLED', "Enable Rangefinder - UAVCAN", 0, "RANGEFINDER"), # NOQA: E501
Expand All @@ -169,7 +171,7 @@ def __init__(self,
Feature('Sensors', 'BMP388', 'AP_BARO_BMP388_ENABLED', 'Enable BMP388 Barometric Sensor', 1, None),
Feature('Sensors', 'DPS280', 'AP_BARO_DPS280_ENABLED', 'Enable DPS280 Barometric Sensor', 1, None),
Feature('Sensors', 'DUMMY', 'AP_BARO_DUMMY_ENABLED', 'Enable DUMMY Barometric Sensor', 0, None),
Feature('Sensors', 'EXTERNALAHRS', 'AP_BARO_EXTERNALAHRS_ENABLED', 'Enable EXTERNALAHRS Barometric Sensor', 0, None),
Feature('Sensors', 'EXTERNALAHRS', 'AP_BARO_EXTERNALAHRS_ENABLED', 'Enable EXTERNALAHRS Barometric Sensor', 0, 'AHRS_EXT'),
Feature('Sensors', 'FBM320', 'AP_BARO_FBM320_ENABLED', 'Enable FBM320 Barometric Sensor', 1, None),
Feature('Sensors', 'ICM20789', 'AP_BARO_ICM20789_ENABLED', 'Enable ICM20789 Barometric Sensor', 1, None),
Feature('Sensors', 'KELLERLD', 'AP_BARO_KELLERLD_ENABLED', 'Enable KELLERLD Barometric Sensor', 1, None),
Expand Down Expand Up @@ -225,4 +227,4 @@ def __init__(self,
Feature('Payload', 'Camera', 'AP_CAMERA_ENABLED', 'Enable Camera Trigger support', 0, None),
]

BUILD_OPTIONS.sort(key=lambda x: x.category)
BUILD_OPTIONS.sort(key=lambda x: (x.category + x.label))
2 changes: 2 additions & 0 deletions libraries/AP_RPM/AP_RPM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,6 +258,7 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const
{
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
switch (_params[i].type) {
#if AP_RPM_PIN_ENABLED
case RPM_TYPE_PWM:
case RPM_TYPE_PIN:
if (_params[i].pin == -1) {
Expand All @@ -274,6 +275,7 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const
return false;
}
break;
#endif
}
}
return true;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,13 @@
#if AP_RANGEFINDER_SIM_ENABLED

#include <AP_HAL/AP_HAL.h>
#include <SITL/SITL.h>

/*
constructor - registers instance at top RangeFinder driver
*/
AP_RangeFinder_SITL::AP_RangeFinder_SITL(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, uint8_t instance) :
AP_RangeFinder_Backend(_state, _params),
sitl(AP::sitl()),
_instance(instance)
{}

Expand All @@ -32,7 +32,7 @@ AP_RangeFinder_SITL::AP_RangeFinder_SITL(RangeFinder::RangeFinder_State &_state,
*/
void AP_RangeFinder_SITL::update(void)
{
const float dist = sitl->get_rangefinder(_instance);
const float dist = AP::sitl()->get_rangefinder(_instance);

// negative distance means nothing is connected
if (is_negative(dist)) {
Expand Down
5 changes: 0 additions & 5 deletions libraries/AP_RangeFinder/AP_RangeFinder_SITL.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@

#if AP_RANGEFINDER_SIM_ENABLED

#include <SITL/SITL.h>

class AP_RangeFinder_SITL : public AP_RangeFinder_Backend {
public:
// constructor. This incorporates initialisation as well.
Expand All @@ -40,9 +38,6 @@ class AP_RangeFinder_SITL : public AP_RangeFinder_Backend {
return MAV_DISTANCE_SENSOR_UNKNOWN;
}

private:
SITL::SIM *sitl;

uint8_t _instance;

};
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_UAVCAN/AP_UAVCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,7 +352,7 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
#if AP_RANGEFINDER_UAVCAN_ENABLED
AP_RangeFinder_UAVCAN::subscribe_msgs(this);
#endif
#if HAL_EFI_ENABLED
#if HAL_EFI_DRONECAN_ENABLED
AP_EFI_DroneCAN::subscribe_msgs(this);
#endif

Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_AirSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -334,7 +334,7 @@ void AirSim::recv_fdm(const sitl_input& input)
}

// Update Rangefinder data, max sensors limit as defined
uint8_t rng_sensor_count = MIN(state.rng.rng_distances.length, RANGEFINDER_MAX_INSTANCES);
uint8_t rng_sensor_count = MIN(state.rng.rng_distances.length, ARRAY_SIZE(rangefinder_m));
for (uint8_t i=0; i<rng_sensor_count; i++) {
rangefinder_m[i] = state.rng.rng_distances.data[i];
}
Expand Down
4 changes: 2 additions & 2 deletions libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ Aircraft::Aircraft(const char *frame_str) :
}

// init rangefinder array to -1 to signify no data
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++){
for (uint8_t i = 0; i < ARRAY_SIZE(rangefinder_m); i++){
rangefinder_m[i] = -1.0f;
}
}
Expand Down Expand Up @@ -954,7 +954,7 @@ void Aircraft::update_external_payload(const struct sitl_input &input)

{
const float range = rangefinder_range();
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
for (uint8_t i=0; i<ARRAY_SIZE(rangefinder_m); i++) {
rangefinder_m[i] = range;
}
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_Aircraft.h
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ class Aircraft {
} scanner;

// Rangefinder
float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
float rangefinder_m[SITL_NUM_RANGEFINDERS];

// Windvane apparent wind
struct {
Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -663,7 +663,7 @@ Vector3f SIM::convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro)

// get the rangefinder reading for the desired rotation, returns -1 for no data
float SIM::get_rangefinder(uint8_t instance) {
if (instance < RANGEFINDER_MAX_INSTANCES) {
if (instance < ARRAY_SIZE(state.rangefinder_m)) {
return state.rangefinder_m[instance];
}
return -1;
Expand Down
4 changes: 2 additions & 2 deletions libraries/SITL/SITL.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
#include "SIM_IntelligentEnergy24.h"
#include "SIM_Ship.h"
#include "SIM_GPS.h"
#include <AP_RangeFinder/AP_RangeFinder.h>

namespace SITL {

Expand Down Expand Up @@ -78,7 +77,8 @@ struct sitl_fdm {
struct float_array ranges;
} scanner;

float rangefinder_m[RANGEFINDER_MAX_INSTANCES];
#define SITL_NUM_RANGEFINDERS 10
float rangefinder_m[SITL_NUM_RANGEFINDERS];
float airspeed_raw_pressure[AIRSPEED_MAX_SENSORS];

struct {
Expand Down