diff --git a/joint_trajectory_controller/package.xml b/joint_trajectory_controller/package.xml index b41a7cad0c..70d9bd51d2 100644 --- a/joint_trajectory_controller/package.xml +++ b/joint_trajectory_controller/package.xml @@ -4,29 +4,24 @@ 4.1.0 Controller for executing joint-space trajectories on a group of joints Bence Magyar - Jordan Palacios - Karsten Knese + Dr. Denis Štogl + Christoph Froehlich Apache License 2.0 ament_cmake - angles - pluginlib - realtime_tools - - angles - pluginlib - realtime_tools - + angles backward_ros controller_interface control_msgs control_toolbox generate_parameter_library hardware_interface + pluginlib rclcpp rclcpp_lifecycle + realtime_tools rsl tl_expected trajectory_msgs diff --git a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp index 4a65b4ad51..7b68d882ff 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp +++ b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp @@ -215,7 +215,7 @@ class TrajectoryControllerTest : public ::testing::Test } void SetPidParameters( - double p_default = 0.0, double ff_default = 1.0, bool angle_wraparound_default = false) + double p_value = 0.0, double ff_value = 1.0, bool angle_wraparound_value = false) { traj_controller_->trigger_declare_parameters(); auto node = traj_controller_->get_node(); @@ -223,13 +223,13 @@ class TrajectoryControllerTest : public ::testing::Test for (size_t i = 0; i < joint_names_.size(); ++i) { const std::string prefix = "gains." + joint_names_[i]; - const rclcpp::Parameter k_p(prefix + ".p", p_default); + const rclcpp::Parameter k_p(prefix + ".p", p_value); const rclcpp::Parameter k_i(prefix + ".i", 0.0); const rclcpp::Parameter k_d(prefix + ".d", 0.0); const rclcpp::Parameter i_clamp(prefix + ".i_clamp", 0.0); - const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", ff_default); + const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", ff_value); const rclcpp::Parameter angle_wraparound( - prefix + ".angle_wraparound", angle_wraparound_default); + prefix + ".angle_wraparound", angle_wraparound_value); node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale, angle_wraparound}); } }