71 virtual bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
72 size_t num_joints) = 0;
81 virtual bool doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations) = 0;
90 virtual bool reset(
const Eigen::VectorXd& positions,
const Eigen::VectorXd& velocities,
91 const Eigen::VectorXd& accelerations) = 0;