Skip to content

Commit

Permalink
Cleanup comments and unnecessary checks (backport #803)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 15, 2023
1 parent 8bc1b29 commit b0ea83f
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -70,15 +70,13 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
JointTrajectoryController();

/**
* @brief command_interface_configuration This controller requires the position command
* interfaces for the controlled joints
* @brief command_interface_configuration
*/
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration command_interface_configuration() const override;

/**
* @brief command_interface_configuration This controller requires the position and velocity
* state interfaces for the controlled joints
* @brief command_interface_configuration
*/
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
Expand Down
18 changes: 1 addition & 17 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -654,17 +654,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
// get parameters from the listener in case they were updated
params_ = param_listener_->get_params();

// Check if the DoF has changed
if ((dof_ > 0) && (params_.joints.size() != dof_))
{
RCLCPP_ERROR(
logger,
"The JointTrajectoryController does not support restarting with a different number of DOF");
// TODO(andyz): update vector lengths if num. joints did change and re-initialize them so we
// can continue
return CallbackReturn::FAILURE;
}

// get degrees of freedom
dof_ = params_.joints.size();

// TODO(destogl): why is this here? Add comment or move
Expand Down Expand Up @@ -694,12 +684,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
return CallbackReturn::FAILURE;
}

// // Specialized, child controllers set interfaces before calling configure function.
// if (command_interface_types_.empty())
// {
// command_interface_types_ = get_node()->get_parameter("command_interfaces").as_string_array();
// }

if (params_.command_interfaces.empty())
{
RCLCPP_ERROR(logger, "'command_interfaces' parameter is empty.");
Expand Down

0 comments on commit b0ea83f

Please sign in to comment.