Skip to content

Commit

Permalink
Merge branch 'master' into add_set_cmp_sys_id
Browse files Browse the repository at this point in the history
  • Loading branch information
patrickelectric committed Mar 18, 2024
2 parents 9fc9260 + 7ea2928 commit 13342a0
Show file tree
Hide file tree
Showing 213 changed files with 5,230 additions and 1,654 deletions.
2 changes: 2 additions & 0 deletions .github/workflows/test_environment.yml
Expand Up @@ -38,6 +38,8 @@ jobs:
name: mantic
- os: archlinux
name: latest
- os: debian
name: bookworm
- os: debian
name: bullseye
- os: debian
Expand Down
51 changes: 51 additions & 0 deletions AntennaTracker/ReleaseNotes.txt
@@ -1,5 +1,56 @@
Antenna Tracker Release Notes:
------------------------------------------------------------------
AntennaTracker 4.5.0 beta3 14-Mar-2024
Changes from 4.5.0 beta1

Board specific changes
- added PixFlamingo F7 board
- support ICM42688 on BlitzF745AIO
- fixed IMU orientation of CubeRedSecondary
- enable all FPV features on SpeedyBeeF405WING

System level changes

- improved robustness of CRSF parser
- reduced memory used by DDS/ROS2
- added filesystem crc32 binding in lua scripting
- support visual odometry quality metric and added autoswitching lua script
- allow for expansion of fence storage to microSD for larger pologon fences
- allow FTP upload of fence and rally points
- fixed vehicle type of ship simulation for ship landing
- make severity level depend on generator error level in IE 2400 generator
- speed up initial GPS probe by using SERIALn_BAUD first
- allow NanoRadar radar and proximity sensor to share the CAN bus
- added MR72 CAN proximity sensor
- only produce *_with_bl.hex not *.hex in builds if bootloader available
- fixed check for GPS antenna separation in moving baseline yaw
- added GPS_DRV_OPTIONS options for fully parsing RTCMv3 stream
- fixed logging of RTCM fragments in GPS driver
- fixed video recording while armed
- robostness and logging improvements for ExternalAHRS
- fixed RPM from bdshot on boards with IOMCU
- fixed accel cal simple to remove unused IMUs
- fixed float rounding issue in HAL_Linux millis and micros functions
- fixed loading of defaults.parm parameters for dynamic parameter subtrees
- fixed discrimination between GHST and CRSF protocols
- fixed bug in DroneCAN packet parsing for corrupt packets that could cause a crash
- fixed handling of network sockets in scripting when used after close
- fixed bit timing of CANFD buses

New Autopilots supported
- YJUAV_A6Ultra
- AnyLeaf H7

- do relay parameter conversion for parachute parameters if ever has been used
- broaden acceptance criteria for GPS yaw measurement for moving baseline yaw

------------------------------------------------------------------
AntennaTracker 4.5.0 beta1 22-Feb-2024
Changes from 4.2.0
1) Innumerable system-level improvements; see Copter and Plane release notes
2) fix EKF2/EKF3 parameters
3) improve logging
------------------------------------------------------------------
AntennaTracker 4.2.0 beta1 25-May-2022
Changes from 1.1.0
1) Many new supported boards
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/APM_Config.h
Expand Up @@ -5,8 +5,6 @@
//#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 AC_AVOID_ENABLED DISABLED // disable stop-at-fence library
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
//#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
4 changes: 2 additions & 2 deletions ArduCopter/AP_Arming.cpp
Expand Up @@ -299,7 +299,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)

bool AP_Arming_Copter::oa_checks(bool display_failure)
{
#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
char failure_msg[50] = {};
if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {
return true;
Expand Down Expand Up @@ -407,7 +407,7 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
}

// get closest object if we might use it for avoidance
#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
float angle_deg, distance;
if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {
// display error if something is within 60cm
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/Copter.h
Expand Up @@ -103,10 +103,10 @@
#include <AP_Beacon/AP_Beacon.h>
#endif

#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
#include <AC_Avoidance/AC_Avoid.h>
#endif
#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
#include <AC_WPNav/AC_WPNav_OA.h>
#include <AC_Avoidance/AP_OAPathPlanner.h>
#endif
Expand Down Expand Up @@ -155,11 +155,11 @@
#include <AC_CustomControl/AC_CustomControl.h> // Custom control library
#endif

#if AC_AVOID_ENABLED && !AP_FENCE_ENABLED
#if AP_AVOIDANCE_ENABLED && !AP_FENCE_ENABLED
#error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled
#endif

#if AC_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED
#if AP_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED
#error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled
#endif

Expand Down Expand Up @@ -513,7 +513,7 @@ class Copter : public AP_Vehicle {
AP_Mount camera_mount;
#endif

#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
AC_Avoid avoid;
#endif

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Mavlink.cpp
Expand Up @@ -369,7 +369,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
copter.adsb.send_adsb_vehicle(chan);
#endif
#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
AP_OADatabase *oadb = AP_OADatabase::get_singleton();
if (oadb != nullptr) {
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/Parameters.cpp
Expand Up @@ -102,7 +102,7 @@ const AP_Param::Info Copter::var_info[] = {
// @DisplayName: RTL Altitude
// @Description: The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.
// @Units: cm
// @Range: 200 300000
// @Range: 30 300000
// @Increment: 1
// @User: Standard
GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),
Expand Down Expand Up @@ -595,7 +595,7 @@ const AP_Param::Info Copter::var_info[] = {

// @Group: AVOID_
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
GOBJECT(avoid, "AVOID_", AC_Avoid),
#endif

Expand Down Expand Up @@ -917,7 +917,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard
AP_GROUPINFO("TUNE_MAX", 32, ParametersG2, tuning_max, 0),

#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
// @Group: OA_
// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp
AP_SUBGROUPINFO(oa, "OA_", 33, ParametersG2, AP_OAPathPlanner),
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Expand Up @@ -595,7 +595,7 @@ class ParametersG2 {
AP_Float tuning_min;
AP_Float tuning_max;

#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
// object avoidance path planning
AP_OAPathPlanner oa;
#endif
Expand Down
39 changes: 39 additions & 0 deletions ArduCopter/ReleaseNotes.txt
@@ -1,6 +1,45 @@
ArduPilot Copter Release Notes:
-------------------------------

Release 4.5.0-beta3 14-March-2024

Changes from 4.5.0-beta2

1) Board specific changes
- added PixFlamingo F7 board
- support ICM42688 on BlitzF745AIO
- fixed IMU orientation of CubeRedSecondary
- enable all FPV features on SpeedyBeeF405WING

2) System level changes

- improved robustness of CRSF parser
- reduced memory used by DDS/ROS2
- added filesystem crc32 binding in lua scripting
- support visual odometry quality metric and added autoswitching lua script
- allow for expansion of fence storage to microSD for larger pologon fences
- allow FTP upload of fence and rally points
- fixed vehicle type of ship simulation for ship landing
- make severity level depend on generator error level in IE 2400 generator
- speed up initial GPS probe by using SERIALn_BAUD first
- allow NanoRadar radar and proximity sensor to share the CAN bus
- added MR72 CAN proximity sensor
- only produce *_with_bl.hex not *.hex in builds if bootloader available
- fixed check for GPS antenna separation in moving baseline yaw
- added GPS_DRV_OPTIONS options for fully parsing RTCMv3 stream
- fixed logging of RTCM fragments in GPS driver
- fixed video recording while armed
- robostness and logging improvements for ExternalAHRS
- fixed RPM from bdshot on boards with IOMCU
- fixed accel cal simple to remove unused IMUs

3) Copter specific changes
- check fence breaches more often on copter for smaller overrun
- improved copter follow mode at close distances
- fixed default for FLTD for yaw
- fixed reset_target_and_rate method in attitude control

------------------------------------------------------------------
Copter 4.5.0-beta2 14-February-2024

Changes from 4.5.0-beta1:
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/avoidance.cpp
Expand Up @@ -3,7 +3,7 @@
// check if proximity type Simple Avoidance should be enabled based on alt
void Copter::low_alt_avoidance()
{
#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
int32_t alt_cm;
if (!get_rangefinder_height_interpolated_cm(alt_cm)) {
// enable avoidance if we don't have a valid rangefinder reading
Expand Down
22 changes: 9 additions & 13 deletions ArduCopter/config.h
Expand Up @@ -29,7 +29,7 @@
#include "APM_Config.h"
#include <AP_ADSB/AP_ADSB_config.h>
#include <AP_Follow/AP_Follow_config.h>

#include <AC_Avoidance/AC_Avoidance_config.h>

//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -195,7 +195,11 @@
//////////////////////////////////////////////////////////////////////////////
// Follow - follow another vehicle or GCS
#ifndef MODE_FOLLOW_ENABLED
# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED
#if AP_FOLLOW_ENABLED && AP_AVOIDANCE_ENABLED
#define MODE_FOLLOW_ENABLED ENABLED
#else
#define MODE_FOLLOW_ENABLED DISABLED
#endif
#endif

//////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -430,7 +434,7 @@
#endif

#ifndef RTL_ALT_MIN
# define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m)
# define RTL_ALT_MIN 30 // min height above ground for RTL (i.e 30cm)
#endif

#ifndef RTL_CLIMB_MIN_DEFAULT
Expand Down Expand Up @@ -557,16 +561,8 @@
// Fence, Rally and Terrain and AC_Avoidance defaults
//

#ifndef AC_AVOID_ENABLED
#define AC_AVOID_ENABLED ENABLED
#endif

#ifndef AC_OAPATHPLANNER_ENABLED
#define AC_OAPATHPLANNER_ENABLED ENABLED
#endif

#if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED
#error Follow Mode relies on AC_AVOID which is disabled
#if MODE_FOLLOW_ENABLED && !AP_AVOIDANCE_ENABLED
#error Follow Mode relies on AP_AVOIDANCE_ENABLED which is disabled
#endif

#if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode.cpp
Expand Up @@ -947,7 +947,7 @@ float Mode::get_pilot_desired_throttle() const

float Mode::get_avoidance_adjusted_climbrate(float target_rate)
{
#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
AP::ac_avoid()->adjust_velocity_z(pos_control->get_pos_z_p().kP(), pos_control->get_max_accel_z_cmss(), target_rate, G_Dt);
return target_rate;
#else
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode.h
Expand Up @@ -1774,7 +1774,7 @@ class ModeAvoidADSB : public ModeGuided {

};

#if AP_FOLLOW_ENABLED
#if MODE_FOLLOW_ENABLED == ENABLED
class ModeFollow : public ModeGuided {

public:
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/mode_althold.cpp
Expand Up @@ -79,7 +79,7 @@ void ModeAltHold::run()
case AltHold_Flying:
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);

#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
// apply avoidance
copter.avoid.adjust_roll_pitch(target_roll, target_pitch, copter.aparm.angle_max);
#endif
Expand All @@ -100,4 +100,4 @@ void ModeAltHold::run()

// run the vertical position controller and set output throttle
pos_control->update_z_controller();
}
}
2 changes: 1 addition & 1 deletion ArduCopter/mode_flowhold.cpp
Expand Up @@ -332,7 +332,7 @@ void ModeFlowHold::run()
bf_angles.x = constrain_float(bf_angles.x, -angle_max, angle_max);
bf_angles.y = constrain_float(bf_angles.y, -angle_max, angle_max);

#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
// apply avoidance
copter.avoid.adjust_roll_pitch(bf_angles.x, bf_angles.y, copter.aparm.angle_max);
#endif
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_follow.cpp
Expand Up @@ -10,7 +10,7 @@
* TODO: "channel 7 option" to lock onto "pointed at" target
* TODO: do better in terms of loitering around the moving point; may need a PID? Maybe use loiter controller somehow?
* TODO: extrapolate target vehicle position using its velocity and acceleration
* TODO: ensure AC_AVOID_ENABLED is true because we rely on it velocity limiting functions
* TODO: ensure AP_AVOIDANCE_ENABLED is true because we rely on it velocity limiting functions
*/

// initialise follow mode
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_guided.cpp
Expand Up @@ -800,7 +800,7 @@ void ModeGuided::velaccel_control_run()
}

bool do_avoid = false;
#if AC_AVOID_ENABLED
#if AP_AVOIDANCE_ENABLED
// limit the velocity for obstacle/fence avoidance
copter.avoid.adjust_velocity(guided_vel_target_cms, pos_control->get_pos_xy_p().kP(), pos_control->get_max_accel_xy_cmss(), pos_control->get_pos_z_p().kP(), pos_control->get_max_accel_z_cmss(), G_Dt);
do_avoid = copter.avoid.limits_active();
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/system.cpp
Expand Up @@ -93,7 +93,7 @@ void Copter::init_ardupilot()
airspeed.set_log_bit(MASK_LOG_IMU);
#endif

#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
g2.oa.init();
#endif

Expand Down Expand Up @@ -449,7 +449,7 @@ void Copter::allocate_motors(void)
}
AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info);

#if AC_OAPATHPLANNER_ENABLED == ENABLED
#if AP_OAPATHPLANNER_ENABLED
wp_nav = new AC_WPNav_OA(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
#else
wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
Expand Down
7 changes: 3 additions & 4 deletions ArduPlane/ArduPlane.cpp
Expand Up @@ -869,8 +869,8 @@ bool Plane::update_target_location(const Location &old_loc, const Location &new_
next_WP_loc = new_loc;

#if HAL_QUADPLANE_ENABLED
if (control_mode == &mode_qland) {
mode_qland.last_target_loc_set_ms = AP_HAL::millis();
if (control_mode == &mode_qland || control_mode == &mode_qloiter) {
mode_qloiter.last_target_loc_set_ms = AP_HAL::millis();
}
#endif

Expand Down Expand Up @@ -966,8 +966,7 @@ bool Plane::flight_option_enabled(FlightOptions flight_option) const
void Plane::precland_update(void)
{
// alt will be unused if we pass false through as the second parameter:
return g2.precland.update(rangefinder_state.height_estimate*100,
rangefinder_state.in_range && rangefinder_state.in_use);
return g2.precland.update(rangefinder_state.height_estimate*100, rangefinder_state.in_range);
}
#endif

Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/GCS_Mavlink.cpp
Expand Up @@ -1387,9 +1387,11 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
break; //default to MSL altitude
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
cmd.content.location.relative_alt = true;
break;
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
cmd.content.location.relative_alt = true;
cmd.content.location.terrain_alt = true;
Expand Down

0 comments on commit 13342a0

Please sign in to comment.