Skip to content

Commit

Permalink
[JTC] Tolerance tests + Hold on time violation (backport ros-controls…
Browse files Browse the repository at this point in the history
…#613)

* Add new test to ensure that controller goes into position holding when tolerances are violated
* Hold position if goal_time is exceeded with topic interface
* Fix hold on time-violation
  • Loading branch information
christophfroehlich committed Nov 17, 2023
1 parent 170bfa4 commit f475ec9
Show file tree
Hide file tree
Showing 2 changed files with 72 additions and 3 deletions.
14 changes: 11 additions & 3 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -365,19 +365,27 @@ controller_interface::return_type JointTrajectoryController::update(
traj_msg_external_point_ptr_.reset();
traj_msg_external_point_ptr_.initRT(set_hold_position());
}
// else, run another cycle while waiting for outside_goal_tolerance
// to be satisfied or violated within the goal_time_tolerance
}
}
else if (tolerance_violated_while_moving && *(rt_has_pending_goal_.readFromRT()) == false)
{
// we need to ensure that there is no pending goal -> we get a race condition otherwise

RCLCPP_ERROR(get_node()->get_logger(), "Holding position due to state tolerance violation");

traj_msg_external_point_ptr_.reset();
traj_msg_external_point_ptr_.initRT(set_hold_position());
}
else if (
!before_last_point && !within_goal_time && *(rt_has_pending_goal_.readFromRT()) == false)
{
RCLCPP_ERROR(get_node()->get_logger(), "Exceeded goal_time_tolerance: holding position...");

traj_msg_external_point_ptr_.reset();
traj_msg_external_point_ptr_.initRT(set_hold_position());
}
// else, run another cycle while waiting for outside_goal_tolerance
// to be satisfied (will stay in this state until new message arrives)
// or outside_goal_tolerance violated within the goal_time_tolerance
}
}

Expand Down
61 changes: 61 additions & 0 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1666,6 +1666,67 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
executor.cancel();
}

TEST_P(TrajectoryControllerTestParameterized, test_state_tolerances_fail)
{
// set joint tolerance parameters
const double state_tol = 0.0001;
std::vector<rclcpp::Parameter> params = {
rclcpp::Parameter("constraints.joint1.trajectory", state_tol),
rclcpp::Parameter("constraints.joint2.trajectory", state_tol),
rclcpp::Parameter("constraints.joint3.trajectory", state_tol)};

rclcpp::executors::MultiThreadedExecutor executor;
SetUpAndActivateTrajectoryController(executor, false, {params}, true);

// send msg
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(100);
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
// *INDENT-OFF*
std::vector<std::vector<double>> points{
{{3.3, 4.4, 5.5}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
std::vector<std::vector<double>> points_velocities{
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
// *INDENT-ON*
publish(time_from_start, points, rclcpp::Time(0, 0, RCL_STEADY_TIME), {}, points_velocities);
traj_controller_->wait_for_trajectory(executor);
updateController(rclcpp::Duration(FIRST_POINT_TIME));

// it should have aborted and be holding now
expectHoldingPoint(joint_state_pos_);
}

TEST_P(TrajectoryControllerTestParameterized, test_goal_tolerances_fail)
{
// set joint tolerance parameters
const double goal_tol = 0.1;
// set very small goal_time so that goal_time is violated
const double goal_time = 0.000001;
std::vector<rclcpp::Parameter> params = {
rclcpp::Parameter("constraints.joint1.goal", goal_tol),
rclcpp::Parameter("constraints.joint2.goal", goal_tol),
rclcpp::Parameter("constraints.joint3.goal", goal_tol),
rclcpp::Parameter("constraints.goal_time", goal_time)};

rclcpp::executors::MultiThreadedExecutor executor;
SetUpAndActivateTrajectoryController(executor, false, {params}, true);

// send msg
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(100);
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
// *INDENT-OFF*
std::vector<std::vector<double>> points{
{{3.3, 4.4, 5.5}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
std::vector<std::vector<double>> points_velocities{
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
// *INDENT-ON*
publish(time_from_start, points, rclcpp::Time(0, 0, RCL_STEADY_TIME), {}, points_velocities);
traj_controller_->wait_for_trajectory(executor);
updateController(rclcpp::Duration(4 * FIRST_POINT_TIME));

// it should have aborted and be holding now
expectHoldingPoint(joint_state_pos_);
}

// position controllers
INSTANTIATE_TEST_SUITE_P(
PositionTrajectoryControllers, TrajectoryControllerTestParameterized,
Expand Down

0 comments on commit f475ec9

Please sign in to comment.