Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into missionrotation
Browse files Browse the repository at this point in the history
  • Loading branch information
robustini authored Dec 23, 2024
2 parents 940a8a9 + 169d6f6 commit 6de38d9
Show file tree
Hide file tree
Showing 245 changed files with 6,974 additions and 797 deletions.
32 changes: 32 additions & 0 deletions .github/problem-matchers/Lua.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
{
"problemMatcher": [
{
"owner": "Luacheck-problem-matcher",
"fileLocation": [ "relative", "${GITHUB_WORKSPACE}" ],
"pattern": [
{
"regexp": "^( *)(.+.lua):(\\d+):(\\d+): (.*)$",
"file": 2,
"line": 3,
"column": 4,
"message": 5
}
]
},
{
"owner": "Lua-language-server-problem-matcher",
"pattern": [
{
"regexp": "^(.+.lua):(\\d+):(\\d+)",
"file": 1,
"line": 2,
"column": 3
},
{
"regexp": "^(.*)",
"message": 1
}
]
}
]
}
1 change: 0 additions & 1 deletion .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,6 @@ jobs:
PATH: /usr/bin:$(cygpath ${SYSTEMROOT})/system32
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 &&
python3 -m pip install --progress-bar off empy==3.3.4 pexpect &&
python3 -m pip install --progress-bar off dronecan --upgrade &&
cp /usr/bin/ccache /usr/local/bin/ &&
Expand Down
18 changes: 1 addition & 17 deletions .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -175,9 +175,7 @@ jobs:
shell: bash
run: |
sudo apt-get update
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
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 cmake
python3 --version
pip3 install gevent
Expand All @@ -186,24 +184,10 @@ jobs:
sudo apt-get update
sudo apt-get 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
python3 --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-get remove --purge --auto-remove cmake
sudo apt-get update && \
sudo apt-get install -y software-properties-common lsb-release && \
sudo apt-get clean all
wget -O - https://apt.kitware.com/keys/kitware-archive-latest.asc 2>/dev/null | gpg --dearmor - | sudo tee /etc/apt/trusted.gpg.d/kitware.gpg >/dev/null
sudo apt-add-repository "deb https://apt.kitware.com/ubuntu/ $(lsb_release -cs) main"
sudo apt-get update
sudo apt-get install cmake
git submodule update --init --recursive --depth=1
./Tools/scripts/esp32_get_idf.sh
Expand Down
3 changes: 3 additions & 0 deletions .github/workflows/test_scripting.yml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,9 @@ jobs:
with:
submodules: 'recursive'

- name: Register lua problem matcher
run: echo "::add-matcher::.github/problem-matchers/Lua.json"

- name: Lua Linter
shell: bash
run: |
Expand Down
4 changes: 0 additions & 4 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,3 @@ ENV/
env.bak/
venv.bak/
autotest_result_*_junit.xml

# Ignore ESP-IDF SDK defines
/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig
/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig
49 changes: 48 additions & 1 deletion AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,53 @@
Antenna Tracker Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta 13 Nov 2024
Release 4.6.0-beta2 11 Dec 2024

Changes from 4.6.0-beta1

1) Board specfic changes

- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed

2) Copter specific enhancements and bug fixes

- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option

3) Plane related enhancements and bug fixes

- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes

4) Bug Fixes and minor enhancements

- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024

Changes from 4.5.7

Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Param: FS_GCS_ENABLE
// @DisplayName: Ground Station Failsafe Enable
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START or RTL,7:Brake or Land
// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land
// @User: Standard
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),

Expand Down Expand Up @@ -225,7 +225,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Param: FS_THR_ENABLE
// @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,6:Enabled Auto DO_LAND_START or RTL,7:Enabled always Brake or Land
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,6:Enabled Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Enabled always Brake or Land
// @User: Standard
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL),

Expand Down Expand Up @@ -1044,7 +1044,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FS_DR_ENABLE
// @DisplayName: DeadReckon Failsafe Action
// @Description: Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates
// @Values: 0:Disabled/NoAction,1:Land, 2:RTL, 3:SmartRTL or RTL, 4:SmartRTL or Land, 6:Auto DO_LAND_START or RTL
// @Values: 0:Disabled/NoAction,1:Land, 2:RTL, 3:SmartRTL or RTL, 4:SmartRTL or Land, 6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL
// @User: Standard
AP_GROUPINFO("FS_DR_ENABLE", 52, ParametersG2, failsafe_dr_enable, (uint8_t)Copter::FailsafeAction::RTL),

Expand Down
49 changes: 48 additions & 1 deletion ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,53 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta 13 Nov 2024
Release 4.6.0-beta2 11 Dec 2024

Changes from 4.6.0-beta1

1) Board specfic changes

- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed

2) Copter specific enhancements and bug fixes

- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option

3) Plane related enhancements and bug fixes

- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes

4) Bug Fixes and minor enhancements

- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024

Changes from 4.5.7

Expand Down
9 changes: 9 additions & 0 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -789,7 +789,16 @@ float Plane::tecs_hgt_afe(void)
coming.
*/
float hgt_afe;

if (flight_stage == AP_FixedWing::FlightStage::LAND) {

#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
// if external HAGL is active use that
if (get_external_HAGL(hgt_afe)) {
return hgt_afe;
}
#endif

hgt_afe = height_above_target();
#if AP_RANGEFINDER_ENABLED
hgt_afe -= rangefinder_correction();
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -745,7 +745,7 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: RTL_AUTOLAND
// @DisplayName: RTL auto land
// @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location. If this is set to 0 and there is a DO_LAND_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around without it changing RTL behaviour. For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation).
// @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation).If this is set to 0 and there is a DO_LAND_START or DO_RETURN_PATH_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around (see wiki for aborting autolandings) without it changing RTL behaviour.
// @Values: 0:Disable,1:Fly HOME then land via DO_LAND_START mission item, 2:Go directly to landing sequence via DO_LAND_START mission item, 3:OnlyForGoAround, 4:Go directly to landing sequence via DO_RETURN_PATH_START mission item
// @User: Standard
GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)),
Expand Down
49 changes: 48 additions & 1 deletion ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,53 @@
ArduPilot Plane Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta 13 Nov 2024
Release 4.6.0-beta2 11 Dec 2024

Changes from 4.6.0-beta1

1) Board specfic changes

- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed

2) Copter specific enhancements and bug fixes

- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option

3) Plane related enhancements and bug fixes

- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes

4) Bug Fixes and minor enhancements

- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024

Changes from 4.5.7

Expand Down
17 changes: 14 additions & 3 deletions ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,12 @@ void ModeTakeoff::update()
if (!takeoff_mode_setup) {
plane.auto_state.takeoff_altitude_rel_cm = alt * 100;
const uint16_t altitude = plane.relative_ground_altitude(false,true);
const float direction = degrees(ahrs.get_yaw());
const Vector2f &groundspeed2d = ahrs.groundspeed_vector();
const float direction = wrap_360(degrees(groundspeed2d.angle()));
const float groundspeed = groundspeed2d.length();

// see if we will skip takeoff as already flying
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && groundspeed > 3) {
if (altitude >= alt) {
gcs().send_text(MAV_SEVERITY_INFO, "Above TKOFF alt - loitering");
plane.next_WP_loc = plane.current_loc;
Expand Down Expand Up @@ -115,7 +118,15 @@ void ModeTakeoff::update()

plane.set_flight_stage(AP_FixedWing::FlightStage::TAKEOFF);

if (!plane.throttle_suppressed) {
/*
don't lock in the takeoff loiter location until we reach
a ground speed of AIRSPEED_MIN*0.3 to cope with aircraft
with no compass or poor compass. If flying in a very
strong headwind then the is_flying() check above will
eventually trigger
*/
if (!plane.throttle_suppressed &&
groundspeed > plane.aparm.airspeed_min*0.3) {
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff to %.0fm for %.1fm heading %.1f deg",
alt, dist, direction);
plane.takeoff_state.start_time_ms = millis();
Expand Down
Loading

0 comments on commit 6de38d9

Please sign in to comment.