AC_Avoidance: Fix some typos

Fixed some typos found in the code.
This commit is contained in:
Mykhailo Kuznietsov 2023-10-11 18:41:49 +11:00 committed by Peter Barker
parent ad0b0a1c05
commit 6c426ab637
6 changed files with 9 additions and 9 deletions

View File

@ -143,7 +143,7 @@ void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desir
adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);
find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
// backup_vel_fence is set to zero after each fence incase the velocity is unset from previous methods
// backup_vel_fence is set to zero after each fence in case the velocity is unset from previous methods
backup_vel_fence.zero();
adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);
find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
@ -229,7 +229,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa
}
// let user take control if they are backing away at a greater speed than what we have calculated
// this has to be done for x,y,z seperately. For eg, user is doing fine in "x" direction but might need backing up in "y".
// this has to be done for x,y,z separately. For eg, user is doing fine in "x" direction but might need backing up in "y".
if (!is_zero(desired_backup_vel.x)) {
if (is_positive(desired_backup_vel.x)) {
desired_vel_cms.x = MAX(desired_vel_cms.x, desired_backup_vel.x);
@ -505,7 +505,7 @@ void AC_Avoid::limit_velocity_3D(float kP, float accel_cmss, Vector3f &desired_v
return;
}
// create a margin_cm length vector in the direction of desired_vel_cms
// this will create larger margin towards the direction vehicle is traveling in
// this will create larger margin towards the direction vehicle is travelling in
const Vector3f margin_vector = desired_vel_cms.normalized() * margin_cm;
const Vector2f limit_direction_xy{obstacle_vector.x, obstacle_vector.y};

View File

@ -18,7 +18,7 @@
#define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter)
#define AC_AVOID_ANGLE_MAX_PERCENT 0.75f // object avoidance max lean angle as a percentage (expressed in 0 ~ 1 range) of total vehicle max lean angle
#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happend in the last x ms
#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happened in the last x ms
#define AC_AVOID_ACCEL_TIMEOUT_MS 200 // stored velocity used to calculate acceleration will be reset if avoidance is active after this many ms
/*
@ -213,7 +213,7 @@ private:
AP_Int8 _behavior; // avoidance behaviour (slide or stop)
AP_Float _backup_speed_max; // Maximum speed that will be used to back away (in m/s)
AP_Float _alt_min; // alt below which Proximity based avoidance is turned off
AP_Float _accel_max; // maximum accelration while simple avoidance is active
AP_Float _accel_max; // maximum acceleration while simple avoidance is active
AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles
bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable)

View File

@ -74,7 +74,7 @@ private:
// BendyRuler parameters
AP_Float _lookahead; // object avoidance will look this many meters ahead of vehicle
AP_Float _bendy_ratio; // object avoidance will avoid major directional change if change in margin ratio is less than this param
AP_Int16 _bendy_angle; // object avoidance will try avoding change in direction over this much angle
AP_Int16 _bendy_angle; // object avoidance will try avoiding change in direction over this much angle
AP_Int8 _bendy_type; // Type of BendyRuler to run
// internal variables used by background thread

View File

@ -230,7 +230,7 @@ uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importanc
return 0x0;
}
// returns true when there's more work inthe queue to do
// returns true when there's more work in the queue to do
bool AP_OADatabase::process_queue()
{
if (!healthy()) {

View File

@ -925,7 +925,7 @@ bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &d
}
}
}
// report error incase path not found
// report error in case path not found
if (!success) {
err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH;
}

View File

@ -197,6 +197,6 @@ private:
uint8_t _log_num_points;
uint8_t _log_visgraph_version;
// refernce to AP_OAPathPlanner options param
// reference to AP_OAPathPlanner options param
AP_Int16 &_options;
};