Skip to content

Commit

Permalink
Merge branch 'master' into patch-1
Browse files Browse the repository at this point in the history
  • Loading branch information
njwhite committed Dec 27, 2023
2 parents 8d2d663 + 1e626a7 commit 20273d0
Show file tree
Hide file tree
Showing 352 changed files with 7,994 additions and 1,647 deletions.
6 changes: 3 additions & 3 deletions AntennaTracker/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ class Parameters {
k_param_format_version = 0,
k_param_software_type, // deprecated

k_param_gcs0 = 100, // stream rates for uartA
k_param_gcs1, // stream rates for uartC
k_param_gcs0 = 100, // stream rates for SERIAL0
k_param_gcs1, // stream rates for SERIAL1
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial0_baud, // deprecated
Expand All @@ -60,7 +60,7 @@ class Parameters {
k_param_sitl,
k_param_pidPitch_old, // deprecated
k_param_pidYaw_old, // deprecated
k_param_gcs2, // stream rates for uartD
k_param_gcs2, // stream rates for SERIAL2
k_param_serial2_baud, // deprecated

k_param_yaw_slew_time,
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,9 +451,9 @@ const AP_Param::Info Copter::var_info[] = {
#endif

#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Group: RELAY
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
GOBJECT(relay, "RELAY", AP_Relay),
#endif

#if PARACHUTE == ENABLED
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.4.4 05-Dec-2023
Copter 4.4.4 19-Dec-2023 / 4.4.4-beta1 05-Dec-2023
Changes from 4.4.3
1) Autopilot related enhancement and fixes
- CubeOrange Sim-on-hardware compilation fix
Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -433,10 +433,6 @@
# define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL
#endif

#ifndef RTL_ABS_MIN_CLIMB
# define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb
#endif

#ifndef RTL_CONE_SLOPE_DEFAULT
# define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone
#endif
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -483,14 +483,14 @@ void ModeRTL::compute_return_target()
int32_t target_alt = MAX(rtl_path.return_target.alt, 0);

// increase target to maximum of current altitude + climb_min and rtl altitude
target_alt = MAX(target_alt, curr_alt + MAX(0, g.rtl_climb_min));
target_alt = MAX(target_alt, MAX(g.rtl_altitude, RTL_ALT_MIN));
const float min_rtl_alt = MAX(RTL_ALT_MIN, curr_alt + MAX(0, g.rtl_climb_min));
target_alt = MAX(target_alt, MAX(g.rtl_altitude, min_rtl_alt));

// reduce climb if close to return target
float rtl_return_dist_cm = rtl_path.return_target.get_distance(rtl_path.origin_point) * 100.0f;
// don't allow really shallow slopes
if (g.rtl_cone_slope >= RTL_MIN_CONE_SLOPE) {
target_alt = MAX(curr_alt, MIN(target_alt, MAX(rtl_return_dist_cm*g.rtl_cone_slope, curr_alt+RTL_ABS_MIN_CLIMB)));
target_alt = MIN(target_alt, MAX(rtl_return_dist_cm * g.rtl_cone_slope, min_rtl_alt));
}

// set returned target alt to new target_alt (don't change altitude type)
Expand Down
22 changes: 22 additions & 0 deletions ArduPlane/AP_ExternalControl_Plane.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
/*
external control library for plane
*/


#include "AP_ExternalControl_Plane.h"
#if AP_EXTERNAL_CONTROL_ENABLED

#include "Plane.h"

/*
Sets the target global position for a loiter point.
*/
bool AP_ExternalControl_Plane::set_global_position(const Location& loc)
{

// set_target_location already checks if plane is ready for external control.
// It doesn't check if flying or armed, just that it's in guided mode.
return plane.set_target_location(loc);
}

#endif // AP_EXTERNAL_CONTROL_ENABLED
21 changes: 21 additions & 0 deletions ArduPlane/AP_ExternalControl_Plane.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@

/*
external control library for plane
*/
#pragma once

#include <AP_ExternalControl/AP_ExternalControl.h>

#if AP_EXTERNAL_CONTROL_ENABLED

#include <AP_Common/Location.h>

class AP_ExternalControl_Plane : public AP_ExternalControl {
public:
/*
Sets the target global position for a loiter point.
*/
bool set_global_position(const Location& loc) override WARN_IF_UNUSED;
};

#endif // AP_EXTERNAL_CONTROL_ENABLED
6 changes: 4 additions & 2 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -798,8 +798,8 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const
return true;
}

#if AP_SCRIPTING_ENABLED
// set target location (for use by scripting)
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
// set target location (for use by external control and scripting)
bool Plane::set_target_location(const Location &target_loc)
{
Location loc{target_loc};
Expand All @@ -816,7 +816,9 @@ bool Plane::set_target_location(const Location &target_loc)
plane.set_guided_WP(loc);
return true;
}
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

#if AP_SCRIPTING_ENABLED
// set target location (for use by scripting)
bool Plane::get_target_location(Location& target_loc)
{
Expand Down
19 changes: 17 additions & 2 deletions ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,9 @@ void Plane::Log_Write_Attitude(void)
logger.Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
logger.Write_PID(LOG_PIQY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
logger.Write_PID(LOG_PIQA_MSG, quadplane.pos_control->get_accel_z_pid().get_pid_info() );

// Write tailsitter specific log at same rate as PIDs
quadplane.tailsitter.write_log();
}
if (quadplane.in_vtol_mode() && quadplane.pos_control->is_active_xy()) {
logger.Write_PID(LOG_PIDN_MSG, quadplane.pos_control->get_vel_xy_pid().get_pid_info_x());
Expand Down Expand Up @@ -383,12 +386,11 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: DCRt: desired climb rate
// @Field: CRt: climb rate
// @Field: TMix: transition throttle mix value
// @Field: Sscl: speed scalar for tailsitter control surfaces
// @Field: Trn: Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done
// @Field: Ast: Q assist active
#if HAL_QUADPLANE_ENABLED
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
"QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" , true },
"QTUN", "QffffffeccfBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Trn,Ast", "s----mmmnn---", "F----00000---" , true },
#endif

// @LoggerMessage: PIQR,PIQP,PIQY,PIQA
Expand All @@ -406,6 +408,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: SRate: slew rate
// @Field: Flags: bitmask of PID state flags
// @FieldBitmaskEnum: Flags: log_PID_Flags
#if HAL_QUADPLANE_ENABLED
{ LOG_PIQR_MSG, sizeof(log_PID),
"PIQR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },
{ LOG_PIQP_MSG, sizeof(log_PID),
Expand All @@ -414,6 +417,18 @@ const struct LogStructure Plane::log_structure[] = {
"PIQY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },
{ LOG_PIQA_MSG, sizeof(log_PID),
"PIQA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },
#endif

// @LoggerMessage: TSIT
// @Description: tailsitter speed scailing values
// @Field: TimeUS: Time since system startup
// @Field: Ts: throttle scailing used for tilt motors
// @Field: Ss: speed scailing used for control surfaces method from Q_TAILSIT_GSCMSK
// @Field: Tmin: minimum output throttle caculated from disk thoery gain scale with Q_TAILSIT_MIN_VO
#if HAL_QUADPLANE_ENABLED
{ LOG_TSIT_MSG, sizeof(Tailsitter::log_tailsitter),
"TSIT", "Qfff", "TimeUS,Ts,Ss,Tmin", "s---", "F---" , true },
#endif

// @LoggerMessage: PIDG
// @Description: Plane Proportional/Integral/Derivative gain values for Heading when using COMMAND_INT control.
Expand Down
10 changes: 5 additions & 5 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -757,9 +757,9 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(arming, "ARMING_", AP_Arming_Plane),

#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Group: RELAY
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
GOBJECT(relay, "RELAY", AP_Relay),
#endif

#if PARACHUTE == ENABLED
Expand Down Expand Up @@ -1175,7 +1175,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Units: V
// @Increment: 0.1
// @User: Advanced
AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_thr_batt_voltage_max, 0.0f),
AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_batt_cmp.batt_voltage_max, 0.0f),

// @Param: FWD_BAT_VOLT_MIN
// @DisplayName: Forward throttle battery voltage compensation minimum voltage
Expand All @@ -1184,14 +1184,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Units: V
// @Increment: 0.1
// @User: Advanced
AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_thr_batt_voltage_min, 0.0f),
AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_batt_cmp.batt_voltage_min, 0.0f),

// @Param: FWD_BAT_IDX
// @DisplayName: Forward throttle battery compensation index
// @Description: Which battery monitor should be used for doing compensation for the forward throttle
// @Values: 0:First battery, 1:Second battery
// @User: Advanced
AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_thr_batt_idx, 0),
AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_batt_cmp.batt_idx, 0),

// @Param: FS_EKF_THRESH
// @DisplayName: EKF failsafe variance threshold
Expand Down
29 changes: 23 additions & 6 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,14 +159,14 @@ class Parameters {

// 110: Telemetry control
//
k_param_gcs0 = 110, // stream rates for uartA
k_param_gcs1, // stream rates for uartC
k_param_gcs0 = 110, // stream rates for SERIAL0
k_param_gcs1, // stream rates for SERIAL1
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial1_baud_old, // deprecated
k_param_telem_delay,
k_param_serial0_baud_old, // deprecated
k_param_gcs2, // stream rates for uartD
k_param_gcs2, // stream rates for SERIAL2
k_param_serial2_baud_old, // deprecated
k_param_serial2_protocol, // deprecated

Expand Down Expand Up @@ -542,9 +542,26 @@ class ParametersG2 {
AP_Int8 crow_flap_aileron_matching;

// Forward throttle battery voltage compensation
AP_Float fwd_thr_batt_voltage_max;
AP_Float fwd_thr_batt_voltage_min;
AP_Int8 fwd_thr_batt_idx;
class FWD_BATT_CMP {
public:
// Calculate the throttle scale to compensate for battery voltage drop
void update();

// Apply throttle scale to min and max limits
void apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const;

// Apply throttle scale to throttle demand
float apply_throttle(float throttle) const;

AP_Float batt_voltage_max;
AP_Float batt_voltage_min;
AP_Int8 batt_idx;

private:
bool enabled;
float ratio;
} fwd_batt_cmp;


#if OFFBOARD_GUIDED == ENABLED
// guided yaw heading PID
Expand Down
17 changes: 11 additions & 6 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@
#include <AP_Follow/AP_Follow.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h>
#if AP_EXTERNAL_CONTROL_ENABLED
#include <AP_ExternalControl/AP_ExternalControl.h>
#include "AP_ExternalControl_Plane.h"
#endif

#include "GCS_Mavlink.h"
Expand Down Expand Up @@ -167,6 +167,10 @@ class Plane : public AP_Vehicle {
friend class ModeThermal;
friend class ModeLoiterAltQLand;

#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Plane;
#endif

Plane(void);

private:
Expand Down Expand Up @@ -776,9 +780,9 @@ class Plane : public AP_Vehicle {

AP_Param param_loader {var_info};

// dummy implementation of external control
// external control library
#if AP_EXTERNAL_CONTROL_ENABLED
AP_ExternalControl external_control;
AP_ExternalControl_Plane external_control;
#endif

static const AP_Scheduler::Task scheduler_tasks[];
Expand Down Expand Up @@ -1091,7 +1095,7 @@ class Plane : public AP_Vehicle {
// servos.cpp
void set_servos_idle(void);
void set_servos();
void set_servos_controlled(void);
void set_throttle(void);
void set_takeoff_expected(void);
void set_servos_old_elevons(void);
void set_servos_flaps(void);
Expand All @@ -1103,7 +1107,6 @@ class Plane : public AP_Vehicle {
void servos_auto_trim(void);
void servos_twin_engine_mix();
void force_flare();
void throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) const;
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func);
bool suppress_throttle(void);
Expand Down Expand Up @@ -1241,8 +1244,10 @@ class Plane : public AP_Vehicle {
void failsafe_check(void);
bool is_landing() const override;
bool is_taking_off() const override;
#if AP_SCRIPTING_ENABLED
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
bool set_target_location(const Location& target_loc) override;
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if AP_SCRIPTING_ENABLED
bool get_target_location(Location& target_loc) override;
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
bool set_velocity_match(const Vector2f &velocity) override;
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
Release 4.4.4-beta1 5th December 2023
-------------------------------------
Release 4.4.4 19th December 2023
--------------------------------

Changes from 4.4.3:

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -348,6 +348,7 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);
setup_terrain_target_alt(next_WP_loc);
set_target_altitude_location(next_WP_loc);
plane.altitude_error_cm = calc_altitude_error_cm();

if (aparm.loiter_radius < 0) {
loiter.direction = -1;
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,7 @@ enum log_messages {
LOG_PIDG_MSG,
LOG_AETR_MSG,
LOG_OFG_MSG,
LOG_TSIT_MSG,
};

#define MASK_LOG_ATTITUDE_FAST (1<<0)
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,9 @@ bool Mode::enter()
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");
plane.mission.reset();
}

// Make sure the flight stage is correct for the new mode
plane.update_flight_stage();
}

return enter_result;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ const AP_Param::GroupInfo ModeTakeoff::var_info[] = {

// @Param: LVL_ALT
// @DisplayName: Takeoff mode altitude level altitude
// @Description: This is the altitude below which the wings are held level for TAKEOFF and AUTO modes. Below this altitude, roll demand is restricted to LEVEL_ROLL_LIMIT. Normal-flight roll restriction resumes above TKOFF_LVL_ALT*2 or TKOFF_ALT, whichever is lower. Roll limits are scaled while between those altitudes for a smooth transition.
// @Description: This is the altitude below which the wings are held level for TAKEOFF and AUTO modes. Below this altitude, roll demand is restricted to LEVEL_ROLL_LIMIT. Normal-flight roll restriction resumes above TKOFF_LVL_ALT*3 or TKOFF_ALT, whichever is lower. Roll limits are scaled while between TKOFF_LVL_ALT and those altitudes for a smooth transition.
// @Range: 0 50
// @Increment: 1
// @Units: m
Expand Down
Loading

0 comments on commit 20273d0

Please sign in to comment.