Skip to content

Commit

Permalink
Merge remote-tracking branch 'ArduPilot/Copter-4.4' into Copter-4.4-K…
Browse files Browse the repository at this point in the history
…akuteH7Mini_OEM
  • Loading branch information
martinwilco committed Dec 13, 2023
2 parents 06e856f + 981b721 commit bae5171
Show file tree
Hide file tree
Showing 157 changed files with 8,932 additions and 813 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ jobs:
shell: C:\cygwin\bin\bash.exe -eo pipefail '{0}'
run: >-
ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip &&
python -m pip install --progress-bar off empy pexpect &&
python -m pip install --progress-bar off empy==3.3.4 pexpect &&
python -m pip install --progress-bar off dronecan --upgrade &&
cp /usr/bin/ccache /usr/local/bin/ &&
cd /usr/local/bin && ln -s ccache /usr/local/bin/gcc &&
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ jobs:
./install.sh
source ./export.sh
cd ../..
python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy dronecan
python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan
which cmake
./waf configure --board ${{matrix.config}}
./waf plane
Expand Down
3 changes: 2 additions & 1 deletion AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,15 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK

using GCS_MAVLINK::GCS_MAVLINK;

uint8_t sysid_my_gcs() const override;

protected:

// telem_delay is not used by Tracker but is pure virtual, thus
// this implementaiton. it probably *should* be used by Tracker,
// as currently Tracker may brick XBees
uint32_t telem_delay() const override { return 0; }

uint8_t sysid_my_gcs() const override;

MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_long_t &packet) override;
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/GCS_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,10 @@ class GCS_Copter : public GCS
bool simple_input_active() const override;
bool supersimple_input_active() const override;

uint8_t sysid_this_mav() const override;

protected:

uint8_t sysid_this_mav() const override;

// minimum amount of time (in microseconds) that must remain in
// the main scheduler loop before we are allowed to send any
Expand Down
58 changes: 57 additions & 1 deletion ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,62 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.4.4 05-Dec-2023
Changes from 4.4.3
1) Autopilot related enhancement and fixes
- CubeOrange Sim-on-hardware compilation fix
- RADIX2HD supports external I2C compasses
- SpeedyBeeF405v4 support
2) Bug fixes
- DroneCAN battery monitor with cell monitor SoC reporting fix
- NTF_LED_TYPES parameter description fixed (was missing IS31FL3195)
- ProfiLED output fixed in both Notify and Scripting
- Scripting bug that could cause crash if parameters were added in flight
- STAT_BOOTCNT param fix (was not updating in some cases)
- Takeoff RPM check fixed where motors are attached to AUX channels
- don't query hobbywing DroneCAN ESC IDs while armed
------------------------------------------------------------------
Copter 4.4.3 14-Nov-2023
Changes from 4.4.3-beta1
1) AP_GPS: correct uBlox M10 configuration on low flash boards
------------------------------------------------------------------
Copter 4.4.3-beta1 07-Nov-2023
Changes from 4.4.2
1) Autopilot related enhancements and fixes
- BETAFTP-F405 board configuration fixes
- CubeOrangePlus-BG edition ICM45486 IMU setup fixed
- YJUAV_A6SE_H743 support
2) Minor enhancements
- GPS_DRV_OPTION allows using ellipsoid height in more GPS drivers
- Lua script support for fully populating ESC telemetry data
3) Bug fixes
- AK09916 compass being non-responsive fixed
- IxM42xxx IMUs "stuck" gyros fixed
- MAVLink response fixed when no airspeed sensor during preflight calibration
- Notch filtering protection when using uninitialised RPM source in ESC telemetry
- SIYI gimbal driver parsing bug fixed (was causing lost packets)
------------------------------------------------------------------
Copter 4.4.2 22-Oct-2023 / Copter 4.4.2-beta1 13-Oct-2023
Changes from 4.4.1
1) Autopilot related enhancements and fixes
- BETAFPV-F405 support
- MambaF405v2 battery and serial setup corrected
- mRo Control Zero OEM H7 bdshot support
- SpeedyBee-F405-Wing gets VTX power control
- SpeedyBee-F405-Mini support
- T-Motor H743 Mini support
2) EKF3 supports baroless boards
3) GPS-for-yaw allows base GPS to update at only 3Hz
4) INA battery monitor supports config of shunt resistor used (see BATTx_SHUNT)
5) Log VER message includes vehicle type
6) OpenDroneId option to auto-store IDs in persistent flash
7) RC SBUS protection against invalid data in first 4 channels
8) Bug fixes
- BMI088 IMU error value handling fixed to avoid occasional negative spike
- Dev environment CI autotest stability improvements
- OSD correct DisplayPort BF MSP symbols
- OSD option to correct direction arrows for BF font set
- Sensor status reporting to GCS fixed for baroless boards
------------------------------------------------------------------
Copter 4.4.1 26-Sep-2023 / 4.4.1-beta2 14-Sep-2023
Changes from 4.4.1-beta1
1) Autopilot related enhancements
Expand Down Expand Up @@ -194,7 +251,6 @@ Changes from 4.3.6
- Touchdown detection threshold is configurable (see PLDP_THRESH)
- Position controller angle max adjusted inflight with CH6 Tuning knob (set TUNE=59)
- Surface tracking time constant allows tuning response (see SURFTRAK_TC)
- Takeoff throttle max is configurable (see TKOFF_TH_MAX)
- Throttle-Gain boost increases attitude control gains when throttle high (see ATC_THR_G_BOOST)
- Waypoint navigation cornering acceleration is configurable (see WPNAV_ACCEL_C)
- WeatherVane into the wind in Auto and Guided modes (see WVANE_ENABLE)
Expand Down
6 changes: 6 additions & 0 deletions ArduCopter/takeoff_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ void Copter::takeoff_check()

// check ESCs are sending RPM at expected level
uint32_t motor_mask = motors->get_motor_mask();
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
// In 4.4 and earlier ESC telemetry is always indexed from 1 for servo channels 9+
motor_mask >>= 8;
}
#endif
const bool telem_active = AP::esc_telem().is_telemetry_active(motor_mask);
const bool rpm_adequate = AP::esc_telem().are_motors_running(motor_mask, g2.takeoff_rpm_min);

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.4.1"
#define THISFIRMWARE "ArduCopter V4.4.4-beta1"

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

#define FW_MAJOR 4
#define FW_MINOR 4
#define FW_PATCH 1
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_PATCH 4
#define FW_TYPE FIRMWARE_VERSION_TYPE_BETA

#include <AP_Common/AP_FWVersionDefine.h>
4 changes: 2 additions & 2 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,7 @@ void Plane::stabilize_stick_mixing_fbw()
// non-linear and ends up as 2x the maximum, to ensure that
// the user can direct the plane in any direction with stick
// mixing.
float roll_input = channel_roll->norm_input();
float roll_input = channel_roll->norm_input_dz();
if (roll_input > 0.5f) {
roll_input = (3*roll_input - 1);
} else if (roll_input < -0.5f) {
Expand All @@ -273,7 +273,7 @@ void Plane::stabilize_stick_mixing_fbw()
return;
}

float pitch_input = channel_pitch->norm_input();
float pitch_input = channel_pitch->norm_input_dz();
if (pitch_input > 0.5f) {
pitch_input = (3*pitch_input - 1);
} else if (pitch_input < -0.5f) {
Expand Down
3 changes: 2 additions & 1 deletion ArduPlane/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,14 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK

using GCS_MAVLINK::GCS_MAVLINK;

uint8_t sysid_my_gcs() const override;

protected:

uint32_t telem_delay() const override;

void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg) override;

uint8_t sysid_my_gcs() const override;
bool sysid_enforce() const override;

MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
Expand Down
5 changes: 4 additions & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -723,6 +723,9 @@ class Plane : public AP_Vehicle {
// are we trying to follow terrain?
bool terrain_following;

// are we waiting to load terrain data to init terrain following
bool terrain_following_pending;

// target altitude above terrain in cm, valid if terrain_following
// is set
int32_t terrain_alt_cm;
Expand Down Expand Up @@ -836,7 +839,7 @@ class Plane : public AP_Vehicle {
void reset_offset_altitude(void);
void set_offset_altitude_location(const Location &start_loc, const Location &destination_loc);
bool above_location_current(const Location &loc);
void setup_terrain_target_alt(Location &loc) const;
void setup_terrain_target_alt(Location &loc);
int32_t adjusted_altitude_cm(void);
int32_t adjusted_relative_altitude_cm(void);
float mission_alt_offset(void);
Expand Down
62 changes: 62 additions & 0 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,65 @@
Release 4.4.4-beta1 5th December 2023
-------------------------------------

Changes from 4.4.3:

- CubeOrange Sim-on-hardware compilation fix
- RADIX2HD supports external I2C compasses
- SpeedyBeeF405v4 support
- DroneCAN battery monitor with cell monitor SoC reporting fix
- ProfiLED output fixed in both Notify and Scripting
- NTF_LED_TYPES parameter description fixed (was missing IS31FL3195)
- Scripting bug that could cause crash if parameters were added in flight
- STAT_BOOTCNT param fix (was not updating in some cases)
- don't query hobbywing DroneCAN ESC IDs while armed
- clamp empy version to prevent build errors

Release 4.4.3 14th November 2023
--------------------------------

Changes from 4.4.2:

- fixed setup of ICM45486 IMU on CubeOrangePlus-BG edition
- disable AFSR on IxM42xxx IMUs to prevent gyro bias for "stuck" gyros
- fixed AK09916 compass being non-responsive
- implement GPS_DRV_OPTION for using ellipsoid height in more GPS drivers
- fixed SIYI AP_Mount parsing bug
- configuration fixes for BETAFTP-F405 boards
- fixed origin versus home relative bug in quadplane landing and guided takeoff
- correct mavlink response for no airspeed sensor on preflight calibration
- protect against notch filtering with uninitialised RPM source in ESC telemetry
- allow lua scripts to populate full ESC telemetry data
- added YJUAV_A6SE_H743 support
- fixed uBlox M10 GPS support on boards with 1M flash

Release 4.4.2 23th October 2023
-------------------------------

Changes from 4.4.1

- BETAFPV-F405 support
- MambaF405v2 battery and serial setup corrected
- mRo Control Zero OEM H7 bdshot support
- SpeedyBee-F405-Wing gets VTX power control
- SpeedyBee-F405-Mini support
- T-Motor H743 Mini support
- EKF3 supports baroless boards
- INA battery monitor supports config of shunt resistor used (see BATTx_SHUNT)
- BMI088 IMU error value handling fixed to avoid occasional negative spike
- Dev environment CI autotest stability improvements
- OSD correct DisplayPort BF MSP symbols
- OSD option to correct direction arrows for BF font set
- Sensor status reporting to GCS fixed for baroless boards
- added opendroneid option to auto-store IDs in persistent flash
- fixed TECS bug that could cause inability to climb or descend
- fixed race condition when starting TECS controlled mode
- fixed RTL with rally point and terrain follow
- protect against invalid data in SBUS for first 4 channels
- added build type to VER message
- allow moving baseline rover at 3Hz
- use RC deadzones in stick mixing


Release 4.4.1 26th September 2023
---------------------------------

Expand Down
14 changes: 12 additions & 2 deletions ArduPlane/altitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,12 @@ void Plane::set_target_altitude_location(const Location &loc)
target_altitude.amsl_cm += home.alt;
}
#if AP_TERRAIN_AVAILABLE
if (target_altitude.terrain_following_pending) {
/* we didn't get terrain data to init when we started on this
target, retry
*/
setup_terrain_target_alt(next_WP_loc);
}
/*
if this location has the terrain_alt flag set and we know the
terrain altitude of our current location then treat it as a
Expand Down Expand Up @@ -448,12 +454,16 @@ bool Plane::above_location_current(const Location &loc)
modify a destination to be setup for terrain following if
TERRAIN_FOLLOW is enabled
*/
void Plane::setup_terrain_target_alt(Location &loc) const
void Plane::setup_terrain_target_alt(Location &loc)
{
#if AP_TERRAIN_AVAILABLE
if (terrain_enabled_in_current_mode()) {
loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN);
if (!loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) {
target_altitude.terrain_following_pending = true;
return;
}
}
target_altitude.terrain_following_pending = false;
#endif
}

Expand Down
6 changes: 5 additions & 1 deletion ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,11 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
// default to non-VTOL loiter
auto_state.vtol_loiter = false;

// log when new commands start
#if AP_TERRAIN_AVAILABLE
plane.target_altitude.terrain_following_pending = false;
#endif

// log when new commands start
if (should_log(MASK_LOG_CMD)) {
logger.Write_Mission_Cmd(mission, cmd);
}
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,10 @@ bool Mode::enter()
quadplane.mode_enter();
#endif

#if AP_TERRAIN_AVAILABLE
plane.target_altitude.terrain_following_pending = false;
#endif

bool enter_result = _enter();

if (enter_result) {
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2821,15 +2821,15 @@ void QuadPlane::vtol_position_controller(void)
if (plane.control_mode == &plane.mode_guided || vtol_loiter_auto) {
plane.ahrs.get_location(plane.current_loc);
int32_t target_altitude_cm;
if (!plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME,target_altitude_cm)) {
if (!plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN,target_altitude_cm)) {
break;
}
if (poscontrol.slow_descent &&
plane.prev_WP_loc.get_distance(plane.next_WP_loc) > 50) {
// gradually descend as we approach target
plane.auto_state.wp_proportion = plane.current_loc.line_path_proportion(plane.prev_WP_loc, plane.next_WP_loc);
int32_t prev_alt;
if (plane.prev_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME,prev_alt)) {
if (plane.prev_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN,prev_alt)) {
target_altitude_cm = linear_interpolate(prev_alt,
target_altitude_cm,
plane.auto_state.wp_proportion,
Expand Down
8 changes: 4 additions & 4 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.4.1"
#define THISFIRMWARE "ArduPlane V4.4.4-beta1"

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

#define FW_MAJOR 4
#define FW_MINOR 4
#define FW_PATCH 1
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_PATCH 4
#define FW_TYPE FIRMWARE_VERSION_TYPE_BETA

#include <AP_Common/AP_FWVersionDefine.h>
3 changes: 1 addition & 2 deletions ArduSub/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK {

using GCS_MAVLINK::GCS_MAVLINK;

uint8_t sysid_my_gcs() const override;
protected:

uint32_t telem_delay() const override {
Expand All @@ -16,8 +17,6 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK {

MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;

uint8_t sysid_my_gcs() const override;

MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
Expand Down
4 changes: 2 additions & 2 deletions Blimp/GCS_Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@ class GCS_Blimp : public GCS

bool vehicle_initialised() const override;

protected:

uint8_t sysid_this_mav() const override;

protected:

// minimum amount of time (in microseconds) that must remain in
// the main scheduler loop before we are allowed to send any
// mavlink messages. We want to prioritise the main flight
Expand Down
Loading

0 comments on commit bae5171

Please sign in to comment.