Skip to content

Commit

Permalink
Merge branch 'master' into afs-improvement2
Browse files Browse the repository at this point in the history
  • Loading branch information
eppravitra authored Apr 12, 2023
2 parents 3aac163 + db7fad0 commit 3a7b20b
Show file tree
Hide file tree
Showing 333 changed files with 11,446 additions and 8,877 deletions.
3 changes: 3 additions & 0 deletions .github/workflows/test_scripts.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ jobs:
check_autotest_options,
param_parse,
python-cleanliness,
astyle-cleanliness,
validate_board_list,
]
steps:
Expand All @@ -29,4 +30,6 @@ jobs:
CI_BUILD_TARGET: ${{matrix.config}}
shell: bash
run: |
sudo apt update
sudo apt-get install -y astyle
Tools/scripts/build_ci.sh
3 changes: 0 additions & 3 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,6 +1,3 @@
[submodule "modules/uavcan"]
path = modules/uavcan
url = https://github.com/DroneCAN/libuavcan.git
[submodule "modules/waf"]
path = modules/waf
url = https://github.com/ArduPilot/waf.git
Expand Down
5 changes: 5 additions & 0 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,11 @@ repos:
- id: check-xml
- id: check-yaml

- repo: https://github.com/lsst-ts/pre-commit-xmllint
rev: v1.0.0
hooks:
- id: format-xmllint
files: libraries/AP_DDS/dds_xrce_profile.xml
# Disable isort and mypy temporarily due to config conflicts
# # Use to sort python imports by name and put system import first.
# - repo: https://github.com/pycqa/isort
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,6 @@
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
//#define BEACON_ENABLED DISABLED // disable beacon support
//#define STATS_ENABLED DISABLED // disable statistics support
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
Expand Down
6 changes: 0 additions & 6 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,6 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
return false;
}

// if we are using motor Estop switch, it must not be in Estop position
if (SRV_Channels::get_emergency_stop()){
check_failed(display_failure, "Motor Emergency Stopped");
return false;
}

if (!disarm_switch_checks(display_failure)) {
return false;
}
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if HAL_PROXIMITY_ENABLED
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36),
#endif
#if BEACON_ENABLED == ENABLED
#if AP_BEACON_ENABLED
SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39),
#endif
SCHED_TASK(update_altitude, 10, 100, 42),
Expand All @@ -180,7 +180,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(three_hz_loop, 3, 75, 57),
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),
SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63),
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
SCHED_TASK(update_precland, 400, 50, 69),
#endif
#if FRAME_CONFIG == HELI_FRAME
Expand Down Expand Up @@ -550,7 +550,7 @@ void Copter::ten_hz_logging_loop()
#if HAL_PROXIMITY_ENABLED
g2.proximity.log(); // Write proximity sensor distances
#endif
#if BEACON_ENABLED == ENABLED
#if AP_BEACON_ENABLED
g2.beacon.log();
#endif
}
Expand Down
9 changes: 5 additions & 4 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@
#include <AC_Sprayer/AC_Sprayer.h> // Crop sprayer library
#include <AP_ADSB/AP_ADSB.h> // ADS-B RF based collision avoidance module library
#include <AP_Proximity/AP_Proximity.h> // ArduPilot proximity sensor library
#include <AC_PrecLand/AC_PrecLand_config.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Winch/AP_Winch_config.h>

Expand Down Expand Up @@ -99,8 +100,8 @@
#include "AP_Rally.h" // Rally point library
#include "AP_Arming.h"

// libraries which are dependent on #defines in defines.h and/or config.h
#if BEACON_ENABLED == ENABLED
#include <AP_Beacon/AP_Beacon_config.h>
#if AP_BEACON_ENABLED
#include <AP_Beacon/AP_Beacon.h>
#endif

Expand All @@ -115,7 +116,7 @@
#if AP_GRIPPER_ENABLED
# include <AP_Gripper/AP_Gripper.h>
#endif
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
# include <AC_PrecLand/AC_PrecLand.h>
# include <AC_PrecLand/AC_PrecLand_StateMachine.h>
#endif
Expand Down Expand Up @@ -529,7 +530,7 @@ class Copter : public AP_Vehicle {
#endif

// Precision Landing
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
AC_PrecLand precland;
AC_PrecLand_StateMachine precland_statemachine;
#endif
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif

#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
if (copter.precland.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -640,7 +640,7 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)
*/
void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
{
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
copter.precland.handle_msg(packet, timestamp_ms);
#endif
}
Expand Down
80 changes: 3 additions & 77 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -664,7 +664,7 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
#endif

#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
// @Group: PLND_
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
GOBJECT(precland, "PLND_", AC_PrecLand),
Expand Down Expand Up @@ -776,7 +776,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),

#if BEACON_ENABLED == ENABLED
#if AP_BEACON_ENABLED
// @Group: BCN
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),
Expand Down Expand Up @@ -1225,7 +1225,7 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
*/
ParametersG2::ParametersG2(void)
: temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise
#if BEACON_ENABLED == ENABLED
#if AP_BEACON_ENABLED
, beacon()
#endif
#if HAL_PROXIMITY_ENABLED
Expand Down Expand Up @@ -1294,12 +1294,6 @@ ParametersG2::ParametersG2(void)
old object. This should be zero for top level parameters.
*/
const AP_Param::ConversionInfo conversion_table[] = {
// PARAMETER_CONVERSION - Added: Oct-2014
{ Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" },
// PARAMETER_CONVERSION - Added: Jan-2015
{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
// PARAMETER_CONVERSION - Added: Jan-2017
{ Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" },
// battery
Expand Down Expand Up @@ -1370,46 +1364,7 @@ void Copter::load_parameters(void)
// handle conversion of PID gains
void Copter::convert_pid_parameters(void)
{
// conversion info
const AP_Param::ConversionInfo pid_conversion_info[] = {
// PARAMETER_CONVERSION - Added: Apr-2016
{ Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" },
{ Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" },
{ Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" },
{ Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_RAT_PIT_P" },
{ Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_RAT_PIT_I" },
{ Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_RAT_PIT_D" },
{ Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_RAT_YAW_P" },
{ Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" },
{ Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" },
#if FRAME_CONFIG == HELI_FRAME
// PARAMETER_CONVERSION - Added: May-2016
{ Parameters::k_param_pid_rate_roll, 4, AP_PARAM_FLOAT, "ATC_RAT_RLL_VFF" },
{ Parameters::k_param_pid_rate_pitch, 4, AP_PARAM_FLOAT, "ATC_RAT_PIT_VFF" },
{ Parameters::k_param_pid_rate_yaw , 4, AP_PARAM_FLOAT, "ATC_RAT_YAW_VFF" },
#endif
};
const AP_Param::ConversionInfo imax_conversion_info[] = {
// PARAMETER_CONVERSION - Added: Apr-2016
{ Parameters::k_param_pid_rate_roll, 5, AP_PARAM_FLOAT, "ATC_RAT_RLL_IMAX" },
{ Parameters::k_param_pid_rate_pitch, 5, AP_PARAM_FLOAT, "ATC_RAT_PIT_IMAX" },
{ Parameters::k_param_pid_rate_yaw, 5, AP_PARAM_FLOAT, "ATC_RAT_YAW_IMAX" },
#if FRAME_CONFIG == HELI_FRAME
// PARAMETER_CONVERSION - Added: May-2016
{ Parameters::k_param_pid_rate_roll, 7, AP_PARAM_FLOAT, "ATC_RAT_RLL_ILMI" },
{ Parameters::k_param_pid_rate_pitch, 7, AP_PARAM_FLOAT, "ATC_RAT_PIT_ILMI" },
{ Parameters::k_param_pid_rate_yaw, 7, AP_PARAM_FLOAT, "ATC_RAT_YAW_ILMI" },
#endif
};
// conversion from Copter-3.3 to Copter-3.4
const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {
// PARAMETER_CONVERSION - Added: May-2016
{ Parameters::k_param_p_stabilize_roll, 0, AP_PARAM_FLOAT, "ATC_ANG_RLL_P" },
{ Parameters::k_param_p_stabilize_pitch, 0, AP_PARAM_FLOAT, "ATC_ANG_PIT_P" },
{ Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" },
// PARAMETER_CONVERSION - Added: Apr-2016
{ Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" },
{ Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" },
// PARAMETER_CONVERSION - Added: Jan-2018
{ Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" },
{ Parameters::k_param_pi_vel_xy, 0, AP_PARAM_FLOAT, "PSC_VELXY_P" },
Expand All @@ -1429,11 +1384,6 @@ void Copter::convert_pid_parameters(void)
{ Parameters::k_param_p_alt_hold, 0, AP_PARAM_FLOAT, "PSC_POSZ_P" },
{ Parameters::k_param_p_pos_xy, 0, AP_PARAM_FLOAT, "PSC_POSXY_P" },
};
const AP_Param::ConversionInfo throttle_conversion_info[] = {
// PARAMETER_CONVERSION - Added: Jun-2016
{ Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" },
{ Parameters::k_param_throttle_mid, 0, AP_PARAM_FLOAT, "MOT_THST_HOVER" }
};
const AP_Param::ConversionInfo loiter_conversion_info[] = {
// PARAMETER_CONVERSION - Added: Apr-2018
{ Parameters::k_param_wp_nav, 4, AP_PARAM_FLOAT, "LOIT_SPEED" },
Expand All @@ -1442,34 +1392,10 @@ void Copter::convert_pid_parameters(void)
{ Parameters::k_param_wp_nav, 9, AP_PARAM_FLOAT, "LOIT_BRK_ACCEL" }
};

// PARAMETER_CONVERSION - Added: Apr-2016
// gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees
// and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500
float pid_scaler = 1.27f;

#if FRAME_CONFIG != HELI_FRAME
// Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation
if (g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_X || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_V || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_H) {
pid_scaler = 0.9f;
}
#endif

// scale PID gains
for (const auto &info : pid_conversion_info) {
AP_Param::convert_old_parameter(&info, pid_scaler);
}
// reduce IMAX into -1 ~ +1 range
for (const auto &info : imax_conversion_info) {
AP_Param::convert_old_parameter(&info, 1.0f/4500.0f);
}
// convert angle controller gain and filter without scaling
for (const auto &info : angle_and_filt_conversion_info) {
AP_Param::convert_old_parameter(&info, 1.0f);
}
// convert throttle parameters (multicopter only)
for (const auto &info : throttle_conversion_info) {
AP_Param::convert_old_parameter(&info, 0.001f);
}
// convert RC_FEEL_RP to ATC_INPUT_TC
// PARAMETER_CONVERSION - Added: Mar-2018
const AP_Param::ConversionInfo rc_feel_rp_conversion_info = { Parameters::k_param_rc_feel_rp, 0, AP_PARAM_INT8, "ATC_INPUT_TC" };
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -525,7 +525,7 @@ class ParametersG2 {
// temperature calibration handling
AP_TempCalibration temp_calibration;

#if BEACON_ENABLED == ENABLED
#if AP_BEACON_ENABLED
// beacon (non-GPS positioning) library
AP_Beacon beacon;
#endif
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -391,7 +391,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
break;

case AUX_FUNC::PRECISION_LOITER:
#if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED
#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED == ENABLED
switch (ch_flag) {
case AuxSwitchPos::HIGH:
copter.mode_loiter.set_precision_loiter_enabled(true);
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6--beta2 27-Mar-2023
Changes from 4.3.5
1) Bi-directional DShot fix for possible motor stop approx 72min after startup
------------------------------------------------------------------
Copter Copter 4.3.5 14-Mar-2023 / 4.3.5-rc1 01-Mar-2023
Changes from 4.3.4
1) Bug fixes
Expand Down
13 changes: 0 additions & 13 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -138,12 +138,6 @@
# define AUTOTUNE_ENABLED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// Precision Landing with companion computer or IRLock sensor
#ifndef PRECISION_LANDING
# define PRECISION_LANDING ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// Parachute release
#ifndef PARACHUTE
Expand Down Expand Up @@ -294,13 +288,6 @@
# define MODE_AUTOROTATE_ENABLED DISABLED
#endif

//////////////////////////////////////////////////////////////////////////////

// Beacon support - support for local positioning systems
#ifndef BEACON_ENABLED
# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES
#endif

//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
//////////////////////////////////////////////////////////////////////////////
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -594,7 +594,7 @@ void Mode::land_run_vertical_control(bool pause_descent)
// Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed.
cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed));

#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
const bool navigating = pos_control->is_active_xy();
bool doing_precision_landing = !copter.ap.land_repo_active && copter.precland.target_acquired() && navigating;

Expand Down Expand Up @@ -668,7 +668,7 @@ void Mode::land_run_horizontal_control()
AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE);
}
copter.ap.land_repo_active = true;
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
} else {
// no override right now, check if we should allow precland
if (copter.precland.allow_precland_after_reposition()) {
Expand All @@ -681,7 +681,7 @@ void Mode::land_run_horizontal_control()

// this variable will be updated if prec land target is in sight and pilot isn't trying to reposition the vehicle
copter.ap.prec_land_active = false;
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
copter.ap.prec_land_active = !copter.ap.land_repo_active && copter.precland.target_acquired();
// run precision landing
if (copter.ap.prec_land_active) {
Expand Down Expand Up @@ -738,7 +738,7 @@ void Mode::land_run_horizontal_control()
// pause_descent is true if vehicle should not descend
void Mode::land_run_normal_or_precland(bool pause_descent)
{
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
if (pause_descent || !copter.precland.enabled()) {
// we don't want to start descending immediately or prec land is disabled
// in both cases just run simple land controllers
Expand All @@ -753,7 +753,7 @@ void Mode::land_run_normal_or_precland(bool pause_descent)
#endif
}

#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
// Go towards a position commanded by prec land state machine in order to retry landing
// The passed in location is expected to be NED and in m
void Mode::precland_retry_position(const Vector3f &retry_pos)
Expand Down
Loading

0 comments on commit 3a7b20b

Please sign in to comment.