Skip to content

Commit

Permalink
Merge 'Copter-4.5.3' into Copter-4.5-AocodaRC
Browse files Browse the repository at this point in the history
  • Loading branch information
lida2003 committed Jun 10, 2024
2 parents 6e3b24d + ee14ff3 commit 44b1107
Show file tree
Hide file tree
Showing 47 changed files with 4,253 additions and 66 deletions.
33 changes: 25 additions & 8 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,30 @@
Antenna Tracker Release Notes:
------------------------------
Release 4.5.3 28th May 2024

No changes from 4.5.3-beta1
------------------------------------------------------------------
Release 4.5.3-beta1 16th May 2024

Changes from 4.5.2

1) Board specific enhancements and bug fixes

- correct default GPS port on MambaH743v4
- added SDMODELV2
- added iFlight Blitz H7 Pro
- added BLITZ Wing H743
- added highres IMU sampling on Pixhawk6X

2) System level minor enhancements and bug fixes

- fixed rare crash bug in lua scripting on script fault handling
- fixed Neopixel pulse proportions to work with more LED variants
- fixed timeout in lua rangefinder drivers
- workaround hardware issue in IST8310 compass
- allow FIFO rate logging for highres IMU sampling

------------------------------------------------------------------
Release 4.5.2 14th May 2024

No changes from 4.5.2-beta1
Expand Down Expand Up @@ -52,14 +77,6 @@ There are no other changes in this release.
------------------------------------------------------------------
Release 4.5.0 2nd April 2024

No changes from 4.5.0-beta4
------------------------------------------------------------------
Release 4.5.0 2nd April 2024

No changes from 4.5.0-beta4
------------------------------------------------------------------
Release 4.5.0 2nd April 2024

No changes from 4.5.0-beta4
------------------------------------------------------------------
Release 4.5.0-beta4 22nd March 2024
Expand Down
6 changes: 2 additions & 4 deletions AntennaTracker/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,12 @@

#include "ap_version.h"

#define THISFIRMWARE "AntennaTracker V4.5.2"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,2,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL

#define FW_MAJOR 4
#define FW_MINOR 5
#define FW_PATCH 2
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
30 changes: 30 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,35 @@
ArduPilot Copter Release Notes:
-------------------------------
Release 4.5.3 28th May 2024

No changes from 4.5.3-beta1
------------------------------------------------------------------
Release 4.5.3-beta1 16th May 2024

Changes from 4.5.2

1) Board specific enhancements and bug fixes

- correct default GPS port on MambaH743v4
- added SDMODELV2
- added iFlight Blitz H7 Pro
- added BLITZ Wing H743
- added highres IMU sampling on Pixhawk6X

2) System level minor enhancements and bug fixes

- fixed rare crash bug in lua scripting on script fault handling
- fixed Neopixel pulse proportions to work with more LED variants
- fixed timeout in lua rangefinder drivers
- workaround hardware issue in IST8310 compass
- allow FIFO rate logging for highres IMU sampling

3) Copter specific changes

- fixed speed constraint during avoidance backoff
- zero D_FF during autotune twitch

------------------------------------------------------------------
Release 4.5.2 14th May 2024

No changes from 4.5.2-beta1
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@

#include "ap_version.h"

#define THISFIRMWARE "ArduCopter V4.5.2"
#define THISFIRMWARE "ArduCopter V4.5.3"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,2,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL

#define FW_MAJOR 4
#define FW_MINOR 5
#define FW_PATCH 2
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
29 changes: 29 additions & 0 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,34 @@
ArduPilot Plane Release Notes:
------------------------------
Release 4.5.3 28th May 2024

No changes from 4.5.3-beta1
------------------------------------------------------------------
Release 4.5.3-beta1 16th May 2024

Changes from 4.5.2

1) Board specific enhancements and bug fixes

- correct default GPS port on MambaH743v4
- added SDMODELV2
- added iFlight Blitz H7 Pro
- added BLITZ Wing H743
- added highres IMU sampling on Pixhawk6X

2) System level minor enhancements and bug fixes

- fixed rare crash bug in lua scripting on script fault handling
- fixed Neopixel pulse proportions to work with more LED variants
- fixed timeout in lua rangefinder drivers
- workaround hardware issue in IST8310 compass
- allow FIFO rate logging for highres IMU sampling

3) Plane specific changes

- fixed cancelling of FWD_GAIN setting for tiltrotors

------------------------------------------------------------------
Release 4.5.2 14th May 2024

No changes from 4.5.2-beta1
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ void Tiltrotor::continuous_update(void)
// operate in all VTOL modes except Q_AUTOTUNE. Forward rotor tilt is used to produce
// forward thrust equivalent to what would have been produced by a forward thrust motor
// set to quadplane.forward_throttle_pct()
const float fwd_g_demand = 0.01f * quadplane.forward_throttle_pct() / plane.quadplane.q_fwd_thr_gain;
const float fwd_g_demand = 0.01 * quadplane.forward_throttle_pct();
const float fwd_tilt_deg = MIN(degrees(atanf(fwd_g_demand)), (float)max_angle_deg);
slew(MIN(fwd_tilt_deg * (1/90.0), get_forward_flight_tilt()));
return;
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@

#include "ap_version.h"

#define THISFIRMWARE "ArduPlane V4.5.2"
#define THISFIRMWARE "ArduPlane V4.5.3"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,2,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL

#define FW_MAJOR 4
#define FW_MINOR 5
#define FW_PATCH 2
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
29 changes: 29 additions & 0 deletions Rover/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,34 @@
Rover Release Notes:
--------------------
Release 4.5.3 28th May 2024

No changes from 4.5.3-beta1
------------------------------------------------------------------
Release 4.5.3-beta1 16th May 2024

Changes from 4.5.2

1) Board specific enhancements and bug fixes

- correct default GPS port on MambaH743v4
- added SDMODELV2
- added iFlight Blitz H7 Pro
- added BLITZ Wing H743
- added highres IMU sampling on Pixhawk6X

2) System level minor enhancements and bug fixes

- fixed rare crash bug in lua scripting on script fault handling
- fixed Neopixel pulse proportions to work with more LED variants
- fixed timeout in lua rangefinder drivers
- workaround hardware issue in IST8310 compass
- allow FIFO rate logging for highres IMU sampling

3) Rover specific changes

- correct clamping of RTL_SPEED for fractional speed values

------------------------------------------------------------------
Release 4.5.2 14th May 2024

No changes from 4.5.2-beta1
Expand Down
2 changes: 1 addition & 1 deletion Rover/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ bool ModeRTL::_enter()
}

// initialise waypoint navigation library
g2.wp_nav.init(MAX(0, g2.rtl_speed));
g2.wp_nav.init(MAX(0.0f, g2.rtl_speed));

// set target to the closest rally point or home
#if HAL_RALLY_ENABLED
Expand Down
6 changes: 3 additions & 3 deletions Rover/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@

#include "ap_version.h"

#define THISFIRMWARE "ArduRover V4.5.2"
#define THISFIRMWARE "ArduRover V4.5.3"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,2,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL

#define FW_MAJOR 4
#define FW_MINOR 5
#define FW_PATCH 2
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
40 changes: 37 additions & 3 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,11 +65,11 @@ Reserved "NXP ucans32k146" 34
# values from external vendors
EXT_HW_RADIOLINK_MINI_PIX 3

# NOTE: the full range from 1000 to 1999 (inclusive) is reserved for
# NOTE: the full range from 1000 to 19999 (inclusive) is reserved for
# use by the ArduPilot bootloader. Do not allocate IDs in this range
# except via changes to the ArduPilot code

# Do not allocate IDs in the range 1000 to 1999 except via a PR
# Do not allocate IDs in the range 1000 to 19999 except via a PR
# against this file in https://github.com/ArduPilot/ardupilot/tree/master/Tools/AP_Bootloader/board_types.txt

# values starting with AP_ are implemented in the ArduPilot bootloader
Expand Down Expand Up @@ -227,7 +227,7 @@ AP_HW_YJUAV_A6 1113
AP_HW_YJUAV_A6Nano 1114
AP_HW_ACNS_CM4PILOT 1115
AP_HW_ACNS_F405AIO 1116
AP_HW_BLITZF7 1117
AP_HW_BLITZF7AIO 1117
AP_HW_RADIX2HD 1118
AP_HW_HEEWING_F405 1119
AP_HW_PodmanH7 1120
Expand Down Expand Up @@ -264,9 +264,21 @@ AP_HW_BotBloxSwitch 1148
AP_HW_MatekH7A3 1149
AP_HW_MicoAir405v2 1150
AP_HW_ORAQF405PRO 1155
AP_HW_CBU_StampH743 1156
AP_HW_FOXEERF405_V2 1157
AP_HW_CSKY405 1158
AP_HW_NxtPX4v2 1159
AP_HW_PixPilot-V6PRO 1160
AP_HW_MicoAir405Mini 1161
AP_HW_BlitzH7Pro 1162
AP_HW_BlitzF7Mini 1163
AP_HW_BlitzF7 1164
AP_HW_MicoAir743 1166
AP_HW_BlitzH7Wing 1168
AP_HW_SDMODELH7V2 1167

AP_HW_JHEMCUF405WING 1169
AP_HW_MatekG474 1170

AP_HW_ESP32_PERIPH 1205
AP_HW_ESP32S3_PERIPH 1206
Expand All @@ -283,7 +295,15 @@ AP_HW_VIMDRONES_PERIPH 1407

AP_HW_PIXHAWK6X_PERIPH 1408
AP_HW_CUBERED_PERIPH 1409
AP_HW_RadiolinkPIX6 1410

AP_HW_JHEMCU-H743HD 1411

AP_HW_LongbowF405 1422

AP_HW_MountainEagleH743 1444

AP_HW_SakuraRC-H743 2714

# IDs 5000-5099 reserved for Carbonix
# IDs 5100-5199 reserved for SYPAQ Systems
Expand All @@ -305,8 +325,22 @@ AP_HW_Sierra-TrueFlow 5307
AP_HW_Sierra-TrueNavIC-Pro 5308
AP_HW_Sierra-F1-Pro 5309

#IDs 5401-5499 reserved for holybro
AP_HW_Holybro-PMU-F4 5401
AP_HW_Holybro-UM982-G4 5402
AP_HW_Holybro-UM960-H7 5403
AP_HW_Holybro-PERIPH-H7 5404

#IDs 5501-5599 reserved for MATEKSYS
AP_HW_MATEKH743SE 5501

# IDs 6000-6099 reserved for SpektreWorks

# IDs 6600-6699 reserved for Eagle Eye Drones

# OpenDroneID enabled boards. Use 10000 + the base board ID
AP_HW_CubeOrange_ODID 10140
AP_HW_Pixhawk6_ODID 10053

# do not allocate board IDs above 10,000 for non-ODID boards.
# do not allocate board IDs above 19,999 in this file.
53 changes: 53 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -1602,6 +1602,58 @@ def MaxAltFence(self):

self.zero_throttle()

# MaxAltFence - fly up and make sure fence action does not trigger
# Also check that the vehicle will not try and descend too fast when trying to backup from a max alt fence due to avoidance
def MaxAltFenceAvoid(self):
'''Test Max Alt Fence Avoidance'''
self.takeoff(10, mode="LOITER")
"""Hold loiter position."""

# enable fence, only max altitude, defualt is 100m
# No action, rely on avoidance to prevent the breach
self.set_parameters({
"FENCE_ENABLE": 1,
"FENCE_TYPE": 1,
"FENCE_ACTION": 0,
})

# Try and fly past the fence
self.set_rc(3, 1920)

# Avoid should prevent the vehicle flying past the fence, so the altitude wait should timeouts
try:
self.wait_altitude(140, 150, timeout=90, relative=True)
raise NotAchievedException("Avoid should prevent reaching altitude")
except AutoTestTimeoutException:
pass
except Exception as e:
raise e

# Check descent is not too fast, allow 10% above the configured backup speed
max_descent_rate = -self.get_parameter("AVOID_BACKUP_SPD") * 1.1

def get_climb_rate(mav, m):
m_type = m.get_type()
if m_type != 'VFR_HUD':
return
if m.climb < max_descent_rate:
raise NotAchievedException("Decending too fast want %f got %f" % (max_descent_rate, m.climb))

self.context_push()
self.install_message_hook_context(get_climb_rate)

# Reduce fence alt, this will result in a fence breach, but there is no action.
# Avoid should then backup the vehicle to be under the new fence alt.
self.set_parameters({
"FENCE_ALT_MAX": 50,
})
self.wait_altitude(40, 50, timeout=90, relative=True)

self.context_pop()

self.set_rc(3, 1500)
self.do_RTL()

# fly_alt_min_fence_test - fly down until you hit the fence floor
def MinAltFence(self):
'''Test Min Alt Fence'''
Expand Down Expand Up @@ -10124,6 +10176,7 @@ def tests1d(self):
self.HorizontalFence,
self.HorizontalAvoidFence,
self.MaxAltFence,
self.MaxAltFenceAvoid,
self.MinAltFence,
self.FenceFloorEnabledLanding,
self.AutoTuneSwitch,
Expand Down
Binary file added Tools/bootloaders/BlitzH743Pro_bl.bin
Binary file not shown.
Loading

0 comments on commit 44b1107

Please sign in to comment.