Skip to content

Commit

Permalink
Merge branch 'master' into zeroOneBootLoader
Browse files Browse the repository at this point in the history
  • Loading branch information
ZeroOne-Aero authored Jul 19, 2024
2 parents 70aeafe + 5a54d9a commit 699cd75
Show file tree
Hide file tree
Showing 686 changed files with 44,470 additions and 28,414 deletions.
2 changes: 2 additions & 0 deletions .github/workflows/macos_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -188,5 +188,7 @@ jobs:
echo $PATH
./waf configure --board ${{matrix.config}}
./waf
./waf configure --board ${{matrix.config}} --debug
./waf
ccache -s
ccache -z
172 changes: 172 additions & 0 deletions .github/workflows/qurt_build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,172 @@
name: QURT Build

on:
push:
paths-ignore:
# remove other vehicles
- 'AntennaTracker/**'
- 'Blimp/**'
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
- 'Tools/CHDK-Script/**'
- 'Tools/CPUInfo/**'
- 'Tools/CodeStyle/**'
- 'Tools/FilterTestTool/**'
- 'Tools/Frame_params/**'
- 'Tools/GIT_Test/**'
- 'Tools/Hello/**'
- 'Tools/IO_Firmware/**'
- 'Tools/Linux_HAL_Essentials/**'
- 'Tools/LogAnalyzer/**'
- 'Tools/Pozyx/**'
- 'Tools/PrintVersion.py'
- 'Tools/Replay/**'
- 'Tools/UDP_Proxy/**'
- 'Tools/Vicon/**'
- 'Tools/bootloaders/**'
- 'Tools/completion/**'
- 'Tools/debug/**'
- 'Tools/environment_install/**'
- 'Tools/geotag/**'
- 'Tools/gittools/**'
- 'Tools/mavproxy_modules/**'
- 'Tools/simulink/**'
- 'Tools/vagrant/**'
# Discard python file from Tools/scripts as not used
- 'Tools/scripts/**.py'
- 'Tools/scripts/build_sizes/**'
- 'Tools/scripts/build_tests/**'
- 'Tools/scripts/CAN/**'
- 'Tools/scripts/signing/**'
# Remove autotest
- 'Tools/autotest/**'
# Remove markdown files as irrelevant
- '**.md'
# Remove dotfile at root directory
- './.dir-locals.el'
- './.dockerignore'
- './.editorconfig'
- './.flake8'
- './.gitattributes'
- './.github'
- './.gitignore'
- './.pre-commit-config.yaml'
- './.pydevproject'
- './.valgrind-suppressions'
- './.valgrindrc'
- 'Dockerfile'
- 'Vagrantfile'
- 'Makefile'
# Remove some directories check
- '.vscode/**'
- '.github/ISSUE_TEMPLATE/**'
# Remove change on other workflows
- '.github/workflows/test_environment.yml'

pull_request:
paths-ignore:
# remove other vehicles
- 'AntennaTracker/**'
- 'Blimp/**'
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
- 'Tools/bootloaders/**'
- 'Tools/CHDK-Script/**'
- 'Tools/CodeStyle/**'
- 'Tools/completion/**'
- 'Tools/CPUInfo/**'
- 'Tools/debug/**'
- 'Tools/environment_install/**'
- 'Tools/FilterTestTool/**'
- 'Tools/Frame_params/**'
- 'Tools/geotag/**'
- 'Tools/GIT_Test/**'
- 'Tools/gittools/**'
- 'Tools/Hello/**'
- 'Tools/IO_Firmware/**'
- 'Tools/Linux_HAL_Essentials/**'
- 'Tools/LogAnalyzer/**'
- 'Tools/mavproxy_modules/**'
- 'Tools/Pozyx/**'
- 'Tools/PrintVersion.py'
- 'Tools/Replay/**'
- 'Tools/simulink/**'
- 'Tools/UDP_Proxy/**'
- 'Tools/vagrant/**'
- 'Tools/Vicon/**'
# Discard python file from Tools/scripts as not used
- 'Tools/scripts/**.py'
- 'Tools/scripts/build_sizes/**'
- 'Tools/scripts/build_tests/**'
- 'Tools/scripts/CAN/**'
- 'Tools/scripts/signing/**'
# Remove autotest
- 'Tools/autotest/**'
# Remove markdown files as irrelevant
- '**.md'
# Remove dotfile at root directory
- './.dir-locals.el'
- './.dockerignore'
- './.editorconfig'
- './.flake8'
- './.gitattributes'
- './.github'
- './.gitignore'
- './.pre-commit-config.yaml'
- './.pydevproject'
- './.valgrind-suppressions'
- './.valgrindrc'
- 'Dockerfile'
- 'Vagrantfile'
- 'Makefile'
# Remove some directories check
- '.vscode/**'
- '.github/ISSUE_TEMPLATE/**'
# Remove change on other workflows
- '.github/workflows/test_environment.yml'

workflow_dispatch:

concurrency:
group: ci-${{github.workflow}}-${{ github.ref }}
cancel-in-progress: true

jobs:
build:
runs-on: 'ardupilot-qurt'

steps:
- uses: actions/checkout@v4
with:
submodules: 'recursive'

- name: Build QURT
run: |
./waf configure --board QURT
./waf copter
./waf plane
./waf rover
cp -a build/QURT/bin/arducopter build/QURT/ArduPilot.so
cp -a build/QURT/bin/arducopter build/QURT/ArduPilot_Copter.so
cp -a build/QURT/bin/arduplane build/QURT/ArduPilot_Plane.so
cp -a build/QURT/bin/ardurover build/QURT/ArduPilot_Rover.so
- name: Archive build
uses: actions/upload-artifact@v3
with:
name: qurt-binaries
path: |
build/QURT/ardupilot
build/QURT/ArduPilot_Copter.so
build/QURT/ArduPilot_Plane.so
build/QURT/ArduPilot_Rover.so
build/QURT/ArduPilot.so
retention-days: 7
35 changes: 35 additions & 0 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,40 @@
Antenna Tracker Release Notes:
------------------------------
Release 4.5.5-beta1 1st July 2024

Changes from 4.5.4

1) Board specific enhancements and bug fixes

- fixed IOMCU transmission errors when using bdshot
- update relay parameter names on various boards
- add ASP5033 airspeed in minimal builds
- added RadiolinkPIX6
- fix Aocoda-RC H743Dual motor issue
- use ICM45686 as an ICM20649 alternative in CubeRedPrimary

2) System level minor enhancements and bug fixes

- correct use-after-free in script statistics
- added arming check for eeprom full
- fixed a block logging issue which caused log messages to be dropped
- enable Socket SO_REUSEADDR on LwIP
- removed IST8310 overrun message
- added Siyi ZT6 support
- added BTFL sidebar symbols to the OSD
- added CRSF extended link stats to the OSD
- use the ESC with the highest RPM in the OSD when only one can be displayed
- support all Tramp power levels on high power VTXs
- emit jump count in missions even if no limit
- improve the bitmask indicating persistent parameters on bootloader flash
- fix duplicate error condition in the MicroStrain7

5) Other minor enhancements and bug fixes

- specify pymonocypher version in more places
- added DroneCAN dependencies to custom builds

------------------------------------------------------------------
Release 4.5.4 12th June 2024

Changes from 4.5.3
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
//#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
//#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
Expand Down
6 changes: 5 additions & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -257,6 +257,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
return false;
break;
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
#if AP_RANGEFINDER_ENABLED
if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no rangefinder");
return false;
Expand All @@ -266,6 +267,9 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "RTL_ALT>RNGFND_MAX_CM");
return false;
}
#else
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "rangefinder not in firmware");
#endif
break;
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
// these checks are done in AP_Arming
Expand Down Expand Up @@ -444,7 +448,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif

if (mode_requires_gps) {
if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {
if (!copter.position_ok()) {
// vehicle level position estimate checks
check_failed(display_failure, "Need Position Estimate");
Expand Down
28 changes: 27 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#endif
SCHED_TASK(auto_disarm_check, 10, 50, 27),
SCHED_TASK(auto_trim, 10, 75, 30),
#if RANGEFINDER_ENABLED == ENABLED
#if AP_RANGEFINDER_ENABLED
SCHED_TASK(read_rangefinder, 20, 100, 33),
#endif
#if HAL_PROXIMITY_ENABLED
Expand Down Expand Up @@ -446,6 +446,32 @@ bool Copter::has_ekf_failsafed() const
return failsafe.ekf;
}

// get target location (for use by scripting)
bool Copter::get_target_location(Location& target_loc)
{
return flightmode->get_wp(target_loc);
}

/*
update_target_location() acts as a wrapper for set_target_location
*/
bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)
{
/*
by checking the caller has provided the correct old target
location we prevent a race condition where the user changes mode
or commands a different target in the controlling lua script
*/
Location next_WP_loc;
flightmode->get_wp(next_WP_loc);
if (!old_loc.same_loc_as(next_WP_loc) ||
old_loc.get_alt_frame() != new_loc.get_alt_frame()) {
return false;
}

return set_target_location(new_loc);
}

#endif // AP_SCRIPTING_ENABLED

// returns true if vehicle is landing. Only used by Lua scripts
Expand Down
10 changes: 8 additions & 2 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@
#if AP_TERRAIN_AVAILABLE
# include <AP_Terrain/AP_Terrain.h>
#endif
#if RANGEFINDER_ENABLED == ENABLED
#if AP_RANGEFINDER_ENABLED
# include <AP_RangeFinder/AP_RangeFinder.h>
#endif

Expand Down Expand Up @@ -258,6 +258,7 @@ class Copter : public AP_Vehicle {
// helper function to get inertially interpolated rangefinder height.
bool get_rangefinder_height_interpolated_cm(int32_t& ret) const;

#if AP_RANGEFINDER_ENABLED
class SurfaceTracking {
public:

Expand Down Expand Up @@ -292,6 +293,7 @@ class Copter : public AP_Vehicle {
bool valid_for_logging; // true if we have a desired target altitude
bool reset_target; // true if target should be reset because of change in surface being tracked
} surface_tracking;
#endif

#if AP_RPM_ENABLED
AP_RPM rpm_sensor;
Expand Down Expand Up @@ -626,6 +628,7 @@ class Copter : public AP_Vehicle {
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};
// returns true if option is enabled for this vehicle
bool option_is_enabled(FlightOption option) const {
Expand Down Expand Up @@ -670,6 +673,8 @@ class Copter : public AP_Vehicle {
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
bool start_takeoff(float alt) override;
bool get_target_location(Location& target_loc) override;
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override;
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override;
Expand Down Expand Up @@ -825,7 +830,8 @@ class Copter : public AP_Vehicle {
void set_land_complete(bool b);
void set_land_complete_maybe(bool b);
void update_throttle_mix();

bool get_force_flying() const;

#if AP_LANDINGGEAR_ENABLED
// landing_gear.cpp
void landinggear_update();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif

#if RANGEFINDER_ENABLED == ENABLED
#if AP_RANGEFINDER_ENABLED
const RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
Expand Down
Loading

0 comments on commit 699cd75

Please sign in to comment.