Skip to content

Commit

Permalink
Merge branch 'Plane-4.3' into pr-4.3/fix-ccache
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored Nov 9, 2023
2 parents a46a1e2 + ac69667 commit 73bfc7b
Show file tree
Hide file tree
Showing 17 changed files with 100 additions and 46 deletions.
8 changes: 8 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,13 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
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
8 changes: 4 additions & 4 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.3.7"
#define THISFIRMWARE "ArduCopter V4.3.8-beta1"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,3,7,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,3,8,FIRMWARE_VERSION_TYPE_BETA+1

#define FW_MAJOR 4
#define FW_MINOR 3
#define FW_PATCH 7
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_PATCH 8
#define FW_TYPE FIRMWARE_VERSION_TYPE_BETA

#include <AP_Common/AP_FWVersionDefine.h>
11 changes: 11 additions & 0 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,14 @@
Release 4.3.8 24th August 2023
------------------------------

Changes since 4.3.8:

- fixed scripting restart bug which could cause a crash on a math error
- fixed RTK injection when first module is a moving baseline BASE
- fixed auto-enable of fence on forced arm
- fixed race condition that can cause gyro glitches with notch filtering
- fixed INAxxx battery monitors to allow for battery reset remaining

Release 4.3.7 31st May 2023
---------------------------

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ bool Mode::enter()
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane.
plane.guided_state.target_alt = -1; // same as above, although a target alt of -1 is rare on plane.
plane.guided_state.target_alt_time_ms = 0;
plane.guided_state.last_target_alt = 0;
#endif

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.3.7"
#define THISFIRMWARE "ArduPlane V4.3.8"

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

#define FW_MAJOR 4
#define FW_MINOR 3
#define FW_PATCH 7
#define FW_PATCH 8
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

#include <AP_Common/AP_FWVersionDefine.h>
8 changes: 8 additions & 0 deletions Rover/release-notes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,13 @@
Rover Release Notes:
------------------------------------------------------------------
Rover 4.3.0-beta14 12-Aug-2023
Changes from 4.3.0-beta13
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
------------------------------------------------------------------
Rover 4.3.0-beta13 27-Mar-2023
Changes from 4.3.0-beta12
1) Bug fixes
Expand Down
4 changes: 2 additions & 2 deletions Rover/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,10 @@

#include "ap_version.h"

#define THISFIRMWARE "ArduRover V4.3.0-beta13"
#define THISFIRMWARE "ArduRover V4.3.0-beta14"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_BETA+13
#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_BETA+14

#define FW_MAJOR 4
#define FW_MINOR 3
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -1109,7 +1109,7 @@ def VibrationFailsafe(self):
self.change_mode("LAND")

# check vehicle descends to 2m or less within 40 seconds
self.wait_altitude(-5, 2, timeout=40, relative=True)
self.wait_altitude(-5, 2, timeout=50, relative=True)

# force disarm of vehicle (it will likely not automatically disarm)
self.disarm_vehicle(force=True)
Expand Down
23 changes: 13 additions & 10 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1479,16 +1479,6 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
}
}

#if AP_FENCE_ENABLED
AC_Fence *fence = AP::fence();
if (fence != nullptr) {
// If a fence is set to auto-enable, turn on the fence
if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
fence->enable(true);
}
}
#endif

// note that this will prepare AP_Logger to start logging
// so should be the last check to be done before arming

Expand Down Expand Up @@ -1565,6 +1555,19 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
}
#endif

#if AP_FENCE_ENABLED
if (armed) {
auto *fence = AP::fence();
if (fence != nullptr) {
// If a fence is set to auto-enable, turn on the fence
if (fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
fence->enable(true);
gcs().send_text(MAV_SEVERITY_INFO, "Fence: auto-enabled");
}
}
}
#endif

return armed;
}

Expand Down
1 change: 0 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend
bool has_cell_voltages() const override { return false; }
bool has_temperature() const override { return false; }
bool has_current() const override { return true; }
bool reset_remaining(float percentage) override { return false; }
bool get_cycle_count(uint16_t &cycles) const override { return false; }

void init(void) override;
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ class AP_BattMonitor_LTC2946 : public AP_BattMonitor_Backend
bool has_cell_voltages() const override { return false; }
bool has_temperature() const override { return false; }
bool has_current() const override { return true; }
bool reset_remaining(float percentage) override { return false; }
bool get_cycle_count(uint16_t &cycles) const override { return false; }

virtual void init(void) override;
Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_GPS/AP_GPS_UAVCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -947,9 +947,12 @@ void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len)
// using a different uavcan instance than the first GPS, as we
// send the data as broadcast on all UAVCAN devive ports and we
// don't want to send duplicates
const uint32_t now_ms = AP_HAL::millis();
if (_detected_module == 0 ||
_detected_modules[_detected_module].ap_uavcan != _detected_modules[0].ap_uavcan) {
_detected_modules[_detected_module].ap_uavcan != _detected_modules[0].ap_uavcan ||
now_ms - _detected_modules[0].last_inject_ms > 2000) {
_detected_modules[_detected_module].ap_uavcan->send_RTCMStream(data, len);
_detected_modules[_detected_module].last_inject_ms = now_ms;
}
}

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_GPS/AP_GPS_UAVCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend {
AP_UAVCAN* ap_uavcan;
uint8_t node_id;
uint8_t instance;
uint32_t last_inject_ms;
AP_GPS_UAVCAN* driver;
} _detected_modules[GPS_MAX_RECEIVERS];

Expand Down
43 changes: 23 additions & 20 deletions libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -687,7 +687,8 @@ void NavEKF3_core::checkGyroCalStatus(void)
void NavEKF3_core::updateFilterStatus(void)
{
// init return value
filterStatus.value = 0;
nav_filter_status status;
status.value = 0;
bool doingBodyVelNav = (PV_AidingMode != AID_NONE) && (imuSampleTime_ms - prevBodyVelFuseTime_ms < 5000);
bool doingFlowNav = (PV_AidingMode != AID_NONE) && flowDataValid;
bool doingWindRelNav = (!tasTimeout && assume_zero_sideslip()) || !dragTimeout;
Expand All @@ -700,28 +701,30 @@ void NavEKF3_core::updateFilterStatus(void)
bool hgtNotAccurate = (frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::GPS) && !validOrigin;

// set individual flags
filterStatus.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check)
filterStatus.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid
filterStatus.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid
filterStatus.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid
filterStatus.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid
filterStatus.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid
filterStatus.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid
filterStatus.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode
filterStatus.flags.pred_horiz_pos_rel = filterStatus.flags.horiz_pos_rel; // EKF3 enters the required mode before flight
filterStatus.flags.pred_horiz_pos_abs = filterStatus.flags.horiz_pos_abs; // EKF3 enters the required mode before flight
filterStatus.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
filterStatus.flags.takeoff = dal.get_takeoff_expected(); // The EKF has been told to expect takeoff is in a ground effect mitigation mode and has started the EKF-GSF yaw estimator
filterStatus.flags.touchdown = dal.get_touchdown_expected(); // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS); // GPS glitching is affecting navigation accuracy
filterStatus.flags.gps_quality_good = gpsGoodToAlign;
status.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check)
status.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid
status.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid
status.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid
status.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid
status.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid
status.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid
status.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode
status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_rel; // EKF3 enters the required mode before flight
status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs; // EKF3 enters the required mode before flight
status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
status.flags.takeoff = dal.get_takeoff_expected(); // The EKF has been told to expect takeoff is in a ground effect mitigation mode and has started the EKF-GSF yaw estimator
status.flags.touchdown = dal.get_touchdown_expected(); // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
status.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
status.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS); // GPS glitching is affecting navigation accuracy
status.flags.gps_quality_good = gpsGoodToAlign;
// for reporting purposes we report rejecting airspeed after 3s of not fusing when we want to fuse the data
filterStatus.flags.rejecting_airspeed = lastTasFailTime_ms != 0 &&
status.flags.rejecting_airspeed = lastTasFailTime_ms != 0 &&
(imuSampleTime_ms - lastTasFailTime_ms) < 1000 &&
(imuSampleTime_ms - lastTasPassTime_ms) > 3000;
filterStatus.flags.initalized = filterStatus.flags.initalized || healthy();
filterStatus.flags.dead_reckoning = (PV_AidingMode != AID_NONE) && doingWindRelNav && !((doingFlowNav && gndOffsetValid) || doingNormalGpsNav || doingBodyVelNav);
status.flags.initalized = status.flags.initalized || healthy();
status.flags.dead_reckoning = (PV_AidingMode != AID_NONE) && doingWindRelNav && !((doingFlowNav && gndOffsetValid) || doingNormalGpsNav || doingBodyVelNav);

filterStatus.value = status.value;
}

void NavEKF3_core::runYawEstimatorPrediction()
Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_Scripting/AP_Scripting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,15 @@ void AP_Scripting::repl_stop(void) {
// can't do any more cleanup here, closing the open FD's is the REPL's responsibility
}

/*
avoid optimisation of the thread function. This avoids nasty traps
where setjmp/longjmp does not properly handle save/restore of
floating point registers on exceptions. This is an extra protection
over the top of the fix in luaD_rawrunprotected() for the same issue
*/
#pragma GCC push_options
#pragma GCC optimize ("O0")

void AP_Scripting::thread(void) {
while (true) {
// reset flags
Expand Down Expand Up @@ -264,6 +273,7 @@ void AP_Scripting::thread(void) {
}
}
}
#pragma GCC pop_options

void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd_in)
{
Expand Down
12 changes: 10 additions & 2 deletions libraries/AP_Scripting/lua/src/ldo.c
Original file line number Diff line number Diff line change
Expand Up @@ -133,21 +133,29 @@ l_noret luaD_throw (lua_State *L, int errcode) {
}
}


// remove optimization
#pragma GCC push_options
#pragma GCC optimize ("O0")
int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) {
unsigned short oldnCcalls = L->nCcalls;
struct lua_longjmp lj;
lj.status = LUA_OK;
lj.previous = L->errorJmp; /* chain new error handler */
L->errorJmp = &lj;
LUAI_TRY(L, &lj,
#ifdef ARM_MATH_CM7
__asm__("vpush {s16-s31}");
#endif
(*f)(L, ud);
);
#ifdef ARM_MATH_CM7
__asm__("vpop {s16-s31}");
#endif
L->errorJmp = lj.previous; /* restore old error handler */
L->nCcalls = oldnCcalls;
return lj.status;
}

#pragma GCC pop_options
/* }====================================================== */


Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS_FTP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ void GCS_MAVLINK::ftp_worker(void) {
}

// if it's a rerequest and we still have the last response then send it
if ((request.sysid == reply.sysid) && (request.compid = reply.compid) &&
if ((request.sysid == reply.sysid) && (request.compid == reply.compid) &&
(request.session == reply.session) && (request.seq_number + 1 == reply.seq_number)) {
ftp_push_replies(reply);
continue;
Expand Down

0 comments on commit 73bfc7b

Please sign in to comment.