ArduCopter: move AC_Avoidance defines into libraries

This commit is contained in:
Peter Barker 2024-03-09 13:35:26 +11:00 committed by Peter Barker
parent 4781938694
commit cb76ce534b
14 changed files with 23 additions and 33 deletions

View File

@ -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

View File

@ -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;
@ -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

View File

@ -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
@ -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
@ -513,7 +513,7 @@ private:
AP_Mount camera_mount;
#endif
#if AC_AVOID_ENABLED == ENABLED
#if AP_AVOIDANCE_ENABLED
AC_Avoid avoid;
#endif

View File

@ -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);

View File

@ -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
@ -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),

View File

@ -595,7 +595,7 @@ public:
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

View File

@ -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

View File

@ -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>
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
@ -557,16 +557,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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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();

View File

@ -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
@ -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);