Skip to content

Commit

Permalink
Cleanup package.xml und clarify tests of JTC. (#889) (#925)
Browse files Browse the repository at this point in the history
  • Loading branch information
mergify[bot] committed Dec 12, 2023
1 parent cbc7439 commit 6f6f389
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 14 deletions.
15 changes: 5 additions & 10 deletions joint_trajectory_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,29 +4,24 @@
<version>3.19.1</version>
<description>Controller for executing joint-space trajectories on a group of joints</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="jordan.palacios@pal-robotics.com">Jordan Palacios</maintainer>
<maintainer email="karsten@openrobotics.org">Karsten Knese</maintainer>
<maintainer email="denis.stogl@stoglrobotics.de">Dr. Denis Štogl</maintainer>
<maintainer email="christoph.froehlich@ait.ac.at">Christoph Froehlich</maintainer>

<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>angles</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>realtime_tools</build_depend>

<exec_depend>angles</exec_depend>
<exec_depend>pluginlib</exec_depend>
<exec_depend>realtime_tools</exec_depend>

<depend>angles</depend>
<depend>backward_ros</depend>
<depend>controller_interface</depend>
<depend>control_msgs</depend>
<depend>control_toolbox</depend>
<depend>generate_parameter_library</depend>
<depend>hardware_interface</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>realtime_tools</depend>
<depend>rsl</depend>
<depend>tl_expected</depend>
<depend>trajectory_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -215,21 +215,21 @@ 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();

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});
}
}
Expand Down

0 comments on commit 6f6f389

Please sign in to comment.