Skip to content

Commit a9f6e98

Browse files
knorth55corot
authored andcommitted
add oscillation angle in move_base
1 parent f04bc20 commit a9f6e98

File tree

5 files changed

+11
-1
lines changed

5 files changed

+11
-1
lines changed

mbf_abstract_nav/include/mbf_abstract_nav/move_base_action.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,9 @@ class MoveBaseAction
134134
//! minimal move distance to not detect an oscillation
135135
double oscillation_distance_;
136136

137+
//! minimal rotation to not detect an oscillation
138+
double oscillation_angle_;
139+
137140
GoalHandle goal_handle_;
138141

139142
std::string name_;

mbf_abstract_nav/src/mbf_abstract_nav/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,3 +38,5 @@ def add_mbf_abstract_nav_params(gen):
3838
"How long in seconds to allow for oscillation before executing recovery behaviors", 0.0, 0, 60)
3939
gen.add("oscillation_distance", double_t, 0,
4040
"How far in meters the robot must move to be considered not to be oscillating", 0.5, 0, 10)
41+
gen.add("oscillation_angle", double_t, 0,
42+
"How far in radian the robot must rotate to be considered not to be oscillating", 3.14, 0, 6.28)

mbf_abstract_nav/src/move_base_action.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ MoveBaseAction::MoveBaseAction(const std::string& name, const mbf_utility::Robot
5757
, action_client_recovery_(private_nh_, "recovery")
5858
, oscillation_timeout_(0)
5959
, oscillation_distance_(0)
60+
, oscillation_angle_(0)
6061
, replanning_thread_shutdown_(false)
6162
, recovery_enabled_(true)
6263
, behaviors_(behaviors)
@@ -86,6 +87,7 @@ void MoveBaseAction::reconfigure(
8687
replanning_period_.fromSec(0.0);
8788
oscillation_timeout_ = ros::Duration(config.oscillation_timeout);
8889
oscillation_distance_ = config.oscillation_distance;
90+
oscillation_angle_ = config.oscillation_angle;
8991
recovery_enabled_ = config.recovery_enabled;
9092
}
9193

@@ -198,7 +200,8 @@ void MoveBaseAction::actionExePathFeedback(
198200
{
199201
// check if oscillating
200202
// moved more than the minimum oscillation distance
201-
if (mbf_utility::distance(robot_pose_, last_oscillation_pose_) >= oscillation_distance_)
203+
if (mbf_utility::distance(robot_pose_, last_oscillation_pose_) >= oscillation_distance_ ||
204+
mbf_utility::angle(robot_pose_, last_oscillation_pose_) >= oscillation_angle_)
202205
{
203206
last_oscillation_reset_ = ros::Time::now();
204207
last_oscillation_pose_ = robot_pose_;

mbf_costmap_nav/src/mbf_costmap_nav/costmap_controller_execution.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,7 @@ mbf_abstract_nav::MoveBaseFlexConfig CostmapControllerExecution::toAbstract(cons
7070
abstract_config.controller_max_retries = config.controller_max_retries;
7171
abstract_config.oscillation_timeout = config.oscillation_timeout;
7272
abstract_config.oscillation_distance = config.oscillation_distance;
73+
abstract_config.oscillation_angle = config.oscillation_angle;
7374
return abstract_config;
7475
}
7576

mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -463,6 +463,7 @@ void CostmapNavigationServer::reconfigure(mbf_costmap_nav::MoveBaseFlexConfig& c
463463
abstract_config.recovery_patience = config.recovery_patience;
464464
abstract_config.oscillation_timeout = config.oscillation_timeout;
465465
abstract_config.oscillation_distance = config.oscillation_distance;
466+
abstract_config.oscillation_angle = config.oscillation_angle;
466467
abstract_config.restore_defaults = config.restore_defaults;
467468
mbf_abstract_nav::AbstractNavigationServer::reconfigure(abstract_config, level);
468469

0 commit comments

Comments
 (0)