Skip to content

[JTC] Process tolerances sent with action goal #716

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

Merged
merged 32 commits into from
Jul 3, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
c3acc81
Process tolerances sent with action goal
christophfroehlich Jul 24, 2023
c168ab3
Merge branch 'master' into jtc/action_tolerances
destogl Jul 24, 2023
0328c94
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Aug 3, 2023
880b87b
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Aug 15, 2023
57d6b32
Remove whitespaces
christophfroehlich Aug 15, 2023
ac0e871
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Aug 16, 2023
2c717d0
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Sep 12, 2023
31afb42
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Sep 14, 2023
16a8828
Fix merge conflict
christophfroehlich Sep 14, 2023
6a95acb
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Oct 9, 2023
4a3ba8b
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Nov 15, 2023
bf6d034
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Nov 19, 2023
22543a9
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Nov 28, 2023
fcaa1b9
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Dec 22, 2023
534746c
Fix format
christophfroehlich Dec 22, 2023
06400fa
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Jan 31, 2024
7e8fa9f
Merge branch 'master' into jtc/action_tolerances
bmagyar Jun 10, 2024
ae5efec
Apply suggestions from code review
christophfroehlich Jun 18, 2024
cb0e733
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Jun 18, 2024
597a2b8
Use ERASE_CONSTANT
christophfroehlich Jun 18, 2024
88666eb
Don't compare double with == -1
christophfroehlich Jun 18, 2024
7cc1244
Don't accept negative tolerances
christophfroehlich Jun 20, 2024
6d21d3a
Fix tests and improve error messages.
christophfroehlich Jun 20, 2024
a5d548c
Add a test for wrong joints too
christophfroehlich Jun 20, 2024
e48ca7b
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Jun 20, 2024
4f1b755
Move tolerances tests to own file
christophfroehlich Jun 20, 2024
ec87dc0
Apply suggestions from code review
christophfroehlich Jun 21, 2024
54d279c
Remove duplicate check
christophfroehlich Jun 22, 2024
1a592ab
Pass std::vector instead of parameter struct
christophfroehlich Jun 24, 2024
2bdc0c2
Use a static child logger
christophfroehlich Jun 24, 2024
36ecdda
Remove test_tolerances_utils
christophfroehlich Jun 24, 2024
34ca300
Update docs
christophfroehlich Jun 24, 2024
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
Prev Previous commit
Next Next commit
Fix tests and improve error messages.
  • Loading branch information
christophfroehlich committed Jun 20, 2024
commit 6d21d3a4973cffb771de5627303b54c1b46133cc
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ SegmentTolerances get_segment_tolerances(
// There are two special values for tolerances:
// * 0 - The tolerance is unspecified and will remain at whatever the default is
// * -1 - The tolerance is "erased".
// If there was a default, the joint will be allowed to move without restriction.
// If there was a default, the joint will be allowed to move without restriction.
constexpr double ERASE_VALUE = -1.0;
auto is_erase_value = [](double value)
{ return fabs(value - ERASE_VALUE) < std::numeric_limits<float>::epsilon(); };
Expand All @@ -162,7 +162,10 @@ SegmentTolerances get_segment_tolerances(
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint + "' specified in goal.path_tolerance does not exist").c_str());
("joint '" + joint +
"' specified in goal.path_tolerance does not exist. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
auto i = std::distance(params.joints.cbegin(), it);
Expand All @@ -178,7 +181,9 @@ SegmentTolerances get_segment_tolerances(
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint + "' specified in goal.path_tolerance has a negative position tolerance")
("joint '" + joint +
"' specified in goal.path_tolerance has a negative position tolerance. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
Expand All @@ -195,7 +200,9 @@ SegmentTolerances get_segment_tolerances(
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint + "' specified in goal.path_tolerance has a negative velocity tolerance")
("joint '" + joint +
"' specified in goal.path_tolerance has a negative velocity tolerance. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
Expand All @@ -213,7 +220,8 @@ SegmentTolerances get_segment_tolerances(
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.path_tolerance has a negative acceleration tolerance")
"' specified in goal.path_tolerance has a negative acceleration tolerance. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
Expand All @@ -237,7 +245,10 @@ SegmentTolerances get_segment_tolerances(
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint + "' specified in goal.goal_tolerance does not exist").c_str());
("joint '" + joint +
"' specified in goal.goal_tolerance does not exist. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
auto i = std::distance(params.joints.cbegin(), it);
Expand All @@ -253,7 +264,9 @@ SegmentTolerances get_segment_tolerances(
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint + "' specified in goal.goal_tolerance has a negative position tolerance")
("joint '" + joint +
"' specified in goal.goal_tolerance has a negative position tolerance. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
Expand All @@ -270,7 +283,9 @@ SegmentTolerances get_segment_tolerances(
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint + "' specified in goal.goal_tolerance has a negative velocity tolerance")
("joint '" + joint +
"' specified in goal.goal_tolerance has a negative velocity tolerance. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
Expand All @@ -288,7 +303,8 @@ SegmentTolerances get_segment_tolerances(
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.goal_tolerance has a negative acceleration tolerance")
"' specified in goal.goal_tolerance has a negative acceleration tolerance. "
"Use default tolerances.")
.c_str());
return default_tolerances;
}
Expand Down
159 changes: 71 additions & 88 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -494,44 +494,18 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_multi_point_success)
expectCommandPoint(points_positions.at(1));
}

void check_default_tolerances(joint_trajectory_controller::SegmentTolerances active_tolerances)
{
EXPECT_EQ(active_tolerances.goal_time_tolerance, 1.0);
// acceleration is never set, and goal_state_tolerance.velocity from stopped_velocity_tolerance
EXPECT_EQ(active_tolerances.state_tolerance.size(), 3);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).position, 0.1);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).velocity, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).acceleration, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).position, 0.1);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).velocity, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).acceleration, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).position, 0.1);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).velocity, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).acceleration, 0.0);

EXPECT_EQ(active_tolerances.goal_state_tolerance.size(), 3);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).position, 0.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).velocity, 0.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).acceleration, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).position, 0.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).velocity, 0.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).acceleration, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).position, 0.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).velocity, 0.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).acceleration, 0.0);
}

/**
* No need for parameterized tests
*/
TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
{
// set tolerance parameters
constexpr double default_goal_time = 0.1;
std::vector<rclcpp::Parameter> params = {
rclcpp::Parameter("constraints.joint1.goal", 0.1),
rclcpp::Parameter("constraints.joint2.goal", 0.1),
rclcpp::Parameter("constraints.joint3.goal", 0.1),
rclcpp::Parameter("constraints.goal_time", 0.1),
rclcpp::Parameter("constraints.goal_time", default_goal_time),
rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.1),
rclcpp::Parameter("constraints.joint1.trajectory", 0.1),
rclcpp::Parameter("constraints.joint2.trajectory", 0.1),
Expand All @@ -540,6 +514,7 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
SetUpExecutor(params);

{
SCOPED_TRACE("Check default values");
SetUpControllerHardware();
std::shared_future<typename GoalHandle::SharedPtr> gh_future;
// send goal
Expand All @@ -564,7 +539,8 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, 1.0);
expectDefaultTolerances(active_tolerances);
}

// send goal with nonzero tolerances, are they accepted?
Expand Down Expand Up @@ -622,29 +598,29 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
EXPECT_EQ(active_tolerances.goal_time_tolerance, 2.0);

EXPECT_EQ(active_tolerances.state_tolerance.size(), 3);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).position, 0.2);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).velocity, 0.3);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).acceleration, 0.4);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).position, 0.2);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).velocity, 0.3);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).acceleration, 0.4);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).position, 0.2);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).velocity, 0.3);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).acceleration, 0.4);

EXPECT_EQ(active_tolerances.goal_state_tolerance.size(), 3);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).position, 1.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).velocity, 2.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).acceleration, 3.1);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).position, 1.2);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).velocity, 2.2);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).acceleration, 3.2);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).position, 1.3);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).velocity, 2.3);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).acceleration, 3.3);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, 2.0);

ASSERT_EQ(active_tolerances.state_tolerance.size(), 3);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).position, 0.2);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).velocity, 0.3);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).acceleration, 0.4);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).position, 0.2);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).velocity, 0.3);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).acceleration, 0.4);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).position, 0.2);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).velocity, 0.3);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).acceleration, 0.4);

ASSERT_EQ(active_tolerances.goal_state_tolerance.size(), 3);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).position, 1.1);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).velocity, 2.1);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).acceleration, 3.1);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).position, 1.2);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).velocity, 2.2);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).acceleration, 3.2);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).position, 1.3);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).velocity, 2.3);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).acceleration, 3.3);
}

// send goal without tolerances again, are the default ones used?
Expand Down Expand Up @@ -673,7 +649,8 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, 1.0);
expectDefaultTolerances(active_tolerances);
}

// send goal with deactivated tolerances (-1)
Expand Down Expand Up @@ -719,34 +696,34 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)

auto active_tolerances = traj_controller_->get_active_tolerances();

EXPECT_EQ(active_tolerances.goal_time_tolerance, 0.0);

EXPECT_EQ(active_tolerances.state_tolerance.size(), 3);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).position, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).velocity, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(0).acceleration, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).position, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).velocity, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(1).acceleration, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).position, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).velocity, 0.0);
EXPECT_EQ(active_tolerances.state_tolerance.at(2).acceleration, 0.0);

EXPECT_EQ(active_tolerances.goal_state_tolerance.size(), 3);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).position, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).velocity, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(0).acceleration, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).position, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).velocity, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(1).acceleration, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).position, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).velocity, 0.0);
EXPECT_EQ(active_tolerances.goal_state_tolerance.at(2).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, 0.0);

ASSERT_EQ(active_tolerances.state_tolerance.size(), 3);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).position, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).position, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).position, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).acceleration, 0.0);

ASSERT_EQ(active_tolerances.goal_state_tolerance.size(), 3);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).position, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).position, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).position, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).acceleration, 0.0);
}

// send goal with invalid tolerances, are the default ones used?
// negative path position tolerance
{
SCOPED_TRACE("negative path position tolerance");
SetUpControllerHardware();

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
Expand Down Expand Up @@ -781,10 +758,11 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
expectDefaultTolerances(active_tolerances);
}
// negative path velocity tolerance
{
SCOPED_TRACE("negative path velocity tolerance");
SetUpControllerHardware();

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
Expand Down Expand Up @@ -819,10 +797,11 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
expectDefaultTolerances(active_tolerances);
}
// negative path acceleration tolerance
{
SCOPED_TRACE("negative path acceleration tolerance");
SetUpControllerHardware();

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
Expand Down Expand Up @@ -857,10 +836,11 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
expectDefaultTolerances(active_tolerances);
}
// negative goal position tolerance
{
SCOPED_TRACE("negative goal position tolerance");
SetUpControllerHardware();

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
Expand Down Expand Up @@ -895,10 +875,11 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
expectDefaultTolerances(active_tolerances);
}
// negative goal velocity tolerance
{
SCOPED_TRACE("negative goal velocity tolerance");
SetUpControllerHardware();

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
Expand Down Expand Up @@ -933,10 +914,11 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
expectDefaultTolerances(active_tolerances);
}
// negative goal acceleration tolerance
{
SCOPED_TRACE("negative goal acceleration tolerance");
SetUpControllerHardware();

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
Expand Down Expand Up @@ -971,7 +953,8 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

auto active_tolerances = traj_controller_->get_active_tolerances();
check_default_tolerances(active_tolerances);
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
expectDefaultTolerances(active_tolerances);
}
}

Expand Down
Loading