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

Gracefully handle jump back in time #203

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from
Open
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
7 changes: 4 additions & 3 deletions actionlib/include/actionlib/server/simple_action_server_imp.h
Original file line number Diff line number Diff line change
Expand Up @@ -295,9 +295,10 @@ void SimpleActionServer<ActionSpec>::goalCallback(GoalHandle goal)
boost::recursive_mutex::scoped_lock lock(lock_);
ROS_DEBUG_NAMED("actionlib", "A new goal has been received by the single goal action server");

// check that the timestamp is past or equal to that of the current goal and the next goal
if ((!current_goal_.getGoal() || goal.getGoalID().stamp >= current_goal_.getGoalID().stamp) &&
(!next_goal_.getGoal() || goal.getGoalID().stamp >= next_goal_.getGoalID().stamp))
// check that the timestamp is past or equal to that of the current goal and the next goal (or time was reset)
ros::Time now = ros::Time::now();
if ((!current_goal_.getGoal() || goal.getGoalID().stamp >= current_goal_.getGoalID().stamp || now < current_goal_.getGoalID().stamp) &&
(!next_goal_.getGoal() || goal.getGoalID().stamp >= next_goal_.getGoalID().stamp || now < next_goal_.getGoalID().stamp))
{
// if next_goal has not been accepted already... its going to get bumped, but we need to let the client know we're preempting
if (next_goal_.getGoal() && (!current_goal_.getGoal() || next_goal_ != current_goal_)) {
Expand Down