diff --git a/moveit_planners/pilz_industrial_motion_planner/package.xml b/moveit_planners/pilz_industrial_motion_planner/package.xml
index d4065026ae..81f00c8268 100644
--- a/moveit_planners/pilz_industrial_motion_planner/package.xml
+++ b/moveit_planners/pilz_industrial_motion_planner/package.xml
@@ -30,9 +30,6 @@
moveit_core
moveit_ros_planning
moveit_ros_move_group
-
liborocos-kdl-dev
pluginlib
rclcpp
diff --git a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp
index 8099652140..72022011c0 100644
--- a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp
+++ b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp
@@ -60,12 +60,10 @@ CommandListManager::CommandListManager(const rclcpp::Node::SharedPtr& node,
// Obtain the aggregated joint limits
pilz_industrial_motion_planner::JointLimitsContainer aggregated_limit_active_joints;
- // TODO(henning): pass PARAM_NAMESPACE_LIMITS
aggregated_limit_active_joints = pilz_industrial_motion_planner::JointLimitsAggregator::getAggregatedLimits(
node_, PARAM_NAMESPACE_LIMITS, model_->getActiveJointModels());
// Obtain cartesian limits
- // TODO(henning): pass PARAM_NAMESPACE_LIMITS
pilz_industrial_motion_planner::CartesianLimit cartesian_limit =
pilz_industrial_motion_planner::CartesianLimitsAggregator::getAggregatedLimits(node_, PARAM_NAMESPACE_LIMITS);