Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into copter_shipland_upsteam
Browse files Browse the repository at this point in the history
  • Loading branch information
KosmX committed Aug 21, 2023
2 parents 3209f18 + 84b3c9e commit fa00144
Show file tree
Hide file tree
Showing 570 changed files with 19,534 additions and 4,053 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/test_ccache.yml
Original file line number Diff line number Diff line change
Expand Up @@ -140,5 +140,5 @@ jobs:
run: |
PATH="/usr/lib/ccache:/opt/gcc-arm-none-eabi-${{matrix.gcc}}/bin:$PATH"
Tools/scripts/build_tests/test_ccache.py --boards MatekF405,MatekF405-bdshot --min-cache-pct=75
Tools/scripts/build_tests/test_ccache.py --boards CubeOrange,Durandal --min-cache-pct=75
Tools/scripts/build_tests/test_ccache.py --boards Durandal,Pixhawk6X --min-cache-pct=73
3 changes: 2 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,8 @@ GRTAGS
GTAGS
*.apj
.gdbinit
/.vscode
.vscode/*
!.vscode/extensions.json
/.history
Parameters.html
Parameters.md
Expand Down
4 changes: 3 additions & 1 deletion .vscode/extensions.json
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
{
"recommendations": [
"augustocdias.tasks-shell-input",
"bierner.markdown-mermaid",
"ms-vscode.cpptools",
"sumneko.lua",
"ms-python.python",
"ms-python.vscode-pylance",
"streetsidesoftware.code-spell-checker",
"chiehyu.vscode-astyle",
"ardupilot-org.ardupilot-devenv"
"ardupilot-org.ardupilot-devenv",
]
}
29 changes: 11 additions & 18 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,29 +23,35 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)

// check if motor interlock and either Emergency Stop aux switches are used
// at the same time. This cannot be allowed.
bool passed = true;
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&
(rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) ||
rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP))){
check_failed(display_failure, "Interlock/E-Stop Conflict");
return false;
passed = false;
}

// check if motor interlock aux switch is in use
// if it is, switch needs to be in disabled position to arm
// otherwise exit immediately.
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
check_failed(display_failure, "Motor Interlock Enabled");
return false;
passed = false;
}

if (!disarm_switch_checks(display_failure)) {
return false;
passed = false;
}

// always check motors
char failure_msg[50] {};
if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
check_failed(display_failure, "Motors: %s", failure_msg);
passed = false;
}

// If not passed all checks return false
if (!passed) {
return false;
}

Expand Down Expand Up @@ -218,19 +224,6 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
}

#if FRAME_CONFIG == HELI_FRAME
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_DUAL &&
copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid Heli FRAME_CLASS");
return false;
}

// check helicopter parameters
if (!copter.motors->parameter_check(display_failure)) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Heli motors checks failed");
return false;
}

char fail_msg[50];
// check input manager parameters
if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) {
Expand Down Expand Up @@ -630,7 +623,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
const char *rc_item = "Throttle";
#endif
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
if (!((method == AP_Arming::Method::MAVLINK || 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))) {
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
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
Expand Down Expand Up @@ -797,7 +790,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che

// do not allow disarm via mavlink if we think we are flying:
if (do_disarm_checks &&
method == AP_Arming::Method::MAVLINK &&
AP_Arming::method_is_GCS(method) &&
!copter.ap.land_complete) {
return false;
}
Expand Down
7 changes: 6 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -591,6 +591,11 @@ void Copter::ten_hz_logging_loop()
g2.winch.write_log();
}
#endif
#if HAL_MOUNT_ENABLED
if (should_log(MASK_LOG_CAMERA)) {
camera_mount.write_log();
}
#endif
}

// twentyfive_hz_logging - should be run at 25hz
Expand All @@ -617,7 +622,7 @@ void Copter::twentyfive_hz_logging()
#endif
}

// three_hz_loop - 3.3hz loop
// three_hz_loop - 3hz loop
void Copter::three_hz_loop()
{
// check if we've lost contact with the ground station
Expand Down
20 changes: 2 additions & 18 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -739,15 +739,15 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_co
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet)
{
switch(packet.command) {
case MAV_CMD_DO_FOLLOW:
#if MODE_FOLLOW_ENABLED == ENABLED
case MAV_CMD_DO_FOLLOW:
// param1: sysid of target to follow
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
copter.g2.follow.set_target_sysid((uint8_t)packet.param1);
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_DENIED;
#endif
return MAV_RESULT_UNSUPPORTED;

case MAV_CMD_DO_REPOSITION:
return handle_command_int_do_reposition(packet);
Expand Down Expand Up @@ -826,16 +826,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
}
return MAV_RESULT_ACCEPTED;

#if MODE_FOLLOW_ENABLED == ENABLED
case MAV_CMD_DO_FOLLOW:
// param1: sysid of target to follow
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
copter.g2.follow.set_target_sysid((uint8_t)packet.param1);
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
#endif

case MAV_CMD_CONDITION_YAW:
// param1 : target angle [0-360]
// param2 : speed during change [deg per second]
Expand Down Expand Up @@ -1013,12 +1003,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_ACCEPTED;
}

// pause or resume an auto mission
case MAV_CMD_DO_PAUSE_CONTINUE: {
mavlink_command_int_t packet_int;
GCS_MAVLINK_Copter::convert_COMMAND_LONG_to_COMMAND_INT(packet, packet_int);
return handle_command_pause_continue(packet_int);
}
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
}
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1040,6 +1040,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Description: set which surface to track in surface tracking
// @Values: 0:Do not track, 1:Ground, 2:Ceiling
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND),

// @Param: FS_DR_ENABLE
Expand Down
35 changes: 33 additions & 2 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,30 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.4.0 18-Aug-2023 / 4.4.0-beta5 12-Aug-2023
Changes from 4.4.0-beta4
1) Autopilots specific changes
- SIYI N7 support
2) Bug fixes
- DroneCAN airspeed sensor fix to handle missing packets
- DroneCAN GPS RTK injection fix
- Notch filter gyro glitch caused by race condition fixed
------------------------------------------------------------------
Copter 4.4.0-beta4 27-July-2023
Changes from 4.4.0-beta3
1) Autopilots specific changes
- Diatone-Mamba-MK4-H743v2 uses SPL06 baro (was DPS280)
- DMA for I2C disabled on F7 and H7 boards
- Foxeer H743v1 default serial protocol config fixes
- HeeWing-F405 and F405v2 support
- iFlight BlitzF7 support
2) Scripts may take action based on VTOL motor loss
3) Bug fixes
- BLHeli returns battery status requested via MSP (avoids hang when using esc-configurator)
- CRSFv3 rescans at baudrates to avoid RX loss
- EK3_ABIAS_P_NSE param range fix
- Scripting restart memory corruption bug fixed
- Siyi A8/ZR10 driver fix to avoid crash if serial port not configured
------------------------------------------------------------------
Copter 4.4.0-beta3 03-July-2023
Changes from 4.4.0-beta2
1) Autopilots specific changes
Expand All @@ -24,7 +49,6 @@ Changes from 4.4.0-beta2
- SERVOx_PROTOCOL "SToRM32 Gimbal Serial" value renamed to "Gimbal" because also used by Siyi
- SERIALx_OPTION "Swap" renamed to "SwapTXRX" for clarity
- SBF GPS ellipsoid height fixed
- Scripting restart memory corruption bug fixed
- Ublox M10S GPS auto configuration fixed
- ZigZag mode user takeoff fixed (users could not takeoff in ZigZag mode previously)
------------------------------------------------------------------
Expand Down Expand Up @@ -264,7 +288,14 @@ Changes from 4.3.6
- Webots 2023a simulator support
- XPlane support for wider range of aircraft
------------------------------------------------------------------
Copter 4.3.7-beta1 24-May-2023
Copter 4.3.8-beta1 12-Aug-2023
Changes from 4.3.7
1) Bug fixes
- DroneCAN GPS RTK injection fix
- INAxxx battery monitors allow for battery reset remaining
- Notch filter gyro glitch caused by race condition fixed
- Scripting restart memory corruption bug fixed
------------------------------------------------------------------
Copter 4.3.7 31-May-2023 / 4.3.7-beta1 24-May-2023
Changes from 4.3.6
1) Bug fixes
Expand Down
25 changes: 14 additions & 11 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
/// change in your local copy of APM_Config.h.
///
#include "APM_Config.h"
#include <AP_Follow/AP_Follow_config.h>


//////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -146,8 +147,8 @@

//////////////////////////////////////////////////////////////////////////////
// Nav-Guided - allows external nav computer to control vehicle
#ifndef NAV_GUIDED
# define NAV_GUIDED !HAL_MINIMIZE_FEATURES
#ifndef AC_NAV_GUIDED
# define AC_NAV_GUIDED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -189,7 +190,7 @@
//////////////////////////////////////////////////////////////////////////////
// Follow - follow another vehicle or GCS
#ifndef MODE_FOLLOW_ENABLED
# define MODE_FOLLOW_ENABLED !HAL_MINIMIZE_FEATURES
# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
Expand All @@ -201,7 +202,7 @@
//////////////////////////////////////////////////////////////////////////////
// GuidedNoGPS mode - control vehicle's angles from GCS
#ifndef MODE_GUIDED_NOGPS_ENABLED
# define MODE_GUIDED_NOGPS_ENABLED !HAL_MINIMIZE_FEATURES
# define MODE_GUIDED_NOGPS_ENABLED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -237,7 +238,7 @@
//////////////////////////////////////////////////////////////////////////////
// System ID - conduct system identification tests on vehicle
#ifndef MODE_SYSTEMID_ENABLED
# define MODE_SYSTEMID_ENABLED !HAL_MINIMIZE_FEATURES
# define MODE_SYSTEMID_ENABLED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
Expand All @@ -249,44 +250,46 @@
//////////////////////////////////////////////////////////////////////////////
// ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B
#ifndef MODE_ZIGZAG_ENABLED
# define MODE_ZIGZAG_ENABLED !HAL_MINIMIZE_FEATURES
# define MODE_ZIGZAG_ENABLED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// Turtle - allow vehicle to be flipped over after a crash
#ifndef MODE_TURTLE_ENABLED
# define MODE_TURTLE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME
# define MODE_TURTLE_ENABLED HAL_DSHOT_ENABLED && FRAME_CONFIG != HELI_FRAME
#endif

//////////////////////////////////////////////////////////////////////////////
// Flowhold - use optical flow to hover in place
#ifndef MODE_FLOWHOLD_ENABLED
# define MODE_FLOWHOLD_ENABLED !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
# define MODE_FLOWHOLD_ENABLED AP_OPTICALFLOW_ENABLED
#endif

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

//////////////////////////////////////////////////////////////////////////////
// Weathervane - allow vehicle to yaw into wind
#ifndef WEATHERVANE_ENABLED
# define WEATHERVANE_ENABLED !HAL_MINIMIZE_FEATURES
# define WEATHERVANE_ENABLED ENABLED
#endif

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

//////////////////////////////////////////////////////////////////////////////
// Autorotate - autonomous auto-rotation - helicopters only
#ifndef MODE_AUTOROTATE_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#if FRAME_CONFIG == HELI_FRAME
#ifndef MODE_AUTOROTATE_ENABLED
# define MODE_AUTOROTATE_ENABLED !HAL_MINIMIZE_FEATURES
# define MODE_AUTOROTATE_ENABLED ENABLED
#endif
#else
# define MODE_AUTOROTATE_ENABLED DISABLED
#endif
#else
# define MODE_AUTOROTATE_ENABLED DISABLED
#endif
#endif

//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
Expand Down Expand Up @@ -561,7 +564,7 @@
#endif

#ifndef AC_OAPATHPLANNER_ENABLED
#define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES
#define AC_OAPATHPLANNER_ENABLED ENABLED
#endif

#if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED
Expand Down
6 changes: 4 additions & 2 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -567,7 +567,7 @@ class ModeAuto : public Mode {
void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd);
void do_spline_wp(const AP_Mission::Mission_Command& cmd);
void get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc, Location& dest_loc, Location& next_dest_loc, bool& next_dest_loc_is_spline);
#if NAV_GUIDED == ENABLED
#if AC_NAV_GUIDED == ENABLED
void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
void do_guided_limits(const AP_Mission::Mission_Command& cmd);
#endif
Expand Down Expand Up @@ -605,7 +605,7 @@ class ModeAuto : public Mode {
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
bool verify_circle(const AP_Mission::Mission_Command& cmd);
bool verify_spline_wp(const AP_Mission::Mission_Command& cmd);
#if NAV_GUIDED == ENABLED
#if AC_NAV_GUIDED == ENABLED
bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
#endif
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
Expand Down Expand Up @@ -1726,6 +1726,7 @@ class ModeAvoidADSB : public ModeGuided {

};

#if AP_FOLLOW_ENABLED
class ModeFollow : public ModeGuided {

public:
Expand Down Expand Up @@ -1755,6 +1756,7 @@ class ModeFollow : public ModeGuided {

uint32_t last_log_ms; // system time of last time desired velocity was logging
};
#endif

class ModeZigZag : public Mode {

Expand Down

0 comments on commit fa00144

Please sign in to comment.