From a8145aa781aefc42fa87eed803f9f22e06aa2e0f Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 24 Jan 2024 12:56:04 +0000 Subject: [PATCH] Use urdf for compute_error tests --- .../test/test_trajectory_controller.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_controller.cpp b/joint_trajectory_controller/test/test_trajectory_controller.cpp index add88c0680..9ee95427b7 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller.cpp +++ b/joint_trajectory_controller/test/test_trajectory_controller.cpp @@ -471,7 +471,8 @@ TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_tru rclcpp::executors::MultiThreadedExecutor executor; std::vector params = {}; SetUpAndActivateTrajectoryController( - executor, params, true, 0.0, 1.0, true /* angle_wraparound */); + executor, params, true, 0.0, 1.0, INITIAL_POS_JOINTS, INITIAL_VEL_JOINTS, INITIAL_ACC_JOINTS, + INITIAL_EFF_JOINTS, test_trajectory_controllers::urdf_rrrbot_continuous); size_t n_joints = joint_names_.size(); @@ -562,7 +563,8 @@ TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_fal rclcpp::executors::MultiThreadedExecutor executor; std::vector params = {}; SetUpAndActivateTrajectoryController( - executor, params, true, 0.0, 1.0, false /* angle_wraparound */); + executor, params, true, 0.0, 1.0, INITIAL_POS_JOINTS, INITIAL_VEL_JOINTS, INITIAL_ACC_JOINTS, + INITIAL_EFF_JOINTS, test_trajectory_controllers::urdf_rrrbot_revolute); size_t n_joints = joint_names_.size();