Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

solution for issue #949 #950

Open
wants to merge 2 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions move_base/include/move_base/move_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -231,6 +231,7 @@ namespace move_base {
move_base::MoveBaseConfig default_config_;
bool setup_, p_freq_change_, c_freq_change_;
bool new_global_plan_;
bool planner_goal_updated_;
};
};
#endif
Expand Down
18 changes: 16 additions & 2 deletions move_base/src/move_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ namespace move_base {
blp_loader_("nav_core", "nav_core::BaseLocalPlanner"),
recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL),
runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) {
runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false), planner_goal_updated_(false) {

as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false);

Expand Down Expand Up @@ -571,13 +571,24 @@ namespace move_base {

//time to plan! get a copy of the goal and unlock the mutex
geometry_msgs::PoseStamped temp_goal = planner_goal_;
planner_goal_updated_ = false;
lock.unlock();
ROS_DEBUG_NAMED("move_base_plan_thread","Planning...");

//run planner
planner_plan_->clear();
bool gotPlan = n.ok() && makePlan(temp_goal, *planner_plan_);


//if new goal available, abandon current plan and go back to makePlan for new goal
if(planner_goal_updated_)
{
if(gotPlan) // still update last_valid_plan_ in case too many goals preempted
last_valid_plan_ = ros::Time::now();
//take the mutex for the next iteration
lock.lock();
continue;
}

if(gotPlan){
ROS_DEBUG_NAMED("move_base_plan_thread","Got Plan with %zu points!", planner_plan_->size());
//pointer swap the plans under mutex (the controller will pull from latest_plan_)
Expand Down Expand Up @@ -649,6 +660,7 @@ namespace move_base {
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
planner_goal_ = goal;
runPlanner_ = true;
planner_goal_updated_ = true;
planner_cond_.notify_one();
lock.unlock();

Expand Down Expand Up @@ -698,6 +710,7 @@ namespace move_base {
lock.lock();
planner_goal_ = goal;
runPlanner_ = true;
planner_goal_updated_ = true;
planner_cond_.notify_one();
lock.unlock();

Expand Down Expand Up @@ -736,6 +749,7 @@ namespace move_base {
lock.lock();
planner_goal_ = goal;
runPlanner_ = true;
planner_goal_updated_ = true;
planner_cond_.notify_one();
lock.unlock();

Expand Down