mirror of https://github.com/ArduPilot/ardupilot
APM_Control: move AC_Avoidance defines into libraries
This commit is contained in:
parent
31eb340928
commit
1e0c56b5b9
|
@ -154,6 +154,7 @@ void AR_PosControl::update(float dt)
|
|||
|
||||
// Limit the velocity to prevent fence violations
|
||||
bool backing_up = false;
|
||||
#if AP_AVOIDANCE_ENABLED
|
||||
AC_Avoid *avoid = AP::ac_avoid();
|
||||
if (avoid != nullptr) {
|
||||
Vector3f vel_3d_cms{_vel_target.x * 100.0f, _vel_target.y * 100.0f, 0.0f};
|
||||
|
@ -162,6 +163,7 @@ void AR_PosControl::update(float dt)
|
|||
_vel_target.x = vel_3d_cms.x * 0.01;
|
||||
_vel_target.y = vel_3d_cms.y * 0.01;
|
||||
}
|
||||
#endif // AP_AVOIDANCE_ENABLED
|
||||
|
||||
// calculate limit vector based on steering limits
|
||||
Vector2f steering_limit_vec;
|
||||
|
|
Loading…
Reference in New Issue