Skip to content

Commit

Permalink
[JTC] Fix test_tolerances_via_actions (#1209)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jul 16, 2024
1 parent 12b5310 commit 0bb8880
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions joint_trajectory_controller/test/test_tolerances.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,14 @@ using trajectory_msgs::msg::JointTrajectoryPoint;
std::vector<std::string> joint_names_ = {"joint1", "joint2", "joint3"};

control_msgs::action::FollowJointTrajectory_Goal prepareGoalMsg(
const std::vector<JointTrajectoryPoint> & points, double timeout,
const std::vector<JointTrajectoryPoint> & points, double goal_time_tolerance,
const std::vector<control_msgs::msg::JointTolerance> path_tolerance =
std::vector<control_msgs::msg::JointTolerance>(),
const std::vector<control_msgs::msg::JointTolerance> goal_tolerance =
std::vector<control_msgs::msg::JointTolerance>())
{
control_msgs::action::FollowJointTrajectory_Goal goal_msg;
goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(timeout);
goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(goal_time_tolerance);
goal_msg.goal_tolerance = goal_tolerance;
goal_msg.path_tolerance = path_tolerance;
goal_msg.trajectory.joint_names = joint_names_;
Expand Down
11 changes: 5 additions & 6 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,14 +153,15 @@ class TestTrajectoryActions : public TrajectoryControllerTest
using GoalOptions = rclcpp_action::Client<FollowJointTrajectoryMsg>::SendGoalOptions;

std::shared_future<typename GoalHandle::SharedPtr> sendActionGoal(
const std::vector<JointTrajectoryPoint> & points, double timeout, const GoalOptions & opt,
const std::vector<JointTrajectoryPoint> & points, double goal_time_tolerance,
const GoalOptions & opt,
const std::vector<control_msgs::msg::JointTolerance> path_tolerance =
std::vector<control_msgs::msg::JointTolerance>(),
const std::vector<control_msgs::msg::JointTolerance> goal_tolerance =
std::vector<control_msgs::msg::JointTolerance>())
{
control_msgs::action::FollowJointTrajectory_Goal goal_msg;
goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(timeout);
goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(goal_time_tolerance);
goal_msg.goal_tolerance = goal_tolerance;
goal_msg.path_tolerance = path_tolerance;
goal_msg.trajectory.joint_names = joint_names_;
Expand Down Expand Up @@ -529,7 +530,7 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
point.positions[2] = 3.0;
points.push_back(point);

gh_future = sendActionGoal(points, 1.0, goal_options_);
gh_future = sendActionGoal(points, 0.0, goal_options_);
}
controller_hw_thread_.join();

Expand All @@ -539,7 +540,6 @@ 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_DOUBLE_EQ(active_tolerances.goal_time_tolerance, 1.0);
expectDefaultTolerances(active_tolerances);
}

Expand Down Expand Up @@ -639,7 +639,7 @@ TEST_F(TestTrajectoryActions, test_tolerances_via_actions)
point.positions[2] = 3.0;
points.push_back(point);

gh_future = sendActionGoal(points, 1.0, goal_options_);
gh_future = sendActionGoal(points, 0.0, goal_options_);
}
controller_hw_thread_.join();

Expand All @@ -649,7 +649,6 @@ 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_DOUBLE_EQ(active_tolerances.goal_time_tolerance, 1.0);
expectDefaultTolerances(active_tolerances);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ const double stopped_velocity_tolerance = 0.1;
joint_trajectory_controller::SegmentTolerances active_tolerances)
{
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);

// acceleration is never set, and goal_state_tolerance.velocity from stopped_velocity_tolerance

ASSERT_EQ(active_tolerances.state_tolerance.size(), 3);
Expand Down

0 comments on commit 0bb8880

Please sign in to comment.