Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into avoid-rid
Browse files Browse the repository at this point in the history
  • Loading branch information
xiemengjie-kay authored Jan 15, 2024
2 parents 33c998d + fb1209f commit a565292
Show file tree
Hide file tree
Showing 840 changed files with 28,279 additions and 7,841 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,7 @@ jobs:
shell: C:\cygwin\bin\bash.exe -eo pipefail '{0}'
run: >-
ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip &&
python -m pip install --progress-bar off empy pexpect &&
python -m pip install --progress-bar off empy==3.3.4 pexpect &&
python -m pip install --progress-bar off dronecan --upgrade &&
cp /usr/bin/ccache /usr/local/bin/ &&
cd /usr/local/bin && ln -s ccache /usr/local/bin/gcc &&
Expand Down
23 changes: 19 additions & 4 deletions .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -161,11 +161,26 @@ jobs:
- name: Install Prerequisites
shell: bash
run: |
sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0
sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10
update-alternatives --query python
python --version
pip3 install gevent
rm -rf /usr/local/bin/cmake
# we actualy want 3.11 .. but the above only gave us 3.10, not ok with esp32 builds.
sudo add-apt-repository ppa:deadsnakes/ppa
sudo apt update
sudo apt install python3.11 python3.11-venv python3.11-distutils -y
sudo apt-get install python3 python3-pip python3-venv python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools
update-alternatives --query python
pip3 install gevent
python --version
python3.11 --version
which python3.11
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3.11 11
update-alternatives --query python
rm -rf /usr/local/bin/cmake
sudo apt remove --purge --auto-remove cmake
sudo apt update && \
sudo apt install -y software-properties-common lsb-release && \
Expand All @@ -183,7 +198,7 @@ jobs:
cd modules/esp_idf
echo "Installing ESP-IDF tools...."
./install.sh 2>&1 > /dev/null
./install.sh esp32,esp32s3 2>&1 > /dev/null
cd ../..
Expand All @@ -200,7 +215,7 @@ jobs:
./install.sh
source ./export.sh
cd ../..
python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy dronecan
python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan
which cmake
./waf configure --board ${{matrix.config}}
./waf plane
Expand Down
5 changes: 4 additions & 1 deletion .github/workflows/test_chibios.yml
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,10 @@ jobs:
CubeRedPrimary-bootloader,
configure-all,
build-options-defaults-test,
signing
signing,
CubeOrange-PPP,
CubeOrange-SOHW,
Pixhawk6X-PPPGW,
]
toolchain: [
chibios,
Expand Down
3 changes: 2 additions & 1 deletion .github/workflows/test_linux_sbc.yml
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,8 @@ jobs:
bebop,
erlebrain2,
pxfmini,
pxf
pxf,
canzero,
]
toolchain: [
armhf,
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_rover.yml
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,8 @@ jobs:
- name: build rover ${{ matrix.toolchain }}
shell: bash
run: |
sudo apt-get update || true
sudo apt-get -y install ppp || true
git config --global --add safe.directory ${GITHUB_WORKSPACE}
if [[ ${{ matrix.toolchain }} == "clang" ]]; then
export CC=clang
Expand Down
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -39,3 +39,6 @@
path = modules/Micro-CDR
url = https://github.com/ardupilot/Micro-CDR.git
branch = master
[submodule "modules/lwip"]
path = modules/lwip
url = https://github.com/ArduPilot/lwip.git
1 change: 1 addition & 0 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,6 +313,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
MSG_MAG_CAL_PROGRESS,
#endif
MSG_EKF_STATUS_REPORT,
MSG_BATTERY_STATUS,
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
Expand Down
1 change: 1 addition & 0 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ const AP_Param::Info Tracker::var_info[] = {
// @DisplayName: Ground station MAVLink system ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
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/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -398,10 +398,10 @@ bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
return filt_status.flags.attitude;
}

#if HAL_PROXIMITY_ENABLED
// check nothing is too close to vehicle
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
{
#if HAL_PROXIMITY_ENABLED

if (!AP_Arming::proximity_checks(display_failure)) {
return false;
Expand All @@ -425,9 +425,9 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
}
#endif

#endif
return true;
}
#endif // HAL_PROXIMITY_ENABLED

// performs mandatory gps checks. returns true if passed
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@ class AP_Arming_Copter : public AP_Arming

bool pre_arm_checks(bool display_failure) override;
bool pre_arm_ekf_attitude_check();
#if HAL_PROXIMITY_ENABLED
bool proximity_checks(bool display_failure) const override;
#endif
bool arm_checks(AP_Arming::Method method) override;

// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
Expand Down
8 changes: 1 addition & 7 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,13 +404,7 @@ bool Copter::set_circle_rate(float rate_dps)
// set desired speed (m/s). Used for scripting.
bool Copter::set_desired_speed(float speed)
{
// exit if vehicle is not in auto mode
if (!flightmode->is_autopilot()) {
return false;
}

wp_nav->set_speed_xy(speed * 100.0f);
return true;
return flightmode->set_speed_xy(speed * 100.0f);
}

#if MODE_AUTO_ENABLED == ENABLED
Expand Down
9 changes: 2 additions & 7 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,12 +77,6 @@
#include "defines.h"
#include "config.h"

#if FRAME_CONFIG == HELI_FRAME
#define AC_AttitudeControl_t AC_AttitudeControl_Heli
#else
#define AC_AttitudeControl_t AC_AttitudeControl_Multi
#endif

#if FRAME_CONFIG == HELI_FRAME
#define MOTOR_CLASS AP_MotorsHeli
#else
Expand Down Expand Up @@ -485,7 +479,8 @@ class Copter : public AP_Vehicle {

// Attitude, Position and Waypoint navigation objects
// To-Do: move inertial nav up or other navigation variables down here
AC_AttitudeControl_t *attitude_control;
AC_AttitudeControl *attitude_control;
const struct AP_Param::GroupInfo *attitude_control_var_info;
AC_PosControl *pos_control;
AC_WPNav *wp_nav;
AC_Loiter *loiter_nav;
Expand Down
25 changes: 18 additions & 7 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ const AP_Param::Info Copter::var_info[] = {
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down Expand Up @@ -450,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 Expand Up @@ -497,11 +498,7 @@ const AP_Param::Info Copter::var_info[] = {

// @Group: ATC_
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
#if FRAME_CONFIG == HELI_FRAME
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli),
#else
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
#endif
GOBJECTVARPTR(attitude_control, "ATC_", &copter.attitude_control_var_info),

// @Group: PSC
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
Expand Down Expand Up @@ -699,6 +696,20 @@ const AP_Param::Info Copter::var_info[] = {
// @Values: 0:Stopped,1:Running
// @User: Standard
GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),

// @Param: THROW_ALT_MIN
// @DisplayName: Throw mode minimum altitude
// @Description: Minimum altitude above which Throw mode will detect a throw or a drop - 0 to disable the check
// @Units: m
// @User: Advanced
GSCALAR(throw_altitude_min, "THROW_ALT_MIN", 0),

// @Param: THROW_ALT_MAX
// @DisplayName: Throw mode maximum altitude
// @Description: Maximum altitude under which Throw mode will detect a throw or a drop - 0 to disable the check
// @Units: m
// @User: Advanced
GSCALAR(throw_altitude_max, "THROW_ALT_MAX", 0),
#endif

#if OSD_ENABLED || OSD_PARAM_ENABLED
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -383,6 +383,8 @@ class Parameters {
// 254,255: reserved

k_param_vehicle = 257, // vehicle common block of parameters
k_param_throw_altitude_min,
k_param_throw_altitude_max,

// the k_param_* space is 9-bits in size
// 511: reserved
Expand Down Expand Up @@ -463,6 +465,8 @@ class Parameters {

#if MODE_THROW_ENABLED == ENABLED
AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;
AP_Int16 throw_altitude_min; // minimum altitude in m above which a throw can be detected
AP_Int16 throw_altitude_max; // maximum altitude in m below which a throw can be detected
#endif

AP_Int16 rc_speed; // speed of fast RC Channels in Hz
Expand Down
15 changes: 15 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,20 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
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
- RADIX2HD supports external I2C compasses
- SpeedyBeeF405v4 support
2) Bug fixes
- DroneCAN battery monitor with cell monitor SoC reporting fix
- NTF_LED_TYPES parameter description fixed (was missing IS31FL3195)
- ProfiLED output fixed in both Notify and Scripting
- Scripting bug that could cause crash if parameters were added in flight
- STAT_BOOTCNT param fix (was not updating in some cases)
- Takeoff RPM check fixed where motors are attached to AUX channels
- don't query hobbywing DroneCAN ESC IDs while armed
------------------------------------------------------------------
Copter 4.4.3 14-Nov-2023
Changes from 4.4.3-beta1
1) AP_GPS: correct uBlox M10 configuration on low flash boards
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,9 +114,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di
} else {
// absolute angle
_fixed_yaw_offset_cd = wrap_180_cd(angle_deg * 100.0 - _yaw_angle_cd);
if ( direction < 0 && is_positive(_fixed_yaw_offset_cd) ) {
if (direction < 0 && is_positive(_fixed_yaw_offset_cd)) {
_fixed_yaw_offset_cd -= 36000.0;
} else if ( direction > 0 && is_negative(_fixed_yaw_offset_cd) ) {
} else if (direction > 0 && is_negative(_fixed_yaw_offset_cd)) {
_fixed_yaw_offset_cd += 36000.0;
}
}
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
10 changes: 9 additions & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ class Mode {
AC_PosControl *&pos_control;
AP_InertialNav &inertial_nav;
AP_AHRS &ahrs;
AC_AttitudeControl_t *&attitude_control;
AC_AttitudeControl *&attitude_control;
MOTOR_CLASS *&motors;
RC_Channel *&channel_roll;
RC_Channel *&channel_pitch;
Expand Down Expand Up @@ -679,6 +679,7 @@ class ModeAuto : public Mode {
int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
uint32_t condition_start;

// Land within Auto state
enum class State {
FlyToLocation = 0,
Descending = 1
Expand Down Expand Up @@ -713,6 +714,13 @@ class ModeAuto : public Mode {
float climb_rate; // climb rate in m/s. provided by mission command
uint32_t start_ms; // system time that nav attitude time command was received (used for timeout)
} nav_attitude_time;

// desired speeds
struct {
float xy; // desired speed horizontally in m/s. 0 if unset
float up; // desired speed upwards in m/s. 0 if unset
float down; // desired speed downwards in m/s. 0 if unset
} desired_speed_override;
};

#if AUTOTUNE_ENABLED == ENABLED
Expand Down
Loading

0 comments on commit a565292

Please sign in to comment.