Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/ArduPilot/ardupilot
Browse files Browse the repository at this point in the history
  • Loading branch information
BryonOI committed Jul 29, 2024
2 parents e2cfd35 + f60ecbf commit b3cf453
Show file tree
Hide file tree
Showing 317 changed files with 38,303 additions and 28,809 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/qurt_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -141,8 +141,8 @@ concurrency:

jobs:
build:
if: github.repository == 'ArduPilot/ardupilot'
runs-on: 'ardupilot-qurt'

steps:
- uses: actions/checkout@v4
with:
Expand Down
11 changes: 10 additions & 1 deletion AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,14 @@
Antenna Tracker Release Notes:
------------------------------
------------------------------------------------------------------
Release 4.5.5-beta2 27 July 2024

Changes from 4.5.5-beta1

1) Board specific enhancements and bug fixes

- CubeRed's second core disabled at boot to avoid spurious writes to RAM
- CubeRed bootloader's dual endpoint update method fixed
------------------------------------------------------------------
Release 4.5.5-beta1 1st July 2024

Changes from 4.5.4
Expand Down
18 changes: 9 additions & 9 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -341,10 +341,10 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
{
// check if fence requires GPS
bool fence_requires_gps = false;
#if AP_FENCE_ENABLED
#if AP_FENCE_ENABLED
// if circular or polygon fence is enabled we need GPS
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif
#endif

// check if flight mode requires GPS
bool mode_requires_gps = copter.flightmode->requires_GPS() || fence_requires_gps || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
Expand Down Expand Up @@ -443,10 +443,10 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)

// check if fence requires GPS
bool fence_requires_gps = false;
#if AP_FENCE_ENABLED
#if AP_FENCE_ENABLED
// if circular or polygon fence is enabled we need GPS
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif
#endif

if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {
if (!copter.position_ok()) {
Expand Down Expand Up @@ -601,11 +601,11 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)

// check throttle
if (check_enabled(ARMING_CHECK_RC)) {
#if FRAME_CONFIG == HELI_FRAME
#if FRAME_CONFIG == HELI_FRAME
const char *rc_item = "Collective";
#else
#else
const char *rc_item = "Throttle";
#endif
#endif
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) {
// above top of deadband is too always high
Expand All @@ -614,12 +614,12 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
return false;
}
// in manual modes throttle must be at zero
#if FRAME_CONFIG != HELI_FRAME
#if FRAME_CONFIG != HELI_FRAME
if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
return false;
}
#endif
#endif
}
}

Expand Down
8 changes: 5 additions & 3 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -474,13 +474,13 @@ bool Copter::update_target_location(const Location &old_loc, const Location &new

#endif // AP_SCRIPTING_ENABLED

// returns true if vehicle is landing. Only used by Lua scripts
// returns true if vehicle is landing.
bool Copter::is_landing() const
{
return flightmode->is_landing();
}

// returns true if vehicle is taking off. Only used by Lua scripts
// returns true if vehicle is taking off.
bool Copter::is_taking_off() const
{
return flightmode->is_taking_off();
Expand Down Expand Up @@ -583,9 +583,11 @@ void Copter::ten_hz_logging_loop()
}
if (should_log(MASK_LOG_RCIN)) {
logger.Write_RCIN();
#if AP_RSSI_ENABLED
if (rssi.enabled()) {
logger.Write_RSSI();
}
#endif
}
if (should_log(MASK_LOG_RCOUT)) {
logger.Write_RCOUT();
Expand Down Expand Up @@ -657,7 +659,7 @@ void Copter::three_hz_loop()
// check for deadreckoning failsafe
failsafe_deadreckon_check();

// update ch6 in flight tuning
//update transmitter based in flight tuning
tuning();

// check if avoidance should be enabled based on alt
Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -634,10 +634,12 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
#endif

#if AP_RSSI_ENABLED
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
GOBJECT(rssi, "RSSI_", AP_RSSI),

#endif

#if AP_RANGEFINDER_ENABLED
// @Group: RNGFND
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::FORCEFLYING:
case AUX_FUNC::CUSTOM_CONTROLLER:
case AUX_FUNC::WEATHER_VANE_ENABLE:
case AUX_FUNC::TRANSMITTER_TUNING:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
break;
default:
Expand Down Expand Up @@ -648,6 +649,9 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;
}
#endif
case AUX_FUNC::TRANSMITTER_TUNING:
// do nothing, used in tuning.cpp for transmitter based tuning
break;

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
Expand Down
11 changes: 10 additions & 1 deletion ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,14 @@
ArduPilot Copter Release Notes:
-------------------------------
------------------------------------------------------------------
Release 4.5.5-beta2 27 July 2024

Changes from 4.5.5-beta1

1) Board specific enhancements and bug fixes

- CubeRed's second core disabled at boot to avoid spurious writes to RAM
- CubeRed bootloader's dual endpoint update method fixed
------------------------------------------------------------------
Release 4.5.5-beta1 1st July 2024

Changes from 4.5.4
Expand Down
11 changes: 8 additions & 3 deletions ArduCopter/fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,10 @@ void Copter::fence_check()
{
const uint8_t orig_breaches = fence.get_breaches();

bool is_landing_or_landed = flightmode->is_landing() || ap.land_complete || !motors->armed();

// check for new breaches; new_breaches is bitmask of fence types breached
const uint8_t new_breaches = fence.check();
const uint8_t new_breaches = fence.check(is_landing_or_landed);

// we still don't do anything when disarmed, but we do check for fence breaches.
// fence pre-arm check actually checks if any fence has been breached
Expand All @@ -24,7 +26,7 @@ void Copter::fence_check()
if (new_breaches) {

if (!copter.ap.land_complete) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence Breached");
fence.print_fence_message("breached", new_breaches);
}

// if the user wants some kind of response and motors are armed
Expand Down Expand Up @@ -81,7 +83,10 @@ void Copter::fence_check()

LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));

} else if (orig_breaches) {
} else if (orig_breaches && fence.get_breaches() == 0) {
if (!copter.ap.land_complete) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared");
}
// record clearing of breach
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
}
Expand Down
25 changes: 21 additions & 4 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,6 +347,20 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
return false;
}

#if AP_FENCE_ENABLED
// may not be allowed to change mode if recovering from fence breach
if (!ignore_checks &&
fence.enabled() &&
fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) &&
fence.get_breaches() &&
motors->armed() &&
get_control_mode_reason() == ModeReason::FENCE_BREACHED &&
!ap.land_complete) {
mode_change_failed(new_flightmode, "in fence recovery");
return false;
}
#endif

if (!new_flightmode->init(ignore_checks)) {
mode_change_failed(new_flightmode, "init failed");
return false;
Expand All @@ -371,10 +385,12 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#endif

#if AP_FENCE_ENABLED
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
fence.manual_recovery_start();
if (fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY) {
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
fence.manual_recovery_start();
}
#endif

#if AP_CAMERA_ENABLED
Expand Down Expand Up @@ -423,6 +439,7 @@ void Copter::update_flight_mode()
#if AP_RANGEFINDER_ENABLED
surface_tracking.invalidate_for_logging(); // invalidate surface tracking alt, flight mode will set to true if used
#endif
attitude_control->landed_gain_reduction(copter.ap.land_complete); // Adjust gains when landed to attenuate ground oscillation

flightmode->run();
}
Expand Down
7 changes: 6 additions & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -596,12 +596,13 @@ class ModeAuto : public Mode {

private:

enum class Options : int32_t {
enum class Option : int32_t {
AllowArming = (1 << 0U),
AllowTakeOffWithoutRaisingThrottle = (1 << 1U),
IgnorePilotYaw = (1 << 2U),
AllowWeatherVaning = (1 << 7U),
};
bool option_is_enabled(Option option) const;

// Enter auto rtl pseudo mode
bool enter_auto_rtl(ModeReason reason);
Expand Down Expand Up @@ -1540,6 +1541,10 @@ class ModeSmartRTL : public ModeRTL {
// point while following our path home. If we take too long we
// may choose to land the vehicle.
uint32_t path_follow_last_pop_fail_ms;

// backup last popped point so that it can be restored to the path
// if vehicle exits SmartRTL mode before reaching home. invalid if zero
Vector3f dest_NED_backup;
};


Expand Down
35 changes: 13 additions & 22 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,15 +202,23 @@ void ModeAuto::set_submode(SubMode new_submode)
}
}

bool ModeAuto::option_is_enabled(Option option) const
{
return ((copter.g2.auto_options & (uint32_t)option) != 0);
}

bool ModeAuto::allows_arming(AP_Arming::Method method) const
{
return ((copter.g2.auto_options & (uint32_t)Options::AllowArming) != 0) && !auto_RTL;
};
if (auto_RTL) {
return false;
}
return option_is_enabled(Option::AllowArming);
}

#if WEATHERVANE_ENABLED == ENABLED
bool ModeAuto::allows_weathervaning() const
{
return (copter.g2.auto_options & (uint32_t)Options::AllowWeatherVaning) != 0;
return option_is_enabled(Option::AllowWeatherVaning);
}
#endif

Expand Down Expand Up @@ -480,11 +488,6 @@ void ModeAuto::land_start()
copter.landinggear.deploy_for_landing();
#endif

#if AP_FENCE_ENABLED
// disable the fence on landing
copter.fence.auto_disable_fence_for_landing();
#endif

// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false;

Expand Down Expand Up @@ -638,7 +641,7 @@ void PayloadPlace::start_descent()
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeAuto::use_pilot_yaw(void) const
{
const bool allow_yaw_option = (copter.g2.auto_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
const bool allow_yaw_option = !option_is_enabled(Option::IgnorePilotYaw);
const bool rtl_allow_yaw = (_mode == SubMode::RTL) && copter.mode_rtl.use_pilot_yaw();
const bool landing = _mode == SubMode::LAND;
return allow_yaw_option || rtl_allow_yaw || landing;
Expand Down Expand Up @@ -779,18 +782,6 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
// point the camera to a specified angle
do_mount_control(cmd);
break;

case MAV_CMD_DO_FENCE_ENABLE:
#if AP_FENCE_ENABLED
if (cmd.p1 == 0) { //disable
copter.fence.enable(false);
gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled");
} else { //enable fence
copter.fence.enable(true);
gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled");
}
#endif //AP_FENCE_ENABLED
break;

#if AC_NAV_GUIDED == ENABLED
case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits
Expand Down Expand Up @@ -1039,7 +1030,7 @@ void ModeAuto::takeoff_run()
{
// if the user doesn't want to raise the throttle we can set it automatically
// note that this can defeat the disarm check on takeoff
if ((copter.g2.auto_options & (int32_t)Options::AllowTakeOffWithoutRaisingThrottle) != 0) {
if (option_is_enabled(Option::AllowTakeOffWithoutRaisingThrottle)) {
copter.set_auto_armed(true);
}
auto_takeoff.run();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ void ModeCircle::run()
}

// update the orbicular rate target based on pilot roll stick inputs
// skip if using CH6 tuning knob for circle rate
// skip if using transmitter based tuning knob for circle rate
if (g.radio_tuning != TUNING_CIRCLE_RATE) {
const float roll_stick = channel_roll->norm_input_dz(); // roll stick normalized -1 to 1

Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -685,6 +685,9 @@ void ModeGuided::takeoff_run()
auto_takeoff.run();
if (auto_takeoff.complete && !takeoff_complete) {
takeoff_complete = true;
#if AP_FENCE_ENABLED
copter.fence.auto_enable_fence_after_takeoff();
#endif
#if AP_LANDINGGEAR_ENABLED
// optionally retract landing gear
copter.landinggear.retract_after_takeoff();
Expand Down
5 changes: 0 additions & 5 deletions ArduCopter/mode_land.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,6 @@ bool ModeLand::init(bool ignore_checks)
copter.landinggear.deploy_for_landing();
#endif

#if AP_FENCE_ENABLED
// disable the fence on landing
copter.fence.auto_disable_fence_for_landing();
#endif

#if AC_PRECLAND_ENABLED
// initialise precland state machine
copter.precland_statemachine.init();
Expand Down
Loading

0 comments on commit b3cf453

Please sign in to comment.