Skip to content

Commit

Permalink
Use urdf for compute_error tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 24, 2024
1 parent 40463d9 commit a8145aa
Showing 1 changed file with 4 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -471,7 +471,8 @@ TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_tru
rclcpp::executors::MultiThreadedExecutor executor;
std::vector<rclcpp::Parameter> 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();

Expand Down Expand Up @@ -562,7 +563,8 @@ TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_fal
rclcpp::executors::MultiThreadedExecutor executor;
std::vector<rclcpp::Parameter> 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();

Expand Down

0 comments on commit a8145aa

Please sign in to comment.