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

Hold joint position if tolerances were violated #395

Open
wants to merge 3 commits into
base: kinetic-devel
Choose a base branch
from
Open
Changes from 2 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
Original file line number Diff line number Diff line change
Expand Up @@ -417,6 +417,10 @@ update(const ros::Time& time, const ros::Duration& period)
ROS_ERROR_STREAM_NAMED(name_,"Path tolerances failed for joint: " << joint_names_[i]);
checkStateTolerancePerJoint(state_joint_error_, joint_tolerances.state_tolerance, true);
}

// If we violate path tolerance then hold current position
setHoldPosition(time_data.uptime, rt_active_goal_);

rt_segment_goal->preallocated_result_->error_code =
control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
rt_segment_goal->setAborted(rt_segment_goal->preallocated_result_);
Expand Down Expand Up @@ -453,6 +457,9 @@ update(const ros::Time& time, const ros::Duration& period)
checkStateTolerancePerJoint(state_joint_error_, tolerances.goal_state_tolerance, true);
}

// If we violate goal tolerances then hold current position
setHoldPosition(time_data.uptime, rt_active_goal_);

rt_segment_goal->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
rt_segment_goal->setAborted(rt_segment_goal->preallocated_result_);
rt_active_goal_.reset();
Expand Down