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

[JTC] Add console output for tolerance checks (backport #932) #938

Merged
merged 3 commits into from
Jan 8, 2024
Merged
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 @@ -147,7 +147,7 @@ inline bool check_state_tolerance_per_joint(
if (show_errors)
{
const auto logger = rclcpp::get_logger("tolerances");
RCLCPP_ERROR(logger, "Path state tolerances failed:");
RCLCPP_ERROR(logger, "State tolerances failed for joint %d:", joint_idx);

if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
{
Expand Down
17 changes: 11 additions & 6 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,20 +253,21 @@ controller_interface::return_type JointTrajectoryController::update(

// Always check the state tolerance on the first sample in case the first sample
// is the last point
// print output per default, goal will be aborted afterwards
if (
(before_last_point || first_sample) &&
(before_last_point || first_sample) && *(rt_is_holding_.readFromRT()) == false &&
!check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.state_tolerance[index], false) &&
*(rt_is_holding_.readFromRT()) == false)
state_error_, index, default_tolerances_.state_tolerance[index],
true /* show_errors */))
{
tolerance_violated_while_moving = true;
}
// past the final point, check that we end up inside goal tolerance
if (
!before_last_point &&
!before_last_point && *(rt_is_holding_.readFromRT()) == false &&
!check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.goal_state_tolerance[index], false) &&
*(rt_is_holding_.readFromRT()) == false)
state_error_, index, default_tolerances_.goal_state_tolerance[index],
false /* show_errors */))
{
outside_goal_tolerance = true;

Expand All @@ -275,6 +276,10 @@ controller_interface::return_type JointTrajectoryController::update(
if (time_difference > default_tolerances_.goal_time_tolerance)
{
within_goal_time = false;
// print once, goal will be aborted afterwards
check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.goal_state_tolerance[index],
true /* show_errors */);
}
}
}
Expand Down
Loading