AC_Avoidance: Add APM_BUILD_Heli

This commit is contained in:
Gone4Dirt 2021-09-28 09:50:57 +01:00 committed by Peter Barker
parent 7fab70b8f1
commit 765f6b69fa
4 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_TYPE(APM_BUILD_ArduCopter)
#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_TYPE(APM_BUILD_ArduCopter)
#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_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)) {

View File

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