diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index efb2b87087..71c1a17374 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -27,7 +27,7 @@ # define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE #endif -#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) +#if APM_BUILD_COPTER_OR_HELI() # define AP_AVOID_ENABLE_Z 1 #endif diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.cpp b/libraries/AC_Avoidance/AP_OABendyRuler.cpp index e1aaba7e4f..434add3af4 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.cpp +++ b/libraries/AC_Avoidance/AP_OABendyRuler.cpp @@ -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_TYPE(APM_BUILD_ArduCopter) +#define VERTICAL_ENABLED APM_BUILD_COPTER_OR_HELI() const AP_Param::GroupInfo AP_OABendyRuler::var_info[] = { diff --git a/libraries/AC_Avoidance/AP_OADatabase.cpp b/libraries/AC_Avoidance/AP_OADatabase.cpp index bff97bf0bc..39d0171fe3 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.cpp +++ b/libraries/AC_Avoidance/AP_OADatabase.cpp @@ -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_TYPE(APM_BUILD_ArduCopter) + #if APM_BUILD_COPTER_OR_HELI() if (!is_zero(_min_alt)) { Vector2f current_pos; if (!AP::ahrs().get_relative_position_NE_home(current_pos)) { diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index 7f167b0241..9c6f008c8f 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -19,7 +19,7 @@ extern const AP_HAL::HAL& hal; #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100 #define AP_AVOIDANCE_RECOVERY_DEFAULT RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT -#else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat +#else // APM_BUILD_TYPE(APM_BUILD_ArduCopter),Heli, Rover, Boat #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30 #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30 #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 300