41 #include <rclcpp/rclcpp.hpp>
44 #include <moveit_smoothing_base_export.h>
46 #include <Eigen/Dense>
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;
virtual bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model, size_t num_joints)=0
virtual bool doSmoothing(Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations)=0
virtual bool reset(const Eigen::VectorXd &positions, const Eigen::VectorXd &velocities, const Eigen::VectorXd &accelerations)=0
virtual ~SmoothingBaseClass()
MOVEIT_CLASS_FORWARD(JointModelGroup)
Main namespace for MoveIt.