Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into new-ChibiOS-Board-podmanH7
Browse files Browse the repository at this point in the history
  • Loading branch information
burgeruser authored Jun 23, 2024
2 parents eb4d70d + 9fdf52c commit 553a149
Show file tree
Hide file tree
Showing 590 changed files with 6,738 additions and 3,698 deletions.
1 change: 1 addition & 0 deletions .github/workflows/test_chibios.yml
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,7 @@ jobs:
CubeOrange-PPP,
SOHW,
Pixhawk6X-PPPGW,
new-check,
]
toolchain: [
chibios,
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/GCS_Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class GCS_Tracker : public GCS

GCS_MAVLINK_Tracker *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override {
return new GCS_MAVLINK_Tracker(params, uart);
return NEW_NOTHROW GCS_MAVLINK_Tracker(params, uart);
}

private:
Expand Down
7 changes: 7 additions & 0 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,12 @@
Antenna Tracker Release Notes:
------------------------------
Release 4.5.4 12th June 2024

Changes from 4.5.3

Disable highres IMU sampling on ICM42670 fixing an issue on some versions of Pixhawk6X

------------------------------------------------------------------
Release 4.5.3 28th May 2024

No changes from 4.5.3-beta1
Expand Down
18 changes: 8 additions & 10 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -450,17 +450,15 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
check_failed(display_failure, "Need Position Estimate");
return false;
}
} else {
if (fence_requires_gps) {
if (!copter.position_ok()) {
// clarify to user why they need GPS in non-GPS flight mode
check_failed(display_failure, "Fence enabled, need position estimate");
return false;
}
} else {
// return true if GPS is not required
return true;
} else if (fence_requires_gps) {
if (!copter.position_ok()) {
// clarify to user why they need GPS in non-GPS flight mode
check_failed(display_failure, "Fence enabled, need position estimate");
return false;
}
} else {
// return true if GPS is not required
return true;
}

// check for GPS glitch (as reported by EKF)
Expand Down
6 changes: 5 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -622,11 +622,15 @@ class Copter : public AP_Vehicle {
};


enum class FlightOptions {
enum class FlightOption : uint32_t {
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
};
// returns true if option is enabled for this vehicle
bool option_is_enabled(FlightOption option) const {
return (g2.flight_options & uint32_t(option)) != 0;
}

static constexpr int8_t _failsafe_priorities[] = {
(int8_t)FailsafeAction::TERMINATE,
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class GCS_Copter : public GCS

GCS_MAVLINK_Copter *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override {
return new GCS_MAVLINK_Copter(params, uart);
return NEW_NOTHROW GCS_MAVLINK_Copter(params, uart);
}

};
4 changes: 4 additions & 0 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,10 @@ MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const
return MAV_STATE_STANDBY;
}

if (!copter.ap.initialised) {
return MAV_STATE_BOOT;
}

return MAV_STATE_ACTIVE;
}

Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
switch(ch_flag) {
case AuxSwitchPos::HIGH: {
// engage mode (if not possible we remain in current flight mode)
copter.set_mode(mode, ModeReason::RC_COMMAND);
copter.set_mode(mode, ModeReason::AUX_FUNCTION);
break;
}
default:
Expand All @@ -163,7 +163,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
case AUX_FUNC::FLIP:
// flip if switch is on, positive throttle and we're actually flying
if (ch_flag == AuxSwitchPos::HIGH) {
copter.set_mode(Mode::Number::FLIP, ModeReason::RC_COMMAND);
copter.set_mode(Mode::Number::FLIP, ModeReason::AUX_FUNCTION);
}
break;

Expand Down
7 changes: 7 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,12 @@
ArduPilot Copter Release Notes:
-------------------------------
Release 4.5.4 12th June 2024

Changes from 4.5.3

Disable highres IMU sampling on ICM42670 fixing an issue on some versions of Pixhawk6X

------------------------------------------------------------------
Release 4.5.3 28th May 2024

No changes from 4.5.3-beta1
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di

// calculate final angle as relative to vehicle heading or absolute
if (relative_angle) {
if (_mode == Mode::HOLD) {
_yaw_angle_cd = copter.ahrs.yaw_sensor;
}
_fixed_yaw_offset_cd = angle_deg * 100.0 * (direction >= 0 ? 1.0 : -1.0);
} else {
// absolute angle
Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -600,10 +600,6 @@
#error Toy mode is not available on Helicopters
#endif

#ifndef OSD_ENABLED
#define OSD_ENABLED DISABLED
#endif

#ifndef HAL_FRAME_TYPE_DEFAULT
#define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X
#endif
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ void Copter::thrust_loss_check()
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed

// no-op if suppressed by flight options param
if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_THRUST_LOSS_CHECK)) != 0) {
if (copter.option_is_enabled(FlightOption::DISABLE_THRUST_LOSS_CHECK)) {
return;
}

Expand Down Expand Up @@ -171,7 +171,7 @@ void Copter::thrust_loss_check()
// the motors library disables this when it is no longer needed to achieve the commanded output

#if AP_GRIPPER_ENABLED
if ((copter.g2.flight_options & uint32_t(FlightOptions::RELEASE_GRIPPER_ON_THRUST_LOSS)) != 0) {
if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) {
gripper.release();
}
#endif
Expand All @@ -182,7 +182,7 @@ void Copter::thrust_loss_check()
void Copter::yaw_imbalance_check()
{
// no-op if suppressed by flight options param
if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_YAW_IMBALANCE_WARNING)) != 0) {
if (copter.option_is_enabled(FlightOption::DISABLE_YAW_IMBALANCE_WARNING)) {
return;
}

Expand Down
31 changes: 18 additions & 13 deletions ArduCopter/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -379,41 +379,46 @@ void Copter::failsafe_deadreckon_check()
// this is always called from a failsafe so we trigger notification to pilot
void Copter::set_mode_RTL_or_land_with_pause(ModeReason reason)
{
#if MODE_RTL_ENABLED
// attempt to switch to RTL, if this fails then switch to Land
if (!set_mode(Mode::Number::RTL, reason)) {
// set mode to land will trigger mode change notification to pilot
set_mode_land_with_pause(reason);
} else {
// alert pilot to mode change
if (set_mode(Mode::Number::RTL, reason)) {
AP_Notify::events.failsafe_mode_change = 1;
return;
}
#endif
// set mode to land will trigger mode change notification to pilot
set_mode_land_with_pause(reason);
}

// set_mode_SmartRTL_or_land_with_pause - sets mode to SMART_RTL if possible or LAND with 4 second delay before descent starts
// this is always called from a failsafe so we trigger notification to pilot
void Copter::set_mode_SmartRTL_or_land_with_pause(ModeReason reason)
{
#if MODE_SMARTRTL_ENABLED
// attempt to switch to SMART_RTL, if this failed then switch to Land
if (!set_mode(Mode::Number::SMART_RTL, reason)) {
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");
set_mode_land_with_pause(reason);
} else {
if (set_mode(Mode::Number::SMART_RTL, reason)) {
AP_Notify::events.failsafe_mode_change = 1;
return;
}
#endif
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");
set_mode_land_with_pause(reason);
}

// set_mode_SmartRTL_or_RTL - sets mode to SMART_RTL if possible or RTL if possible or LAND with 4 second delay before descent starts
// this is always called from a failsafe so we trigger notification to pilot
void Copter::set_mode_SmartRTL_or_RTL(ModeReason reason)
{
#if MODE_SMARTRTL_ENABLED
// attempt to switch to SmartRTL, if this failed then attempt to RTL
// if that fails, then land
if (!set_mode(Mode::Number::SMART_RTL, reason)) {
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");
set_mode_RTL_or_land_with_pause(reason);
} else {
if (set_mode(Mode::Number::SMART_RTL, reason)) {
AP_Notify::events.failsafe_mode_change = 1;
return;
}
#endif
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");
set_mode_RTL_or_land_with_pause(reason);
}

// Sets mode to Auto and jumps to DO_LAND_START, as set with AUTO_RTL param
Expand Down
5 changes: 2 additions & 3 deletions ArduCopter/mode_circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,17 +22,16 @@ bool ModeCircle::init(bool ignore_checks)
copter.circle_nav->init();

#if HAL_MOUNT_ENABLED
AP_Mount *s = AP_Mount::get_singleton();

// Check if the CIRCLE_OPTIONS parameter have roi_at_center
if (copter.circle_nav->roi_at_center()) {
const Vector3p &pos { copter.circle_nav->get_center() };
Location circle_center;
if (!AP::ahrs().get_location_from_origin_offset(circle_center, pos * 0.01)) {
if (!AP::ahrs().get_location_from_origin_offset_NED(circle_center, pos * 0.01)) {
return false;
}
// point at the ground:
circle_center.set_alt_cm(0, Location::AltFrame::ABOVE_TERRAIN);
AP_Mount *s = AP_Mount::get_singleton();
s->set_roi_target(circle_center);
}
#endif
Expand Down
23 changes: 13 additions & 10 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,10 +243,10 @@ void ModeGuided::pos_control_start()
pva_control_start();
}

// initialise guided mode's velocity controller
// initialise guided mode's acceleration controller
void ModeGuided::accel_control_start()
{
// set guided_mode to velocity controller
// set guided_mode to acceleration controller
guided_mode = SubMode::Accel;

// initialise position controller
Expand All @@ -256,7 +256,7 @@ void ModeGuided::accel_control_start()
// initialise guided mode's velocity and acceleration controller
void ModeGuided::velaccel_control_start()
{
// set guided_mode to velocity controller
// set guided_mode to velocity and acceleration controller
guided_mode = SubMode::VelAccel;

// initialise position controller
Expand All @@ -266,7 +266,7 @@ void ModeGuided::velaccel_control_start()
// initialise guided mode's position, velocity and acceleration controller
void ModeGuided::posvelaccel_control_start()
{
// set guided_mode to velocity controller
// set guided_mode to position, velocity and acceleration controller
guided_mode = SubMode::PosVelAccel;

// initialise position controller
Expand Down Expand Up @@ -414,11 +414,14 @@ bool ModeGuided::get_wp(Location& destination) const
case SubMode::Pos:
destination = Location(guided_pos_target_cm.tofloat(), guided_pos_terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
return true;
default:
return false;
case SubMode::Angle:
case SubMode::TakeOff:
case SubMode::Accel:
case SubMode::VelAccel:
case SubMode::PosVelAccel:
break;
}

// should never get here but just in case
return false;
}

Expand Down Expand Up @@ -515,7 +518,7 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y
// set_velaccel - sets guided mode's target velocity and acceleration
void ModeGuided::set_accel(const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request)
{
// check we are in velocity control mode
// check we are in acceleration control mode
if (guided_mode != SubMode::Accel) {
accel_control_start();
}
Expand Down Expand Up @@ -547,7 +550,7 @@ void ModeGuided::set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_
// set_velaccel - sets guided mode's target velocity and acceleration
void ModeGuided::set_velaccel(const Vector3f& velocity, const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request)
{
// check we are in velocity control mode
// check we are in velocity and acceleration control mode
if (guided_mode != SubMode::VelAccel) {
velaccel_control_start();
}
Expand Down Expand Up @@ -589,7 +592,7 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const
}
#endif

// check we are in velocity control mode
// check we are in position, velocity and acceleration control mode
if (guided_mode != SubMode::PosVelAccel) {
posvelaccel_control_start();
}
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ void Copter::arm_motors_check()
// check if arming/disarm using rudder is allowed
AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
arming_counter = 0;
return;
}

Expand Down
Loading

0 comments on commit 553a149

Please sign in to comment.