Skip to content

Commit

Permalink
Merge branch 'master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
BryonOI authored Jul 29, 2024
2 parents d7388a1 + f60ecbf commit a383dfb
Show file tree
Hide file tree
Showing 112 changed files with 6,452 additions and 2,776 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
8 changes: 4 additions & 4 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
2 changes: 1 addition & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -659,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: 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
1 change: 1 addition & 0 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -439,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
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
23 changes: 12 additions & 11 deletions ArduCopter/tuning.cpp
Original file line number Diff line number Diff line change
@@ -1,33 +1,34 @@
#include "Copter.h"

/*
* Function to update various parameters in flight using the ch6 tuning knob
* Function to update various parameters in flight using the TRANSMITTER_TUNING channel knob
* This should not be confused with the AutoTune feature which can be found in control_autotune.cpp
*/

// tuning - updates parameters based on the ch6 tuning knob's position
// tuning - updates parameters based on the ch6 TRANSMITTER_TUNING channel knob's position
// should be called at 3.3hz
void Copter::tuning()
{
const RC_Channel *rc6 = rc().channel(CH_6);
const RC_Channel *rc_tuning = rc().find_channel_for_option(RC_Channel::AUX_FUNC::TRANSMITTER_TUNING);

// exit immediately if tuning channel is not set
if (rc_tuning == nullptr) {
return;
}

// exit immediately if the tuning function is not set or min and max are both zero
if ((g.radio_tuning <= 0) || (is_zero(g2.tuning_min.get()) && is_zero(g2.tuning_max.get()))) {
return;
}

// exit immediately when radio failsafe is invoked or transmitter has not been turned on
if (failsafe.radio || failsafe.radio_counter != 0 || rc6->get_radio_in() == 0) {
return;
}

// exit immediately if a function is assigned to channel 6
if ((RC_Channel::AUX_FUNC)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) {
if (failsafe.radio || failsafe.radio_counter != 0 || rc_tuning->get_radio_in() == 0) {
return;
}

const uint16_t radio_in = rc6->get_radio_in();
float tuning_value = linear_interpolate(g2.tuning_min, g2.tuning_max, radio_in, rc6->get_radio_min(), rc6->get_radio_max());
const uint16_t radio_in = rc_tuning->get_radio_in();
float tuning_value = linear_interpolate(g2.tuning_min, g2.tuning_max, radio_in, rc_tuning->get_radio_min(), rc_tuning->get_radio_max());

#if HAL_LOGGING_ENABLED
Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g2.tuning_min, g2.tuning_max);
#endif
Expand Down
5 changes: 5 additions & 0 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -448,6 +448,10 @@ void Plane::stabilize()
}


/*
* Set the throttle output.
* This is called by TECS-enabled flight modes, e.g. AUTO, GUIDED, etc.
*/
void Plane::calc_throttle()
{
if (aparm.throttle_cruise <= 1) {
Expand All @@ -458,6 +462,7 @@ void Plane::calc_throttle()
return;
}

// Read the TECS throttle output and set it to the throttle channel.
float commanded_throttle = TECS_controller.get_throttle_demand();
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, commanded_throttle);
}
Expand Down
19 changes: 18 additions & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,12 +142,28 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: TKOFF_THR_MAX_T
// @DisplayName: Takeoff throttle maximum time
// @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff without an airspeed sensor. If an airspeed sensor is being used then the throttle is set to maximum until the takeoff airspeed is reached.
// @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff.
// @Units: s
// @Range: 0 10
// @Increment: 0.5
// @User: Standard
ASCALAR(takeoff_throttle_max_t, "TKOFF_THR_MAX_T", 4),

// @Param: TKOFF_THR_MIN
// @DisplayName: Takeoff minimum throttle
// @Description: The minimum throttle to use in takeoffs in AUTO and TAKEOFF flight modes, when TKOFF_OPTIONS bit 0 is set. Also, the minimum throttle to use in a quadpane forward transition. This can be useful to ensure faster takeoffs or transitions on aircraft where the normal throttle control leads to a slow takeoff or transition. It is used when it is larger than THR_MIN, otherwise THR_MIN is used instead.
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Standard
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),

// @Param: TKOFF_OPTIONS
// @DisplayName: Takeoff options
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.
// @Bitmask: 0: When unset the maximum allowed throttle is always used (THR_MAX or TKOFF_THR_MAX) during takeoff. When set TECS is allowed to operate between a minimum (THR_MIN or TKOFF_THR_MIN) and a maximum (THR_MAX or TKOFF_THR_MAX) limit. Applicable only when using an airspeed sensor.
// @User: Advanced
ASCALAR(takeoff_options, "TKOFF_OPTIONS", 0),

// @Param: TKOFF_TDRAG_ELEV
// @DisplayName: Takeoff tail dragger elevator
Expand Down Expand Up @@ -1096,6 +1112,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode
// @Bitmask: 12: Enable FBWB style loiter altitude control
// @Bitmask: 13: Indicate takeoff waiting for neutral rudder with flight control surfaces
// @Bitmask: 14: In AUTO - climb to next waypoint altitude immediately instead of linear climb
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),

Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -357,6 +357,8 @@ class Parameters {
k_param_acro_yaw_rate,
k_param_takeoff_throttle_max_t,
k_param_autotune_options,
k_param_takeoff_throttle_min,
k_param_takeoff_options,
};

AP_Int16 format_version;
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1117,6 +1117,7 @@ class Plane : public AP_Vehicle {
bool auto_takeoff_check(void);
void takeoff_calc_roll(void);
void takeoff_calc_pitch(void);
void takeoff_calc_throttle(const bool use_max_throttle=false);
int8_t takeoff_tail_hold(void);
int16_t get_takeoff_pitch_min_cd(void);
void landing_gear_update(void);
Expand Down
11 changes: 10 additions & 1 deletion ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,14 @@
ArduPilot Plane 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: 9 additions & 2 deletions ArduPlane/altitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,13 @@ void Plane::setup_glide_slope(void)
break;

case Mode::Number::AUTO:

//climb without doing glide slope if option is enabled
if (!above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_CLIMB_IN_AUTO)) {
reset_offset_altitude();
break;
}

// we only do glide slide handling in AUTO when above 20m or
// when descending. The 20 meter threshold is arbitrary, and
// is basically to prevent situations where we try to slowly
Expand Down Expand Up @@ -513,9 +520,9 @@ int32_t Plane::adjusted_altitude_cm(void)
}

/*
return home-relative altitude adjusted for ALT_OFFSET This is useful
return home-relative altitude adjusted for ALT_OFFSET. This is useful
during long flights to account for barometer changes from the GCS,
or to adjust the flying height of a long mission
or to adjust the flying height of a long mission.
*/
int32_t Plane::adjusted_relative_altitude_cm(void)
{
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)
next_WP_loc.lat = home.lat + 10;
next_WP_loc.lng = home.lng + 10;
auto_state.takeoff_speed_time_ms = 0;
auto_state.takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction
auto_state.takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction.
auto_state.height_below_takeoff_to_level_off_cm = 0;
// Flag also used to override "on the ground" throttle disable

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,7 @@ enum FlightOptions {
DISABLE_GROUND_PID_SUPPRESSION = (1<<11),
ENABLE_LOITER_ALT_CONTROL = (1<<12),
INDICATE_WAITING_FOR_RUDDER_NEUTRAL = (1<<13),
IMMEDIATE_CLIMB_IN_AUTO = (1<<14),
};

enum CrowFlapOptions {
Expand Down
10 changes: 5 additions & 5 deletions ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@ const AP_Param::GroupInfo ModeTakeoff::var_info[] = {
// @Increment: 1
// @Units: m
// @User: Standard
AP_GROUPINFO("LVL_ALT", 2, ModeTakeoff, level_alt, 5),
AP_GROUPINFO("LVL_ALT", 2, ModeTakeoff, level_alt, 10),

// @Param: LVL_PITCH
// @DisplayName: Takeoff mode altitude initial pitch
// @Description: This is the target pitch for the initial climb to TKOFF_LVL_ALT
// @Description: This is the target pitch during the takeoff.
// @Range: 0 30
// @Increment: 1
// @Units: deg
Expand Down Expand Up @@ -149,11 +149,11 @@ void ModeTakeoff::update()

if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) {
//below TAKOFF_LVL_ALT
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 100.0);
plane.takeoff_calc_roll();
plane.takeoff_calc_pitch();
plane.takeoff_calc_throttle(true);
} else {
if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT ,or above and loitering
if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT, or above and loitering
#if AP_FENCE_ENABLED
if (!plane.have_autoenabled_fences) {
plane.fence.auto_enable_fence_after_takeoff();
Expand All @@ -164,7 +164,7 @@ void ModeTakeoff::update()
plane.calc_nav_pitch();
plane.calc_throttle();
} else { // still climbing to TAKEOFF_ALT; may be loitering
plane.calc_throttle();
plane.takeoff_calc_throttle();
plane.takeoff_calc_roll();
plane.takeoff_calc_pitch();
}
Expand Down
Loading

0 comments on commit a383dfb

Please sign in to comment.