Skip to content

Commit

Permalink
add oscillation angle in move_base
Browse files Browse the repository at this point in the history
  • Loading branch information
knorth55 authored and corot committed Nov 24, 2023
1 parent f04bc20 commit a9f6e98
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 1 deletion.
3 changes: 3 additions & 0 deletions mbf_abstract_nav/include/mbf_abstract_nav/move_base_action.h
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,9 @@ class MoveBaseAction
//! minimal move distance to not detect an oscillation
double oscillation_distance_;

//! minimal rotation to not detect an oscillation
double oscillation_angle_;

GoalHandle goal_handle_;

std::string name_;
Expand Down
2 changes: 2 additions & 0 deletions mbf_abstract_nav/src/mbf_abstract_nav/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,3 +38,5 @@ def add_mbf_abstract_nav_params(gen):
"How long in seconds to allow for oscillation before executing recovery behaviors", 0.0, 0, 60)
gen.add("oscillation_distance", double_t, 0,
"How far in meters the robot must move to be considered not to be oscillating", 0.5, 0, 10)
gen.add("oscillation_angle", double_t, 0,
"How far in radian the robot must rotate to be considered not to be oscillating", 3.14, 0, 6.28)
5 changes: 4 additions & 1 deletion mbf_abstract_nav/src/move_base_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ MoveBaseAction::MoveBaseAction(const std::string& name, const mbf_utility::Robot
, action_client_recovery_(private_nh_, "recovery")
, oscillation_timeout_(0)
, oscillation_distance_(0)
, oscillation_angle_(0)
, replanning_thread_shutdown_(false)
, recovery_enabled_(true)
, behaviors_(behaviors)
Expand Down Expand Up @@ -86,6 +87,7 @@ void MoveBaseAction::reconfigure(
replanning_period_.fromSec(0.0);
oscillation_timeout_ = ros::Duration(config.oscillation_timeout);
oscillation_distance_ = config.oscillation_distance;
oscillation_angle_ = config.oscillation_angle;
recovery_enabled_ = config.recovery_enabled;
}

Expand Down Expand Up @@ -198,7 +200,8 @@ void MoveBaseAction::actionExePathFeedback(
{
// check if oscillating
// moved more than the minimum oscillation distance
if (mbf_utility::distance(robot_pose_, last_oscillation_pose_) >= oscillation_distance_)
if (mbf_utility::distance(robot_pose_, last_oscillation_pose_) >= oscillation_distance_ ||
mbf_utility::angle(robot_pose_, last_oscillation_pose_) >= oscillation_angle_)
{
last_oscillation_reset_ = ros::Time::now();
last_oscillation_pose_ = robot_pose_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ mbf_abstract_nav::MoveBaseFlexConfig CostmapControllerExecution::toAbstract(cons
abstract_config.controller_max_retries = config.controller_max_retries;
abstract_config.oscillation_timeout = config.oscillation_timeout;
abstract_config.oscillation_distance = config.oscillation_distance;
abstract_config.oscillation_angle = config.oscillation_angle;
return abstract_config;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -463,6 +463,7 @@ void CostmapNavigationServer::reconfigure(mbf_costmap_nav::MoveBaseFlexConfig& c
abstract_config.recovery_patience = config.recovery_patience;
abstract_config.oscillation_timeout = config.oscillation_timeout;
abstract_config.oscillation_distance = config.oscillation_distance;
abstract_config.oscillation_angle = config.oscillation_angle;
abstract_config.restore_defaults = config.restore_defaults;
mbf_abstract_nav::AbstractNavigationServer::reconfigure(abstract_config, level);

Expand Down

0 comments on commit a9f6e98

Please sign in to comment.