102 bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
103 size_t num_joints)
override;
113 bool doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations)
override;
122 bool reset(
const Eigen::VectorXd& positions,
const Eigen::VectorXd& velocities,
123 const Eigen::VectorXd& accelerations)
override;
130 if (osqp_workspace_ !=
nullptr)
132 osqp_cleanup(osqp_workspace_);
138 rclcpp::Node::SharedPtr node_;
140 online_signal_smoothing::Params params_;
144 Eigen::VectorXd last_velocities_;
145 Eigen::VectorXd last_positions_;
147 Eigen::VectorXd cur_acceleration_;
148 Eigen::VectorXd positions_offset_;
149 Eigen::VectorXd velocities_offset_;
151 Eigen::VectorXd max_acceleration_limits_;
152 Eigen::VectorXd min_acceleration_limits_;
154 moveit::core::RobotModelConstPtr robot_model_;
156 Eigen::SparseMatrix<double> constraints_sparse_;
158 OSQPDataWrapperPtr osqp_data_;
159 OSQPWorkspace* osqp_workspace_ =
nullptr;
160 OSQPSettings osqp_settings_;