Skip to content
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
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,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->preallocated_result_->error_string = joint_names_[i] + " path error " + std::to_string( state_joint_error_.position[0] );
Expand Down Expand Up @@ -442,6 +446,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->preallocated_result_->error_string = joint_names_[i] + " goal error " + std::to_string( state_joint_error_.position[0] );
rt_segment_goal->setAborted(rt_segment_goal->preallocated_result_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1203,6 +1203,17 @@ TEST_F(JointTrajectoryControllerTest, pathToleranceViolation)
// Controller continues execution, see https://github.com/ros-controls/ros_controllers/issues/48
// Make sure to restore an error-less state for the tests to continue

// Check that we're not moving
StateConstPtr state1 = getState();
ros::Duration(0.5).sleep(); // Wait
StateConstPtr state2 = getState();
for (unsigned int i = 0; i < n_joints; ++i)
{
EXPECT_NEAR(state1->desired.positions[i], state2->desired.positions[i], EPS);
EXPECT_NEAR(state1->desired.velocities[i], state2->desired.velocities[i], EPS);
EXPECT_NEAR(state1->desired.accelerations[i], state2->desired.accelerations[i], EPS);
}

// Restore perfect control
{
std_msgs::Float64 smoothing;
Expand Down Expand Up @@ -1279,7 +1290,7 @@ TEST_F(JointTrajectoryControllerTest, goalToleranceViolation)
// Make robot respond with a delay
{
std_msgs::Float64 smoothing;
smoothing.data = 0.95;
smoothing.data = 0.98;
smoothing_pub.publish(smoothing);
ASSERT_TRUE(waitForRobotReady());
}
Expand Down Expand Up @@ -1307,6 +1318,9 @@ TEST_F(JointTrajectoryControllerTest, goalToleranceViolation)
// Controller continues execution, see https://github.com/ros-controls/ros_controllers/issues/48
// Make sure to restore an error-less state for the tests to continue

// Check that we're not moving after restoring perfect control
StateConstPtr state1 = getState();

// Restore perfect control
{
std_msgs::Float64 smoothing;
Expand All @@ -1317,6 +1331,13 @@ TEST_F(JointTrajectoryControllerTest, goalToleranceViolation)

ros::Duration timeout = getTrajectoryDuration(traj_goal.trajectory) + ros::Duration(TIMEOUT_TRAJ_EXECUTION_S);
EXPECT_TRUE(waitForStop(timeout));

StateConstPtr state2 = getState();
for (unsigned int i = 0; i < n_joints; ++i)
{
EXPECT_NEAR(state1->actual.positions[i], state2->actual.positions[i], EPS);
EXPECT_NEAR(state1->actual.velocities[i], state2->actual.velocities[i], EPS);
}
}

TEST_F(JointTrajectoryControllerTest, goalToleranceViolationSingleJoint)
Expand Down Expand Up @@ -1380,11 +1401,21 @@ TEST_F(JointTrajectoryControllerTest, goalToleranceViolationSingleJoint)
// Controller continues execution, see https://github.com/ros-controls/ros_controllers/issues/48
// Make sure to restore an error-less state for the tests to continue

// Check that we're not moving after restoring perfect control
StateConstPtr state1 = getState();

// Restore perfect control
smoothings.data.assign({0., 0.});
smoothings_pub.publish(smoothings);
ASSERT_TRUE(waitForRobotReady());
EXPECT_TRUE(waitForStop(restore_timeout));

StateConstPtr state2 = getState();
for (unsigned int i = 0; i < n_joints; ++i)
{
EXPECT_NEAR(state1->actual.positions[i], state2->actual.positions[i], EPS);
EXPECT_NEAR(state1->actual.velocities[i], state2->actual.velocities[i], EPS);
}
}

int main(int argc, char** argv)
Expand Down