AC_Avoidance: bendy ruler format fixes

This commit is contained in:
Randy Mackay 2021-07-14 12:59:27 +09:00
parent 0b26bace7f
commit 075c05baea
2 changed files with 6 additions and 6 deletions

View File

@ -236,7 +236,7 @@ bool AP_OABendyRuler::search_xy_path(const Location& current_loc, const Location
} }
// Search for path in the vertical directions // Search for path in the vertical directions
bool AP_OABendyRuler::search_vertical_path(const Location& current_loc, const Location& destination,Location &destination_new, const float &lookahead_step1_dist, const float &lookahead_step2_dist, const float &bearing_to_dest, const float &distance_to_dest, bool proximity_only) bool AP_OABendyRuler::search_vertical_path(const Location &current_loc, const Location &destination, Location &destination_new, float lookahead_step1_dist, float lookahead_step2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only)
{ {
// check OA_BEARING_INC_VERTICAL definition allows checking in all directions // check OA_BEARING_INC_VERTICAL definition allows checking in all directions
static_assert(360 % OA_BENDYRULER_BEARING_INC_VERTICAL == 0, "check 360 is a multiple of OA_BEARING_INC_VERTICAL"); static_assert(360 % OA_BENDYRULER_BEARING_INC_VERTICAL == 0, "check 360 is a multiple of OA_BEARING_INC_VERTICAL");

View File

@ -40,7 +40,7 @@ private:
bool search_xy_path(const Location& current_loc, const Location& destination, float ground_course_deg, Location &destination_new, float lookahead_step_1_dist, float lookahead_step_2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only); bool search_xy_path(const Location& current_loc, const Location& destination, float ground_course_deg, Location &destination_new, float lookahead_step_1_dist, float lookahead_step_2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only);
// search for path in the Vertical directions // search for path in the Vertical directions
bool search_vertical_path(const Location& current_loc, const Location& destination,Location &destination_new, const float &lookahead_step1_dist, const float &lookahead_step2_dist, const float &bearing_to_dest, const float &distance_to_dest, bool proximity_only); bool search_vertical_path(const Location &current_loc, const Location &destination, Location &destination_new, float lookahead_step1_dist, float lookahead_step2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only);
// calculate minimum distance between a path and any obstacle // calculate minimum distance between a path and any obstacle
float calc_avoidance_margin(const Location &start, const Location &end, bool proximity_only) const; float calc_avoidance_margin(const Location &start, const Location &end, bool proximity_only) const;