AC_Avoid: Simplify accessing boundary

This commit is contained in:
Rishabh 2020-12-27 22:02:34 +05:30 committed by Randy Mackay
parent d359c5ddf2
commit 5092bc2f6d
2 changed files with 5 additions and 3 deletions

View File

@ -1072,7 +1072,10 @@ void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &d
for (uint8_t i = 0; i<obstacle_num; i++) {
// get obstacle from proximity library
Vector3f vector_to_obstacle;
_proximity.get_obstacle(i, vector_to_obstacle);
if (!_proximity.get_obstacle(i, vector_to_obstacle)) {
// this one is not valid
continue;
}
const float dist_to_boundary = vector_to_obstacle.length();
if (is_zero(dist_to_boundary)) {
continue;

View File

@ -22,8 +22,7 @@
#define AC_AVOID_MIN_BACKUP_BREACH_DIST 10.0f // vehicle will backaway if breach is greater than this distance in cm
/*
* This class prevents the vehicle from leaving a polygon fence in
* 2 dimensions by limiting velocity (adjust_velocity).
* This class prevents the vehicle from leaving a polygon fence or avoiding proximity based obstacles
* Additionally the vehicle may back up if the margin to obstacle is breached
*/
class AC_Avoid {