101 bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
102 size_t num_joints)
override;
111 bool doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations)
override;
120 bool reset(
const Eigen::VectorXd& positions,
const Eigen::VectorXd& velocities,
121 const Eigen::VectorXd& accelerations)
override;
124 rclcpp::Node::SharedPtr node_;
125 std::vector<ButterworthFilter> position_filters_;