Skip to content

Commit

Permalink
Merge branch 'master' into pr-murata_sch16t_imu
Browse files Browse the repository at this point in the history
  • Loading branch information
dakejahl authored May 13, 2024
2 parents b2e754a + b853fe3 commit 289d6f5
Show file tree
Hide file tree
Showing 313 changed files with 13,068 additions and 3,680 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
35 changes: 35 additions & 0 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,39 @@
Antenna Tracker Release Notes:
------------------------------
Release 4.5.2-beta1 29th April 2024

Changes from 4.5.1

1) Board specific enhancements and bug fixes

- 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.1 8th April 2024
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
27 changes: 16 additions & 11 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,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
7 changes: 6 additions & 1 deletion 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
6 changes: 6 additions & 0 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -836,6 +836,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
return MAV_RESULT_ACCEPTED;

#if MODE_AUTO_ENABLED == ENABLED
case MAV_CMD_DO_RETURN_PATH_START:
if (copter.mode_auto.return_path_start_auto_RTL(ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;

case MAV_CMD_DO_LAND_START:
if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
Expand Down
41 changes: 41 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,46 @@
ArduPilot Copter Release Notes:
-------------------------------
Release 4.5.2-beta1 29th April 2024

Changes from 4.5.1

1) Board specific enhancements and bug fixes

- 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) Copter specific changes

- Auto mode condition yaw fix to avoid pointing at out-of-date target
- Guided mode angle control yaw target initialisation fix (was always turning North)

5) 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.1 8th April 2024

Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -382,6 +382,9 @@
#ifndef LAND_DETECTOR_ACCEL_MAX
# define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s
#endif
#ifndef LAND_DETECTOR_VEL_Z_MAX
# define LAND_DETECTOR_VEL_Z_MAX 1.0f // vehicle vertical velocity must be under 1m/s
#endif

//////////////////////////////////////////////////////////////////////////////
// Flight mode definitions
Expand Down
12 changes: 10 additions & 2 deletions ArduCopter/land_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,11 +100,19 @@ void Copter::update_land_detector()
}
#endif

// check for aggressive flight requests - requested roll or pitch angle below 15 degrees
const Vector3f angle_target = attitude_control->get_att_target_euler_cd();
bool large_angle_request = angle_target.xy().length() > LAND_CHECK_LARGE_ANGLE_CD;

// check for large external disturbance - angle error over 30 degrees
const float angle_error = attitude_control->get_att_error_angle_deg();
bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG);

// check that the airframe is not accelerating (not falling or braking after fast forward flight)
bool accel_stationary = (land_accel_ef_filter.get().length() <= LAND_DETECTOR_ACCEL_MAX * land_detector_scalar);

// check that vertical speed is within 1m/s of zero
bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100 * land_detector_scalar;
bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100.0 * LAND_DETECTOR_VEL_Z_MAX * land_detector_scalar;

// if we have a healthy rangefinder only allow landing detection below 2 meters
bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM);
Expand All @@ -116,7 +124,7 @@ void Copter::update_land_detector()
const bool WoW_check = true;
#endif

if (motor_at_lower_limit && throttle_mix_at_min && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) {
if (motor_at_lower_limit && throttle_mix_at_min && !large_angle_request && !large_angle_error && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) {
// landed criteria met - increment the counter and check if we've triggered
if( land_detector_count < land_trigger_sec*scheduler.get_loop_rate_hz()) {
land_detector_count++;
Expand Down
17 changes: 9 additions & 8 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,8 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#if MODE_AUTO_ENABLED == ENABLED
if (mode == Mode::Number::AUTO_RTL) {
// Special case for AUTO RTL, not a true mode, just AUTO in disguise
return mode_auto.jump_to_landing_sequence_auto_RTL(reason);
// Attempt to join return path, fallback to do-land-start
return mode_auto.return_path_or_jump_to_landing_sequence_auto_RTL(reason);
}
#endif

Expand Down Expand Up @@ -972,19 +973,19 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms)
switch (motors->get_spool_state()) {

case AP_Motors::SpoolState::SHUT_DOWN:
return AltHold_MotorStopped;
return AltHoldModeState::MotorStopped;

case AP_Motors::SpoolState::GROUND_IDLE:
return AltHold_Landed_Ground_Idle;
return AltHoldModeState::Landed_Ground_Idle;

default:
return AltHold_Landed_Pre_Takeoff;
return AltHoldModeState::Landed_Pre_Takeoff;
}

} else if (takeoff.running() || takeoff.triggered(target_climb_rate_cms)) {
// the aircraft is currently landed or taking off, asking for a positive climb rate and in THROTTLE_UNLIMITED
// the aircraft should progress through the take off procedure
return AltHold_Takeoff;
return AltHoldModeState::Takeoff;

} else if (!copter.ap.auto_armed || copter.ap.land_complete) {
// the aircraft is armed and landed
Expand All @@ -999,17 +1000,17 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms)

if (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) {
// the aircraft is waiting in ground idle
return AltHold_Landed_Ground_Idle;
return AltHoldModeState::Landed_Ground_Idle;

} else {
// the aircraft can leave the ground at any time
return AltHold_Landed_Pre_Takeoff;
return AltHoldModeState::Landed_Pre_Takeoff;
}

} else {
// the aircraft is in a flying state
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
return AltHold_Flying;
return AltHoldModeState::Flying;
}
}

Expand Down
21 changes: 15 additions & 6 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -231,12 +231,12 @@ class Mode {
virtual float throttle_hover() const;

// Alt_Hold based flight mode states used in Alt_Hold, Loiter, and Sport
enum AltHoldModeState {
AltHold_MotorStopped,
AltHold_Takeoff,
AltHold_Landed_Ground_Idle,
AltHold_Landed_Pre_Takeoff,
AltHold_Flying
enum class AltHoldModeState {
MotorStopped,
Takeoff,
Landed_Ground_Idle,
Landed_Pre_Takeoff,
Flying
};
AltHoldModeState get_alt_hold_state(float target_climb_rate_cms);

Expand Down Expand Up @@ -553,6 +553,12 @@ class ModeAuto : public Mode {
// Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode
bool jump_to_landing_sequence_auto_RTL(ModeReason reason);

// Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode
bool return_path_start_auto_RTL(ModeReason reason);

// Try join return path else do land start
bool return_path_or_jump_to_landing_sequence_auto_RTL(ModeReason reason);

// lua accessors for nav script time support
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4);
void nav_script_time_done(uint16_t id);
Expand Down Expand Up @@ -589,6 +595,9 @@ class ModeAuto : public Mode {
AllowWeatherVaning = (1 << 7U),
};

// Enter auto rtl pseudo mode
bool enter_auto_rtl(ModeReason reason);

bool start_command(const AP_Mission::Mission_Command& cmd);
bool verify_command(const AP_Mission::Mission_Command& cmd);
void exit_mission();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_acro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ void ModeAcro::get_pilot_desired_angle_rates(float roll_in, float pitch_in, floa
}

// convert earth-frame level rates to body-frame level rates
attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd() * radians(0.01f), rate_ef_level_cd, rate_bf_level_cd);
attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level_cd, rate_bf_level_cd);

// combine earth frame rate corrections with rate requests
if (g.acro_trainer == (uint8_t)Trainer::LIMITED) {
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_acro_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void ModeAcro_Heli::virtual_flybar( float &roll_out, float &pitch_out, float &ya
rate_ef_level.z = 0;

// convert earth-frame leak rates to body-frame leak rates
attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level);
attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level);

// combine earth frame rate corrections with rate requests
roll_out += rate_bf_level.x;
Expand Down
Loading

0 comments on commit 289d6f5

Please sign in to comment.