Skip to content

Commit

Permalink
Merge branch 'master' into add-response-validation
Browse files Browse the repository at this point in the history
  • Loading branch information
lashVN authored Jul 5, 2024
2 parents ec3c27a + 9090420 commit 0317a44
Show file tree
Hide file tree
Showing 426 changed files with 13,882 additions and 9,427 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
42 changes: 42 additions & 0 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,47 @@
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

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
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
24 changes: 13 additions & 11 deletions 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,23 +448,21 @@ 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");
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
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
16 changes: 13 additions & 3 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 @@ -622,11 +624,16 @@ 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
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};
// 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 Expand Up @@ -666,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 @@ -821,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
30 changes: 18 additions & 12 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 Expand Up @@ -1213,6 +1217,7 @@ void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_messag

// ensure thrust field is not ignored
if (throttle_ignore) {
// The throttle input is not defined
return;
}

Expand All @@ -1231,6 +1236,18 @@ void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_messag
}
}

Vector3f ang_vel_body;
if (!roll_rate_ignore && !pitch_rate_ignore && !yaw_rate_ignore) {
ang_vel_body.x = packet.body_roll_rate;
ang_vel_body.y = packet.body_pitch_rate;
ang_vel_body.z = packet.body_yaw_rate;
} else if (!(roll_rate_ignore && pitch_rate_ignore && yaw_rate_ignore)) {
// The body rates are ill-defined
// input is not valid so stop
copter.mode_guided.init(true);
return;
}

// check if the message's thrust field should be interpreted as a climb rate or as thrust
const bool use_thrust = copter.mode_guided.set_attitude_target_provides_thrust();

Expand All @@ -1252,18 +1269,7 @@ void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_messag
}
}

Vector3f ang_vel;
if (!roll_rate_ignore) {
ang_vel.x = packet.body_roll_rate;
}
if (!pitch_rate_ignore) {
ang_vel.y = packet.body_pitch_rate;
}
if (!yaw_rate_ignore) {
ang_vel.z = packet.body_yaw_rate;
}

copter.mode_guided.set_angle(attitude_quat, ang_vel,
copter.mode_guided.set_angle(attitude_quat, ang_vel_body,
climb_rate_or_thrust, use_thrust);
}

Expand Down
10 changes: 9 additions & 1 deletion ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,15 @@ void Copter::Log_Write_Control_Tuning()
target_climb_rate_cms = pos_control->get_vel_target_z_cms();
}

// get surface tracking alts
float desired_rangefinder_alt;
#if AP_RANGEFINDER_ENABLED
if (!surface_tracking.get_target_dist_for_logging(desired_rangefinder_alt)) {
desired_rangefinder_alt = AP::logger().quiet_nan();
}
#else
// get surface tracking alts
desired_rangefinder_alt = AP::logger().quiet_nan();
#endif

struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
Expand All @@ -56,7 +60,11 @@ void Copter::Log_Write_Control_Tuning()
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
baro_alt : baro_alt,
desired_rangefinder_alt : desired_rangefinder_alt,
#if AP_RANGEFINDER_ENABLED
rangefinder_alt : surface_tracking.get_dist_for_logging(),
#else
rangefinder_alt : AP::logger().quiet_nanf(),
#endif
terr_alt : terr_alt,
target_climb_rate : target_climb_rate_cms,
climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()) // float -> int16_t
Expand Down
8 changes: 5 additions & 3 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -638,7 +638,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
GOBJECT(rssi, "RSSI_", AP_RSSI),

#if RANGEFINDER_ENABLED == ENABLED
#if AP_RANGEFINDER_ENABLED
// @Group: RNGFND
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
GOBJECT(rangefinder, "RNGFND", RangeFinder),
Expand Down Expand Up @@ -1000,11 +1000,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
// @Description: Flight mode specific options
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),

#if RANGEFINDER_ENABLED == ENABLED
#if AP_RANGEFINDER_ENABLED
// @Param: RNGFND_FILT
// @DisplayName: Rangefinder filter
// @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering
Expand All @@ -1028,13 +1028,15 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {

// ACRO_PR_RATE (47), ACRO_Y_RATE (48), PILOT_Y_RATE (49) and PILOT_Y_EXPO (50) moved to command model class

#if AP_RANGEFINDER_ENABLED
// @Param: SURFTRAK_MODE
// @DisplayName: Surface Tracking Mode
// @Description: set which surface to track in surface tracking
// @Values: 0:Do not track, 1:Ground, 2:Ceiling
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND),
#endif

// @Param: FS_DR_ENABLE
// @DisplayName: DeadReckon Failsafe Action
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -652,7 +652,7 @@ class ParametersG2 {

AP_Int32 flight_options;

#if RANGEFINDER_ENABLED == ENABLED
#if AP_RANGEFINDER_ENABLED
AP_Float rangefinder_filt;
#endif

Expand Down
Loading

0 comments on commit 0317a44

Please sign in to comment.