AC_Avoidance: convert APM_BUILD_COPTER_OR_HELI() to APM_BUILD_COPTER_OR_HELI

This commit is contained in:
Andy Piper 2021-10-25 18:05:06 +01:00 committed by Andrew Tridgell
parent f5805058c2
commit f9b6934d7d
3 changed files with 4 additions and 4 deletions

View File

@ -27,7 +27,7 @@
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE
#endif
#if APM_BUILD_COPTER_OR_HELI()
#if APM_BUILD_COPTER_OR_HELI
# define AP_AVOID_ENABLE_Z 1
#endif

View File

@ -32,7 +32,7 @@ const float OA_BENDYRULER_LOOKAHEAD_STEP2_MIN = 2.0f; // step2 checks at least
const float OA_BENDYRULER_LOOKAHEAD_PAST_DEST = 2.0f; // lookahead length will be at least this many meters past the destination
const float OA_BENDYRULER_LOW_SPEED_SQUARED = (0.2f * 0.2f); // when ground course is below this speed squared, vehicle's heading will be used
#define VERTICAL_ENABLED APM_BUILD_COPTER_OR_HELI()
#define VERTICAL_ENABLED APM_BUILD_COPTER_OR_HELI
const AP_Param::GroupInfo AP_OABendyRuler::var_info[] = {

View File

@ -149,7 +149,7 @@ void AP_OADatabase::queue_push(const Vector3f &pos, uint32_t timestamp_ms, float
}
// check if this obstacle needs to be rejected from DB because of low altitude near home
#if APM_BUILD_COPTER_OR_HELI()
#if APM_BUILD_COPTER_OR_HELI
if (!is_zero(_min_alt)) {
Vector2f current_pos;
if (!AP::ahrs().get_relative_position_NE_home(current_pos)) {
@ -166,7 +166,7 @@ void AP_OADatabase::queue_push(const Vector3f &pos, uint32_t timestamp_ms, float
}
}
}
#endif
#endif
// ignore objects that are far away
if ((_dist_max > 0.0f) && (distance > _dist_max)) {