@ -19,12 +19,52 @@
@@ -19,12 +19,52 @@
# include <AP_AHRS/AP_AHRS.h>
# include <AP_Logger/AP_Logger.h>
const float OA_BENDYRULER_LOOKAHEAD_DEFAULT = 15.0f ;
const float OA_BENDYRULER_RATIO_DEFAULT = 1.5f ;
const int16_t OA_BENDYRULER_ANGLE_DEFAULT = 75 ;
const int16_t OA_BENDYRULER_BEARING_INC = 5 ; // check every 5 degrees around vehicle
const float OA_BENDYRULER_LOOKAHEAD_STEP2_RATIO = 1.0f ; // step2's lookahead length as a ratio of step1's lookahead length
const float OA_BENDYRULER_LOOKAHEAD_STEP2_MIN = 2.0f ; // step2 checks at least this many meters past step1's location
const float OA_BENDYRULER_LOOKAHEAD_PAST_DEST = 2.0f ; // lookahead length will be at least this many meters past the destination
const float OA_BENDYRULER_LOW_SPEED_SQUARED = ( 0.2f * 0.2f ) ; // when ground course is below this speed squared, vehicle's heading will be used
const AP_Param : : GroupInfo AP_OABendyRuler : : var_info [ ] = {
// @Param: LOOKAHEAD
// @DisplayName: Object Avoidance look ahead distance maximum
// @Description: Object Avoidance will look this many meters ahead of vehicle
// @Units: m
// @Range: 1 100
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " LOOKAHEAD " , 1 , AP_OABendyRuler , _lookahead , OA_BENDYRULER_LOOKAHEAD_DEFAULT ) ,
// @Param: CONT_RATIO
// @DisplayName: Obstacle Avoidance margin ratio for BendyRuler to change bearing significantly
// @Description: BendyRuler will avoid changing bearing unless ratio of previous margin from obstacle (or fence) to present calculated margin is atleast this much.
// @Range: 1.1 2
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO ( " CONT_RATIO " , 2 , AP_OABendyRuler , _bendy_ratio , OA_BENDYRULER_RATIO_DEFAULT ) ,
// @Param: CONT_ANGLE
// @DisplayName: BendyRuler's bearing change resistance threshold angle
// @Description: BendyRuler will resist changing current bearing if the change in bearing is over this angle
// @Range: 20 180
// @Increment: 5
// @User: Standard
AP_GROUPINFO ( " CONT_ANGLE " , 3 , AP_OABendyRuler , _bendy_angle , OA_BENDYRULER_ANGLE_DEFAULT ) ,
AP_GROUPEND
} ;
AP_OABendyRuler : : AP_OABendyRuler ( )
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
_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
bool AP_OABendyRuler : : update ( const Location & current_loc , const Location & destination , const Vector2f & ground_speed_vec , Location & origin_new , Location & destination_new )
@ -36,6 +76,9 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin
@@ -36,6 +76,9 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin
const float bearing_to_dest = current_loc . get_bearing_to ( destination ) * 0.01f ;
const float distance_to_dest = current_loc . get_distance ( destination ) ;
// make sure user has set a meaningful value for _lookahead
_lookahead = MAX ( _lookahead , 1.0f ) ;
// lookahead distance is adjusted dynamically based on avoidance results
_current_lookahead = constrain_float ( _current_lookahead , _lookahead * 0.5f , _lookahead ) ;
@ -112,13 +155,18 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin
@@ -112,13 +155,18 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin
// calculate minimum margin to fence and obstacles for this scenario
float margin2 = calc_avoidance_margin ( test_loc , test_loc2 ) ;
if ( margin2 > _margin_max ) {
// if the chosen direction is directly towards the destination avoidance can be turned off
const bool active = ( i ! = 0 | | j ! = 0 ) ;
float final_bearing = bearing_test ;
float final_margin = margin ;
// check if we need ignore test_bearing and continue on previous bearing
const bool ignore_bearing_change = resist_bearing_change ( destination , current_loc , active , bearing_test , lookahead_step1_dist , margin , _destination_prev , _bearing_prev , final_bearing , final_margin ) ;
// all good, now project in the chosen direction by the full distance
destination_new = current_loc ;
destination_new . offset_bearing ( bearing_test , distance_to_dest ) ;
destination_new . offset_bearing ( final_ bearing, distance_to_dest ) ;
_current_lookahead = MIN ( _lookahead , _current_lookahead * 1.1f ) ;
// if the chosen direction is directly towards the destination turn off avoidance
const bool active = ( i ! = 0 | | j ! = 0 ) ;
AP : : logger ( ) . Write_OABendyRuler ( active , bearing_to_dest , margin , destination , destination_new ) ;
AP : : logger ( ) . Write_OABendyRuler ( active , bearing_to_dest , ignore_bearing_change , final_margin , destination , destination_new ) ;
return active ;
}
}
@ -144,13 +192,59 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin
@@ -144,13 +192,59 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin
destination_new . offset_bearing ( chosen_bearing , distance_to_dest ) ;
// log results
AP : : logger ( ) . Write_OABendyRuler ( true , chosen_bearing , best_margin , destination , destination_new ) ;
AP : : logger ( ) . Write_OABendyRuler ( true , chosen_bearing , false , best_margin , destination , destination_new ) ;
return true ;
}
/*
This function is called when BendyRuler has found a bearing which is obstacles free at atleast lookahead_step1_dist and then lookahead_step2_dist from the present location
In many situations , this new bearing can be either left or right of the obstacle , and BendyRuler can have a tough time deciding between the two .
It has the tendency to move the vehicle back and forth , if the margin obtained is even slightly better in the newer iteration .
Therefore , this method attempts to avoid changing direction of the vehicle by more than _bendy_angle degrees ,
unless the new margin is atleast _bendy_ratio times better than the margin with previously calculated bearing .
We return true if we have resisted the change and will follow the last calculated bearing .
*/
bool AP_OABendyRuler : : resist_bearing_change ( const Location & destination , const Location & current_loc , bool active , float bearing_test , float lookahead_step1_dist , float margin , Location & prev_dest , float & prev_bearing , float & final_bearing , float & final_margin ) const
{
bool resisted_change = false ;
// see if there was a change in destination, if so, do not resist changing bearing
bool dest_change = false ;
if ( ! destination . same_latlon_as ( prev_dest ) ) {
dest_change = true ;
prev_dest = destination ;
}
// check if we need to resist the change in direction of the vehicle. If we have a clear path to destination, go there any how
if ( active & & ! dest_change & & is_positive ( _bendy_ratio ) ) {
// check the change in bearing between freshly calculated and previous stored BendyRuler bearing
if ( ( fabsf ( wrap_180 ( prev_bearing - bearing_test ) ) > _bendy_angle ) & & ( ! is_equal ( prev_bearing , FLT_MAX ) ) ) {
// check margin in last bearing's direction
Location test_loc_previous_bearing = current_loc ;
test_loc_previous_bearing . offset_bearing ( wrap_180 ( prev_bearing ) , lookahead_step1_dist ) ;
float previous_bearing_margin = calc_avoidance_margin ( current_loc , test_loc_previous_bearing ) ;
if ( margin < ( _bendy_ratio * previous_bearing_margin ) ) {
// don't change direction abruptly. If margin difference is not significant, follow the last direction
final_bearing = prev_bearing ;
final_margin = previous_bearing_margin ;
resisted_change = true ;
}
}
} else {
// reset stored bearing if BendyRuler is not active or if WP has changed for unnecessary resistance to path change
prev_bearing = FLT_MAX ;
}
if ( ! resisted_change ) {
// we are not resisting the change, hence store BendyRuler's presently calculated bearing for future iterations
prev_bearing = bearing_test ;
}
return resisted_change ;
}
// calculate minimum distance between a segment and any obstacle
float AP_OABendyRuler : : calc_avoidance_margin ( const Location & start , const Location & end )
float AP_OABendyRuler : : calc_avoidance_margin ( const Location & start , const Location & end ) const
{
float margin_min = FLT_MAX ;
@ -177,7 +271,7 @@ float AP_OABendyRuler::calc_avoidance_margin(const Location &start, const Locati
@@ -177,7 +271,7 @@ float AP_OABendyRuler::calc_avoidance_margin(const Location &start, const Locati
// calculate minimum distance between a path and the circular fence (centered on home)
// on success returns true and updates margin
bool AP_OABendyRuler : : calc_margin_from_circular_fence ( const Location & start , const Location & end , float & margin )
bool AP_OABendyRuler : : calc_margin_from_circular_fence ( const Location & start , const Location & end , float & margin ) const
{
// exit immediately if polygon fence is not enabled
const AC_Fence * fence = AC_Fence : : get_singleton ( ) ;
@ -203,7 +297,7 @@ bool AP_OABendyRuler::calc_margin_from_circular_fence(const Location &start, con
@@ -203,7 +297,7 @@ bool AP_OABendyRuler::calc_margin_from_circular_fence(const Location &start, con
// calculate minimum distance between a path and all inclusion and exclusion polygons
// on success returns true and updates margin
bool AP_OABendyRuler : : calc_margin_from_inclusion_and_exclusion_polygons ( const Location & start , const Location & end , float & margin )
bool AP_OABendyRuler : : calc_margin_from_inclusion_and_exclusion_polygons ( const Location & start , const Location & end , float & margin ) const
{
const AC_Fence * fence = AC_Fence : : get_singleton ( ) ;
if ( fence = = nullptr ) {
@ -269,7 +363,7 @@ bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_polygons(const Lo
@@ -269,7 +363,7 @@ bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_polygons(const Lo
// calculate minimum distance between a path and all inclusion and exclusion circles
// on success returns true and updates margin
bool AP_OABendyRuler : : calc_margin_from_inclusion_and_exclusion_circles ( const Location & start , const Location & end , float & margin )
bool AP_OABendyRuler : : calc_margin_from_inclusion_and_exclusion_circles ( const Location & start , const Location & end , float & margin ) const
{
// exit immediately if fence is not enabled
const AC_Fence * fence = AC_Fence : : get_singleton ( ) ;
@ -345,7 +439,7 @@ bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_circles(const Loc
@@ -345,7 +439,7 @@ bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_circles(const Loc
// calculate minimum distance between a path and proximity sensor obstacles
// on success returns true and updates margin
bool AP_OABendyRuler : : calc_margin_from_object_database ( const Location & start , const Location & end , float & margin )
bool AP_OABendyRuler : : calc_margin_from_object_database ( const Location & start , const Location & end , float & margin ) const
{
// exit immediately if db is empty
AP_OADatabase * oaDb = AP : : oadatabase ( ) ;