62 bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
63 size_t num_joints)
override;
72 bool doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations)
override;
81 bool reset(
const Eigen::VectorXd& positions,
const Eigen::VectorXd& velocities,
82 const Eigen::VectorXd& accelerations)
override;
88 void printRuckigState();
94 bool getVelAccelJerkBounds(std::vector<double>& joint_velocity_bounds, std::vector<double>& joint_acceleration_bounds,
95 std::vector<double>& joint_jerk_bounds);
98 online_signal_smoothing::Params params_;
100 moveit::core::RobotModelConstPtr robot_model_;
101 bool have_initial_ruckig_output_ =
false;
102 std::optional<ruckig::Ruckig<ruckig::DynamicDOFs>> ruckig_;
103 std::optional<ruckig::InputParameter<ruckig::DynamicDOFs>> ruckig_input_;
104 std::optional<ruckig::OutputParameter<ruckig::DynamicDOFs>> ruckig_output_;