Skip to content

Commit

Permalink
Use a copy of the pointer in update() to avoid crash by cancelCB()
Browse files Browse the repository at this point in the history
  • Loading branch information
oka1125 authored and bmagyar committed Nov 9, 2018
1 parent 0cfdcf4 commit a22f19c
Showing 1 changed file with 6 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -314,10 +314,12 @@ template <class HardwareInterface>
void GripperActionController<HardwareInterface>::
checkForSuccess(const ros::Time& time, double error_position, double current_position, double current_velocity)
{
if(!rt_active_goal_)
RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);

if(!current_active_goal)
return;

if(rt_active_goal_->gh_.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
if(current_active_goal->gh_.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
return;

if(fabs(error_position) < goal_tolerance_)
Expand All @@ -326,7 +328,7 @@ checkForSuccess(const ros::Time& time, double error_position, double current_pos
pre_alloc_result_->position = current_position;
pre_alloc_result_->reached_goal = true;
pre_alloc_result_->stalled = false;
rt_active_goal_->setSucceeded(pre_alloc_result_);
current_active_goal->setSucceeded(pre_alloc_result_);
}
else
{
Expand All @@ -340,7 +342,7 @@ checkForSuccess(const ros::Time& time, double error_position, double current_pos
pre_alloc_result_->position = current_position;
pre_alloc_result_->reached_goal = false;
pre_alloc_result_->stalled = true;
rt_active_goal_->setAborted(pre_alloc_result_);
current_active_goal->setAborted(pre_alloc_result_);
}
}
}
Expand Down

0 comments on commit a22f19c

Please sign in to comment.