Skip to content

Commit

Permalink
Merge branch 'master' into jte_fs_deadreckoning
Browse files Browse the repository at this point in the history
  • Loading branch information
joeyeckstrom authored Jan 30, 2025
2 parents 8128f68 + d529601 commit 2ec2c2f
Show file tree
Hide file tree
Showing 100 changed files with 663 additions and 206 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -807,7 +807,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che

// save compass offsets learned by the EKF if enabled
Compass &compass = AP::compass();
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -962,7 +962,6 @@ Copter::Copter(void)
flight_modes(&g.flight_mode1),
pos_variance_filt(FS_EKF_FILT_DEFAULT),
vel_variance_filt(FS_EKF_FILT_DEFAULT),
hgt_variance_filt(FS_EKF_FILT_DEFAULT),
flightmode(&mode_stabilize),
simple_cos_yaw(1.0f),
super_simple_cos_yaw(1.0),
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,6 @@ class Copter : public AP_Vehicle {
// thus failsafes should be triggered on filtered values in order to avoid transient errors
LowPassFilterFloat pos_variance_filt;
LowPassFilterFloat vel_variance_filt;
LowPassFilterFloat hgt_variance_filt;
bool variances_valid;
uint32_t last_ekf_check_us;

Expand Down
1 change: 0 additions & 1 deletion ArduCopter/ekf_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,6 @@ bool Copter::ekf_over_threshold()
// always update filtered values as this serves the vibration check as well
position_var = pos_variance_filt.apply(position_var, dt);
vel_var = vel_variance_filt.apply(vel_var, dt);
height_var = hgt_variance_filt.apply(height_var, dt);

last_ekf_check_us = now_us;

Expand Down
1 change: 0 additions & 1 deletion ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,6 @@ void Copter::init_ardupilot()

pos_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
vel_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
hgt_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);

// flag that initialisation has completed
ap.initialised = true;
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/toy_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1079,9 +1079,9 @@ void ToyMode::arm_check_compass(void)
if (offsets.length() > copter.compass.get_offsets_max() ||
field < 200 || field > 800 ||
!copter.compass.configured(unused_compass_configured_error_message, ARRAY_SIZE(unused_compass_configured_error_message))) {
if (copter.compass.get_learn_type() != Compass::LEARN_INFLIGHT) {
if (copter.compass.get_learn_type() != Compass::LearnType::INFLIGHT) {
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: enable compass learning");
copter.compass.set_learn_type(Compass::LEARN_INFLIGHT, false);
copter.compass.set_learn_type(Compass::LearnType::INFLIGHT, false);
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/AP_Arming_Sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks
auto &ahrs = AP::ahrs();

// save compass offsets learned by the EKF if enabled
if (ahrs.use_compass() && AP::compass().get_learn_type() == Compass::LEARN_EKF) {
if (ahrs.use_compass() && AP::compass().get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
Expand Down
2 changes: 1 addition & 1 deletion Blimp/AP_Arming_Blimp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_chec

// save compass offsets learned by the EKF if enabled
Compass &compass = AP::compass();
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ void AP_Periph_FW::init()
}
#endif // AP_PERIPH_GPS_ENABLED

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
compass.init();
#endif

Expand Down Expand Up @@ -425,7 +425,7 @@ void AP_Periph_FW::update()
#if AP_PERIPH_GPS_ENABLED
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
const Vector3f &field = compass.get_field();
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
#endif
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ class AP_Periph_FW {
AP_NMEA_Output nmea;
#endif

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
Compass compass;
#endif

Expand Down Expand Up @@ -449,7 +449,7 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_EFI
uint32_t last_efi_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
uint32_t last_mag_update_ms;
#endif
#if AP_PERIPH_GPS_ENABLED
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,7 +263,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GSCALAR(battery_hide_mask, "BATT_HIDE_MASK", HAL_PERIPH_BATT_HIDE_MASK_DEFAULT),
#endif

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
GOBJECT(compass, "COMPASS_", Compass),
Expand Down
6 changes: 3 additions & 3 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,7 +352,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
#if AP_PERIPH_BATTERY_ENABLED
AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
AP_Param::setup_object_defaults(&compass, compass.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
Expand Down Expand Up @@ -1611,7 +1611,7 @@ void AP_Periph_FW::can_start()
}
}
if (!has_uavcan_at_1MHz) {
g.can_protocol[0].set_and_save(uint8_t(AP_CAN::Protocol::DroneCAN));
g.can_protocol[0].set_and_save(AP_CAN::Protocol::DroneCAN);
g.can_baudrate[0].set_and_save(1000000);
}
#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz
Expand Down Expand Up @@ -1882,7 +1882,7 @@ void AP_Periph_FW::can_update()
if (!hal.run_in_maintenance_mode())
#endif
{
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
can_mag_update();
#endif
#if AP_PERIPH_GPS_ENABLED
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/compass.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED

/*
magnetometer support
Expand Down Expand Up @@ -97,4 +97,4 @@ void AP_Periph_FW::can_mag_update(void)
#endif // AP_PERIPH_MAG_HIRES
}

#endif // HAL_PERIPH_ENABLE_MAG
#endif // AP_PERIPH_MAG_ENABLED
6 changes: 3 additions & 3 deletions Tools/AP_Periph/msp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void AP_Periph_FW::msp_sensor_update(void)
#ifdef HAL_PERIPH_ENABLE_BARO
send_msp_baro();
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
send_msp_compass();
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down Expand Up @@ -151,7 +151,7 @@ void AP_Periph_FW::send_msp_baro(void)
}
#endif // HAL_PERIPH_ENABLE_BARO

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
/*
send MSP compass packet
*/
Expand All @@ -176,7 +176,7 @@ void AP_Periph_FW::send_msp_compass(void)

send_msp_packet(MSP2_SENSOR_COMPASS, &p, sizeof(p));
}
#endif // HAL_PERIPH_ENABLE_MAG
#endif // AP_PERIPH_MAG_ENABLED

#ifdef HAL_PERIPH_ENABLE_AIRSPEED
/*
Expand Down
2 changes: 1 addition & 1 deletion Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -954,7 +954,7 @@ def configure_env(self, cfg, env):

AP_PERIPH_GPS_ENABLED = 1,
HAL_PERIPH_ENABLE_AIRSPEED = 1,
HAL_PERIPH_ENABLE_MAG = 1,
AP_PERIPH_MAG_ENABLED = 1,
HAL_PERIPH_ENABLE_BARO = 1,
HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1,
Expand Down
6 changes: 3 additions & 3 deletions Tools/autotest/autotest.py
Original file line number Diff line number Diff line change
Expand Up @@ -154,17 +154,17 @@ def run_unit_tests():

def run_clang_scan_build():
"""Run Clang Scan-build utility."""
if util.run_cmd("scan-build python waf configure",
if util.run_cmd("scan-build python3 waf configure",
directory=util.reltopdir('.')) != 0:
print("Failed scan-build-configure")
return False

if util.run_cmd("scan-build python waf clean",
if util.run_cmd("scan-build python3 waf clean",
directory=util.reltopdir('.')) != 0:
print("Failed scan-build-clean")
return False

if util.run_cmd("scan-build python waf build",
if util.run_cmd("scan-build python3 waf build",
directory=util.reltopdir('.')) != 0:
print("Failed scan-build-build")
return False
Expand Down
30 changes: 18 additions & 12 deletions Tools/scripts/create_OEM_board.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,14 @@ def __init__(self, oem_board_name, board_name):

def run(self):
hwdef_dir = "libraries/AP_HAL_ChibiOS/hwdef"
oem_board_dirpath = f"{hwdef_dir}/{oem_board_name}"
oem_board_dirpath = f"{hwdef_dir}/{self.oem_board_name}"

if os.path.exists(oem_board_dirpath):
raise ValueError(f"{oem_board_dirpath} already exists") # FIXME exception type
raise ValueError(f"{self.oem_board_dirpath} already exists") # FIXME exception type

hwdef_include_relpath = None
for extension in "dat", "inc":
tmp = f"../{board_name}/hwdef.{extension}"
tmp = f"../{self.board_name}/hwdef.{extension}"
tmp_norm = os.path.normpath(f"{oem_board_dirpath}/{tmp}")
if os.path.exists(tmp_norm):
hwdef_include_relpath = tmp
Expand All @@ -44,25 +44,31 @@ def run(self):
use_bootloader_from_board = ch.get_config('USE_BOOTLOADER_FROM_BOARD', default=None, required=False)
if use_bootloader_from_board is None:
hwdef_content += "\n"
hwdef_content += f"USE_BOOTLOADER_FROM_BOARD {board_name}\n"
hwdef_content += f"USE_BOOTLOADER_FROM_BOARD {self.board_name}\n"

subprocess.run(["mkdir", oem_board_dirpath])

# create files and add reference to originals
new_hwdef = pathlib.Path(oem_board_dirpath, "hwdef.dat")

if hwdef_include_relpath is None:
raise ValueError(f"Could not find .inc or .dat for {board_name}")
raise ValueError(f"Could not find .inc or .dat for {self.board_name}")

new_hwdef.write_text(hwdef_content)

if os.path.exists(f"{hwdef_dir}/{board_name}/defaults.parm"):
path = pathlib.Path(f"{hwdef_dir}/{oem_board_name}/defaults.parm")
path.write_text(f"@include ../{board_name}/defaults.parm\n") # noqa
if os.path.exists(f"{hwdef_dir}/{self.board_name}/defaults.parm"):
path = pathlib.Path(f"{hwdef_dir}/{self.oem_board_name}/defaults.parm")
path.write_text(f"@include ../{self.board_name}/defaults.parm\n") # noqa


board_name = sys.argv[1]
oem_board_name = sys.argv[2]
if __name__ == '__main__':
import argparse

oemcreate = OEMCreate(board_name, oem_board_name)
oemcreate.run()
parser = argparse.ArgumentParser(description='ArduPilot OEM board creator')
parser.add_argument('board_name', default=None, help='board to inherit from')
parser.add_argument('oem_board_name', default=None, help='new board name')

args = parser.parse_args()

oemcreate = OEMCreate(args.oem_board_name, args.board_name)
oemcreate.run()
1 change: 0 additions & 1 deletion libraries/AP_ADC/AP_ADC_ADS1115.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,6 @@ float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const
pga = ADS1115_MV_0P256C;
break;
default:
pga = 0.0f;
DEV_PRINTF("Wrong gain");
AP_HAL::panic("ADS1115: wrong gain selected");
break;
Expand Down
10 changes: 9 additions & 1 deletion libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,8 +346,15 @@ void AP_AHRS::reset_gyro_drift(void)
*/
void AP_AHRS::update_state(void)
{
const uint8_t primary_gyro = _get_primary_gyro_index();
#if AP_INERTIALSENSOR_ENABLED
// tell the IMUS about primary changes
if (primary_gyro != state.primary_gyro) {
AP::ins().set_primary(primary_gyro);
}
#endif
state.primary_IMU = _get_primary_IMU_index();
state.primary_gyro = _get_primary_gyro_index();
state.primary_gyro = primary_gyro;
state.primary_accel = _get_primary_accel_index();
state.primary_core = _get_primary_core_index();
state.wind_estimate_ok = _wind_estimate(state.wind_estimate);
Expand All @@ -367,6 +374,7 @@ void AP_AHRS::update_state(void)
state.velocity_NED_ok = _get_velocity_NED(state.velocity_NED);
}

// update run at loop rate
void AP_AHRS::update(bool skip_ins_update)
{
// periodically checks to see if we should update the AHRS
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_Compass/AP_Compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ extern const AP_HAL::HAL& hal;
#endif

#ifndef COMPASS_LEARN_DEFAULT
#define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
#define COMPASS_LEARN_DEFAULT Compass::LearnType::NONE
#endif

#ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
Expand Down Expand Up @@ -119,7 +119,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Description: Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
// @Values: 0:Disabled,2:EKF-Learning,3:InFlight-Learning
// @User: Advanced
AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),
AP_GROUPINFO("LEARN", 3, Compass, _learn, float(COMPASS_LEARN_DEFAULT)),
#endif

#ifndef HAL_BUILD_AP_PERIPH
Expand Down Expand Up @@ -1793,11 +1793,11 @@ Compass::read(void)
any_healthy |= _state[i].healthy;
}
#if COMPASS_LEARN_ENABLED
if (_learn == LEARN_INFLIGHT && !learn_allocated) {
if (_learn == LearnType::INFLIGHT && !learn_allocated) {
learn_allocated = true;
learn = NEW_NOTHROW CompassLearn(*this);
}
if (_learn == LEARN_INFLIGHT && learn != nullptr) {
if (_learn == LearnType::INFLIGHT && learn != nullptr) {
learn->update();
}
#endif
Expand Down Expand Up @@ -1985,7 +1985,7 @@ Compass::use_for_yaw(uint8_t i) const
// when we are doing in-flight compass learning the state
// estimator must not use the compass. The learning code turns off
// inflight learning when it has converged
return _use_for_yaw[Priority(i)] && _learn.get() != LEARN_INFLIGHT;
return _use_for_yaw[Priority(i)] && _learn != LearnType::INFLIGHT;
}

/*
Expand Down
24 changes: 12 additions & 12 deletions libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ friend class AP_Compass_Backend;
#endif // AP_COMPASS_DIAGONALS_ENABLED

// learn offsets accessor
bool learn_offsets_enabled() const { return _learn == LEARN_INFLIGHT; }
bool learn_offsets_enabled() const { return _learn == LearnType::INFLIGHT; }

/// return true if the compass should be used for yaw calculations
bool use_for_yaw(uint8_t i) const;
Expand Down Expand Up @@ -318,24 +318,24 @@ friend class AP_Compass_Backend;

static const struct AP_Param::GroupInfo var_info[];

enum LearnType {
LEARN_NONE=0,
// LEARN_INTERNAL=1,
LEARN_EKF=2,
LEARN_INFLIGHT=3
enum class LearnType {
NONE = 0,
// INTERNAL = 1,
COPY_FROM_EKF = 2,
INFLIGHT = 3,
};

// return the chosen learning type
enum LearnType get_learn_type(void) const {
return (enum LearnType)_learn.get();
LearnType get_learn_type(void) const {
return (LearnType)_learn.get();
}

// set the learning type
void set_learn_type(enum LearnType type, bool save) {
void set_learn_type(LearnType type, bool save) {
if (save) {
_learn.set_and_save((int8_t)type);
_learn.set_and_save(type);
} else {
_learn.set((int8_t)type);
_learn.set(type);
}
}

Expand Down Expand Up @@ -520,7 +520,7 @@ friend class AP_Compass_Backend;
uint8_t _unreg_compass_count;

// settable parameters
AP_Int8 _learn;
AP_Enum<LearnType> _learn;

// board orientation from AHRS
enum Rotation _board_orientation = ROTATION_NONE;
Expand Down
Loading

0 comments on commit 2ec2c2f

Please sign in to comment.