Skip to content

Commit

Permalink
Merge Plane-4.5.3 into ArgenTech
Browse files Browse the repository at this point in the history
  • Loading branch information
robertlong13 committed May 28, 2024
2 parents 7b2b9f6 + 6cedbcb commit 4e75068
Show file tree
Hide file tree
Showing 156 changed files with 8,886 additions and 300 deletions.
84 changes: 66 additions & 18 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,68 @@
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
------------------------------------------------------------------
Release 4.5.2-beta1 29th April 2024

Changes from 4.5.1

1) Board specific enhancements and bug fixes

- FoxeerF405v2 support
- iFlight BLITZ Mini F745 support
- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup

2) System level minor enhancements and bug fixes

- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source
- Crashdump pre-arm check added
- Gimbal gets improved yaw lock reporting to GCS
- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input)
- RM3100 compass SPI bus speed reduced to 1Mhz
- SBUS output fix for channels 1 to 8 also applying to 9 to 16
- ViewPro gimbal supports enable/disable rangefinder from RC aux switch
- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS)
- fixed serial passthrough to avoid data loss at high data rates

3) AHRS / EKF fixes

- Compass learning disabled when using GPS-for-yaw
- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s)
- MicroStrain7 External AHRS position quantization bug fix
- MicroStrain7 init failure warning added
- MicroStrain5 and 7 position and velocity variance reporting fix

4) Other minor enhancements and bug fixes

- DDS_UDP_PORT parameter renamed (was DDS_PORT)
- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS)

------------------------------------------------------------------
Release 4.5.1 8th April 2024
Expand All @@ -11,25 +75,9 @@ be affected by the bug, so this was just a precaution.
There are no other changes in this release.

------------------------------------------------------------------
Release 4.5.0-beta4 22nd March 2024

Changes from 4.5.0-beta3

1) system changes

- fixed a cache corruption issue with microSD card data on H7 based boards
- rename parameter NET_ENABLED to NET_ENABLE
- fixed FDCAN labels for adding new H7 boards
- avoid logging dma.txt to save CPU
- fixed roll/pitch in viewpro driver
- added band X in VideoTX
- fixed quaternion attitude reporting for Microstrain external AHRS
- add RPLidarC1 proximity support

2) new boards
- added MicoAir405v2
- add Orqa F405 Pro
Release 4.5.0 2nd April 2024

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

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

#include "ap_version.h"

#define THISFIRMWARE "AntennaTracker V4.5.1"
#define THISFIRMWARE "AntennaTracker V4.5.3"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,1,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 1
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
75 changes: 75 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,80 @@
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
------------------------------------------------------------------
Release 4.5.2-beta1 29th April 2024

Changes from 4.5.1

1) Board specific enhancements and bug fixes

- FoxeerF405v2 support
- iFlight BLITZ Mini F745 support
- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup

2) System level minor enhancements and bug fixes

- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source
- Crashdump pre-arm check added
- Gimbal gets improved yaw lock reporting to GCS
- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input)
- RM3100 compass SPI bus speed reduced to 1Mhz
- SBUS output fix for channels 1 to 8 also applying to 9 to 16
- ViewPro gimbal supports enable/disable rangefinder from RC aux switch
- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS)
- fixed serial passthrough to avoid data loss at high data rates

3) AHRS / EKF fixes

- Compass learning disabled when using GPS-for-yaw
- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s)
- MicroStrain7 External AHRS position quantization bug fix
- MicroStrain7 init failure warning added
- MicroStrain5 and 7 position and velocity variance reporting fix

4) Copter specific changes

- Auto mode condition yaw fix to avoid pointing at out-of-date target
- Guided mode angle control yaw target initialisation fix (was always turning North)

5) Other minor enhancements and bug fixes

- DDS_UDP_PORT parameter renamed (was DDS_PORT)
- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS)

------------------------------------------------------------------

Release 4.5.1 8th April 2024

Expand Down
7 changes: 2 additions & 5 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,14 +313,11 @@ void ModeGuided::angle_control_start()

// initialise targets
guided_angle_state.update_time_ms = millis();
guided_angle_state.attitude_quat.initialise();
guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z));
guided_angle_state.ang_vel.zero();
guided_angle_state.climb_rate_cms = 0.0f;
guided_angle_state.yaw_rate_cds = 0.0f;
guided_angle_state.use_yaw_rate = false;

// pilot always controls yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
}

// set_destination - sets guided mode's target destination
Expand Down Expand Up @@ -939,7 +936,7 @@ void ModeGuided::angle_control_run()
// check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
uint32_t tnow = millis();
if (tnow - guided_angle_state.update_time_ms > get_timeout_ms()) {
guided_angle_state.attitude_quat.initialise();
guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z));
guided_angle_state.ang_vel.zero();
climb_rate_cms = 0.0f;
if (guided_angle_state.use_thrust) {
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.1"
#define THISFIRMWARE "ArduCopter V4.5.3"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,1,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 1
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -533,7 +533,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: PTCH_LIM_MIN_DEG
// @DisplayName: Minimum Pitch Angle
// @Description: Maximum pitch down angle commanded in modes with stabilized limits
// @Units: cdeg
// @Units: deg
// @Range: -90 0
// @Increment: 10
// @User: Standard
Expand Down
80 changes: 78 additions & 2 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
Release 4.5.1.1 8th April 2024
Release 4.5.3.1 8th April 2024
-------------------------------------
Changes from stock 4.5.1:
Changes from stock 4.5.3:

1) Safety patches
- Failsafe during auto takeoff switches to QLand #26260
Expand All @@ -14,6 +14,82 @@ Changes from stock 4.5.1:
3) Scripts (no impact on firmware)
- Created Engine-Out automatic failsafe script and associated tests

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
------------------------------------------------------------------
Release 4.5.2-beta1 29th April 2024

Changes from 4.5.1

1) Board specific enhancements and bug fixes

- FoxeerF405v2 support
- iFlight BLITZ Mini F745 support
- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup

2) System level minor enhancements and bug fixes

- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source
- Crashdump pre-arm check added
- Gimbal gets improved yaw lock reporting to GCS
- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input)
- RM3100 compass SPI bus speed reduced to 1Mhz
- SBUS output fix for channels 1 to 8 also applying to 9 to 16
- ViewPro gimbal supports enable/disable rangefinder from RC aux switch
- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS)
- fixed serial passthrough to avoid data loss at high data rates

3) AHRS / EKF fixes

- Compass learning disabled when using GPS-for-yaw
- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s)
- MicroStrain7 External AHRS position quantization bug fix
- MicroStrain7 init failure warning added
- MicroStrain5 and 7 position and velocity variance reporting fix

4) Plane specific changes

- Drop min Q_TRANSITION_MS to 500ms
- FBWB/CRUISE missing zero crossing of elevator input fix
- PTCH_LIM_MIN_DEG param units fixed to be deg

5) Other minor enhancements and bug fixes

- DDS_UDP_PORT parameter renamed (was DDS_PORT)
- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS)

Release 4.5.1 8th April 2024
----------------------------

Expand Down
14 changes: 7 additions & 7 deletions ArduPlane/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,13 @@ void ModeRTL::navigate()
}
#endif

uint16_t radius = abs(plane.g.rtl_radius);
if (radius > 0) {
plane.loiter.direction = (plane.g.rtl_radius < 0) ? -1 : 1;
}

plane.update_loiter(radius);

if (!plane.auto_state.checked_for_autoland) {
if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) ||
(plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START &&
Expand All @@ -116,13 +123,6 @@ void ModeRTL::navigate()
plane.auto_state.checked_for_autoland = true;
}
}

uint16_t radius = abs(plane.g.rtl_radius);
if (radius > 0) {
plane.loiter.direction = (plane.g.rtl_radius < 0) ? -1 : 1;
}

plane.update_loiter(radius);
}

#if HAL_QUADPLANE_ENABLED
Expand Down
13 changes: 7 additions & 6 deletions ArduPlane/navigation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -394,15 +394,16 @@ void Plane::update_fbwb_speed_height(void)
elevator_input = -elevator_input;
}

int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100;
change_target_altitude(alt_change_cm);

if (is_zero(elevator_input) && !is_zero(target_altitude.last_elevator_input)) {
// the user has just released the elevator, lock in
// the current altitude
bool input_stop_climb = !is_positive(elevator_input) && is_positive(target_altitude.last_elevator_input);
bool input_stop_descent = !is_negative(elevator_input) && is_negative(target_altitude.last_elevator_input);
if (input_stop_climb || input_stop_descent) {
// user elevator input reached or passed zero, lock in the current altitude
set_target_altitude_current();
}

int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100;
change_target_altitude(alt_change_cm);

#if HAL_SOARING_ENABLED
if (g2.soaring_controller.is_active()) {
if (g2.soaring_controller.get_throttle_suppressed()) {
Expand Down
Loading

0 comments on commit 4e75068

Please sign in to comment.