mirror of https://github.com/ArduPilot/ardupilot
AC_Avoidance: bendy ruler comment update
This commit is contained in:
parent
cb1853b9bb
commit
a1e03cbbe1
|
@ -78,8 +78,8 @@ AP_OABendyRuler::AP_OABendyRuler()
|
|||
_bearing_prev = FLT_MAX;
|
||||
}
|
||||
|
||||
// run background task to find best path and update avoidance_results
|
||||
// returns true and updates origin_new and destination_new if a best path has been found
|
||||
// run background task to find best path
|
||||
// returns true and updates origin_new and destination_new if a best path has been found. returns false if OA is not required
|
||||
// bendy_type is set to the type of BendyRuler used
|
||||
bool AP_OABendyRuler::update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new, OABendyType &bendy_type, bool proximity_only)
|
||||
{
|
||||
|
|
|
@ -22,8 +22,9 @@ public:
|
|||
OA_BENDY_VERTICAL = 2,
|
||||
};
|
||||
|
||||
// run background task to find best path and update avoidance_results
|
||||
// returns true and populates origin_new and destination_new if OA is required. returns false if OA is not required
|
||||
// run background task to find best path
|
||||
// returns true and updates origin_new and destination_new if a best path has been found. returns false if OA is not required
|
||||
// bendy_type is set to the type of BendyRuler used
|
||||
bool update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new, OABendyType &bendy_type, bool proximity_only);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
|
Loading…
Reference in New Issue