Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into L1windcomp
Browse files Browse the repository at this point in the history
  • Loading branch information
menschel authored Nov 11, 2024
2 parents 864761e + da69e22 commit 62bf4cd
Show file tree
Hide file tree
Showing 116 changed files with 4,326 additions and 345 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/colcon.yml
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ jobs:
source ~/ccache.conf &&
ccache -s
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: D:/a/ardupilot/ardupilot/ccache
key: ${{ steps.ccache_cache_timestamp.outputs.cache-key }}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/macos_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_chibios.yml
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{ matrix.gcc }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_coverage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_dds.yml
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.config }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_linux_sbc.yml
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_replay.yml
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
1 change: 1 addition & 0 deletions .github/workflows/test_scripts.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ jobs:
python-cleanliness,
astyle-cleanliness,
validate_board_list,
logger_metadata,
]
steps:
# git checkout the PR
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_blimp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/test_sitl_copter.yml
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down Expand Up @@ -302,7 +302,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down Expand Up @@ -222,7 +222,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_plane.yml
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_rover.yml
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_sub.yml
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_tracker.yml
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_size.yml
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_unit_tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
6 changes: 3 additions & 3 deletions AntennaTracker/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@

#include "ap_version.h"

#define THISFIRMWARE "AntennaTracker V4.6.0-dev"
#define THISFIRMWARE "AntennaTracker V4.7.0-dev"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV

#define FW_MAJOR 4
#define FW_MINOR 6
#define FW_MINOR 7
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

Expand Down
19 changes: 18 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -688,12 +688,29 @@ void Copter::three_hz_loop()
low_alt_avoidance();
}

// ap_value calculates a 32-bit bitmask representing various pieces of
// state about the Copter. It replaces a global variable which was
// used to track this state.
uint32_t Copter::ap_value() const
{
uint32_t ret = 0;

const bool *b = (const bool *)≈
for (uint8_t i=0; i<sizeof(ap); i++) {
if (b[i]) {
ret |= 1U<<i;
}
}

return ret;
}

// one_hz_loop - runs at 1Hz
void Copter::one_hz_loop()
{
#if HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_ANY)) {
Log_Write_Data(LogDataID::AP_STATE, ap.value);
Log_Write_Data(LogDataID::AP_STATE, ap_value());
}
#endif

Expand Down
74 changes: 38 additions & 36 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -347,46 +347,48 @@ class Copter : public AP_Vehicle {
# include USERHOOK_VARIABLES
#endif

// Documentation of GLobals:
typedef union {
struct {
uint8_t unused1 : 1; // 0
uint8_t unused_was_simple_mode : 2; // 1,2
uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully
uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised
uint8_t logging_started : 1; // 6 // true if logging has started
uint8_t land_complete : 1; // 7 // true if we have detected a landing
uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio
uint8_t usb_connected_unused : 1; // 9 // UNUSED
uint8_t rc_receiver_present_unused : 1; // 10 // UNUSED
uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test
uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 14 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
uint8_t system_time_set_unused : 1; // 16 // true if the system time has been set from the GPS
uint8_t gps_glitching : 1; // 17 // true if GPS glitching is affecting navigation accuracy
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
uint8_t land_repo_active : 1; // 21 // true if the pilot is overriding the landing position
uint8_t motor_interlock_switch : 1; // 22 // true if pilot is requesting motor interlock enable
uint8_t in_arming_delay : 1; // 23 // true while we are armed but waiting to spin motors
uint8_t initialised_params : 1; // 24 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
uint8_t unused3 : 1; // 25 // was compass_init_location; true when the compass's initial location has been set
uint8_t unused2 : 1; // 26 // aux switch rc_override is allowed
uint8_t armed_with_airmode_switch : 1; // 27 // we armed using a arming switch
uint8_t prec_land_active : 1; // 28 // true if precland is active
};
uint32_t value;
} ap_t;

ap_t ap;
// ap_value calculates a 32-bit bitmask representing various pieces of
// state about the Copter. It replaces a global variable which was
// used to track this state.
uint32_t ap_value() const;

// These variables are essentially global variables. These should
// be removed over time. It is critical that the offsets of these
// variables remain unchanged - the logging is dependent on this
// ordering!
struct PACKED {
bool unused1; // 0
bool unused_was_simple_mode_byte1; // 1
bool unused_was_simple_mode_byte2; // 2
bool pre_arm_rc_check; // 3 true if rc input pre-arm checks have been completed successfully
bool pre_arm_check; // 4 true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
bool auto_armed; // 5 stops auto missions from beginning until throttle is raised
bool unused_log_started; // 6
bool land_complete; // 7 true if we have detected a landing
bool new_radio_frame; // 8 Set true if we have new PWM data to act on from the Radio
bool unused_usb_connected; // 9
bool unused_receiver_present; // 10
bool compass_mot; // 11 true if we are currently performing compassmot calibration
bool motor_test; // 12 true if we are currently performing the motors test
bool initialised; // 13 true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
bool land_complete_maybe; // 14 true if we may have landed (less strict version of land_complete)
bool throttle_zero; // 15 true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
bool system_time_set_unused; // 16 true if the system time has been set from the GPS
bool gps_glitching; // 17 true if GPS glitching is affecting navigation accuracy
bool using_interlock; // 18 aux switch motor interlock function is in use
bool land_repo_active; // 19 true if the pilot is overriding the landing position
bool motor_interlock_switch; // 20 true if pilot is requesting motor interlock enable
bool in_arming_delay; // 21 true while we are armed but waiting to spin motors
bool initialised_params; // 22 true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
bool unused_compass_init_location; // 23
bool unused2_aux_switch_rc_override_allowed; // 24
bool armed_with_airmode_switch; // 25 we armed using a arming switch
bool prec_land_active; // 26 true if precland is active
} ap;

AirMode air_mode; // air mode is 0 = not-configured ; 1 = disabled; 2 = enabled;
bool force_flying; // force flying is enabled when true;

static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t");

// This is the state of the flight control system
// There are multiple states defined such as STABILIZE, ACRO,
Mode *flightmode;
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
Expand Up @@ -305,7 +305,7 @@ Changes from 4.5.0-beta1:
- broaden acceptance criteria for GPS yaw measurement for moving baseline yaw

------------------------------------------------------------------
Copter 4.5.0-beta1 30-Jan-2025
Copter 4.5.0-beta1 30-Jan-2024
Changes from 4.4.4
1) New autopilots supported
- ACNS-F405AIO
Expand Down Expand Up @@ -989,7 +989,7 @@ Changes from 4.3.6
e) Memory corruption bug in the STM32H757 (very rare)
f) RC input on IOMCU bug fix (RC might not be regained if lost)
------------------------------------------------------------------
Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6--beta2 27-Mar-2023
Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6-beta2 27-Mar-2023
Changes from 4.3.5
1) Bi-directional DShot fix for possible motor stop approx 72min after startup
------------------------------------------------------------------
Expand Down
8 changes: 2 additions & 6 deletions ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -535,11 +535,7 @@ void ModePosHold::update_brake_angle_from_velocity(float &brake_angle, float vel
}

// calculate velocity-only based lean angle
if (velocity >= 0) {
lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (velocity + 60.0f));
} else {
lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (-velocity + 60.0f));
}
lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (fabsf(velocity) + 60.0f));

// do not let lean_angle be too far from brake_angle
brake_angle = constrain_float(lean_angle, brake_angle - brake_rate, brake_angle + brake_rate);
Expand Down Expand Up @@ -592,7 +588,7 @@ void ModePosHold::update_wind_comp_estimate()
}

// limit acceleration
const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * 981.0f;
const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * (GRAVITY_MSS*100);
const float wind_comp_ef_len = wind_comp_ef.length();
if (!is_zero(accel_lim_cmss) && (wind_comp_ef_len > accel_lim_cmss)) {
wind_comp_ef *= accel_lim_cmss / wind_comp_ef_len;
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,6 @@ void Copter::update_auto_armed()
*/
bool Copter::should_log(uint32_t mask)
{
ap.logging_started = logger.logging_started();
return logger.should_log(mask);
}
#endif
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@

#include "ap_version.h"

#define THISFIRMWARE "ArduCopter V4.6.0-dev"
#define THISFIRMWARE "ArduCopter V4.7.0-dev"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV

#define FW_MAJOR 4
#define FW_MINOR 6
#define FW_MINOR 7
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

Expand Down
Loading

0 comments on commit 62bf4cd

Please sign in to comment.