Skip to content

Commit

Permalink
Merge branch 'master' into gpsid_detect
Browse files Browse the repository at this point in the history
  • Loading branch information
Bron2002 authored May 21, 2024
2 parents 3482356 + 7e8a69d commit 3515a06
Show file tree
Hide file tree
Showing 679 changed files with 28,450 additions and 5,352 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/test_environment.yml
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ jobs:
name: focal
- os: ubuntu
name: jammy
- os: ubuntu
name: lunar
- os: ubuntu
name: mantic
- os: ubuntu
name: noble
- os: archlinux
name: latest
- os: debian
Expand Down
18 changes: 18 additions & 0 deletions .github/workflows/test_scripting.yml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,17 @@ jobs:
sudo apt-get -y install lua-check
./Tools/scripts/run_luacheck.sh
- name: Language server check
shell: bash
run: |
python -m pip install github-release-downloader
python ./Tools/scripts/run_lua_language_check.py
- name: Generate docs md
shell: bash
run: |
./Tools/scripts/generate_lua_docs.sh
- name: copy docs
run: |
PATH="/github/home/.local/bin:$PATH"
Expand All @@ -53,3 +64,10 @@ jobs:
run: |
PATH="/github/home/.local/bin:$PATH"
python ./libraries/AP_Scripting/tests/docs_check.py "./libraries/AP_Scripting/docs/docs.lua" "./libraries/AP_Scripting/docs/current_docs.lua"
- name: Upload docs
uses: actions/upload-artifact@v3
with:
name: Docs
path: ScriptingDocs.md
retention-days: 7
5 changes: 5 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,11 @@ build.tmp.binaries/
tasklist.json
modules/esp_idf

# lua-language-server linter
ScriptingDocs.md
/lua-language-server/
repo-LuaLS-lua-language-server.cache

# Ignore Python virtual environments
# from: https://github.com/github/gitignore/blob/4488915eec0b3a45b5c63ead28f286819c0917de/Python.gitignore#L125
.env
Expand Down
2 changes: 0 additions & 2 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -518,7 +518,6 @@ const AP_Param::Info Tracker::var_info[] = {
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
// @Values: 0:None,1:Pitch,2:Yaw
// @Bitmask: 0:Pitch,1:Yaw
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),

Expand Down Expand Up @@ -556,7 +555,6 @@ const AP_Param::Info Tracker::var_info[] = {
// @DisplayName: Auto mode options
// @Description: 1: Scan for unknown target
// @User: Standard
// @Values: 0:None, 1: Scan for unknown target in auto mode
// @Bitmask: 0:Scan for unknown target
GSCALAR(auto_opts, "AUTO_OPTIONS", 0),

Expand Down
83 changes: 60 additions & 23 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,39 +1,76 @@
Antenna Tracker Release Notes:
------------------------------

------------------------------------------------------------------
Release 4.5.1 8th April 2024
Release 4.5.3-beta1 16th May 2024

This release fixes a critical bug in the CRSF R/C protocol parser that
can lead to a handfault and a vehicle crashing. A similar fix was
applied to the GHST protocol, although we believe that GHST could not
be affected by the bug, so this was just a precaution.
Changes from 4.5.2

There are no other changes in this release.
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.0-beta4 22nd March 2024
Release 4.5.2 14th May 2024

Changes from 4.5.0-beta3
No changes from 4.5.2-beta1
------------------------------------------------------------------
Release 4.5.2-beta1 29th April 2024

1) system changes
Changes from 4.5.1

- 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
1) Board specific enhancements and bug fixes

2) new boards
- added MicoAir405v2
- add Orqa F405 Pro
- 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.0 2nd April 2024
Release 4.5.1 8th April 2024

This release fixes a critical bug in the CRSF R/C protocol parser that
can lead to a handfault and a vehicle crashing. A similar fix was
applied to the GHST protocol, although we believe that GHST could not
be affected by the bug, so this was just a precaution.

There are no other changes in this release.

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

Expand Down
1 change: 0 additions & 1 deletion AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50),
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900, 55),
#if HAL_LOGGING_ENABLED
SCHED_TASK(ten_hz_logging_loop, 10, 300, 60),
SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65),
Expand Down
6 changes: 1 addition & 5 deletions AntennaTracker/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,7 @@ def build(bld):
bld.ap_stlib(
name=vehicle + '_libs',
ap_vehicle=vehicle,
ap_libraries=bld.ap_common_vehicle_libraries() + [
'AP_Beacon',
'AP_Arming',
'AP_RCMapper',
],
ap_libraries=bld.ap_common_vehicle_libraries(),
)

bld.ap_program(
Expand Down
12 changes: 0 additions & 12 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -495,18 +495,6 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
}
}

// check if home is too far from EKF origin
if (copter.far_from_EKF_origin(ahrs.get_home())) {
check_failed(display_failure, "Home too far from EKF origin");
return false;
}

// check if vehicle is too far from EKF origin
if (copter.far_from_EKF_origin(copter.current_loc)) {
check_failed(display_failure, "Vehicle too far from EKF origin");
return false;
}

// if we got here all must be ok
return true;
}
Expand Down
9 changes: 9 additions & 0 deletions ArduCopter/AP_ExternalControl_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,15 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f
return true;
}

bool AP_ExternalControl_Copter::set_global_position(const Location& loc)
{
// Check if copter is ready for external control and returns false if it is not.
if (!ready_for_external_control()) {
return false;
}
return copter.set_target_location(loc);
}

bool AP_ExternalControl_Copter::ready_for_external_control()
{
return copter.flightmode->in_guided_mode() && copter.motors->armed();
Expand Down
8 changes: 7 additions & 1 deletion ArduCopter/AP_ExternalControl_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,20 @@

#if AP_EXTERNAL_CONTROL_ENABLED

class AP_ExternalControl_Copter : public AP_ExternalControl {
class AP_ExternalControl_Copter : public AP_ExternalControl
{
public:
/*
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
Velocity is in earth frame, NED [m/s].
Yaw is in earth frame, NED [rad/s].
*/
bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override WARN_IF_UNUSED;

/*
Sets the target global position for a loiter point.
*/
bool set_global_position(const Location& loc) override WARN_IF_UNUSED;
private:
/*
Return true if Copter is ready to handle external control data.
Expand Down
28 changes: 16 additions & 12 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if AP_SERVORELAYEVENTS_ENABLED
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),
#endif
SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63),
#if AC_PRECLAND_ENABLED
SCHED_TASK(update_precland, 400, 50, 69),
#endif
Expand Down Expand Up @@ -273,32 +272,37 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,

constexpr int8_t Copter::_failsafe_priorities[7];

#if AP_SCRIPTING_ENABLED

#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
// set target location (for use by external control and scripting)
bool Copter::set_target_location(const Location& target_loc)
{
// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!flightmode->in_guided_mode()) {
return false;
}

if (mode_guided.do_user_takeoff_start(alt * 100.0f)) {
copter.set_auto_armed(true);
return true;
}
return false;
return mode_guided.set_destination(target_loc);
}
#endif //MODE_GUIDED_ENABLED == ENABLED
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

// set target location (for use by scripting)
bool Copter::set_target_location(const Location& target_loc)
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
{
// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!flightmode->in_guided_mode()) {
return false;
}

return mode_guided.set_destination(target_loc);
if (mode_guided.do_user_takeoff_start(alt * 100.0f)) {
copter.set_auto_armed(true);
return true;
}
return false;
}

// set target position (for use by scripting)
Expand Down
8 changes: 6 additions & 2 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -666,10 +666,15 @@ class Copter : public AP_Vehicle {
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
bool set_target_location(const Location& target_loc) override;
#endif // MODE_GUIDED_ENABLED == ENABLED
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
bool start_takeoff(float alt) override;
bool set_target_location(const Location& target_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 @@ -741,7 +746,6 @@ class Copter : public AP_Vehicle {
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
bool far_from_EKF_origin(const Location& loc);

// compassmot.cpp
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);
Expand Down
Loading

0 comments on commit 3515a06

Please sign in to comment.