41 #include <rclcpp/rclcpp.hpp>
44 #include <moveit_smoothing_base_export.h>
69 virtual bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
70 size_t num_joints) = 0;
77 virtual bool doSmoothing(std::vector<double>& position_vector) = 0;
84 virtual bool reset(
const std::vector<double>& joint_positions) = 0;
virtual bool doSmoothing(std::vector< double > &position_vector)=0
virtual bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model, size_t num_joints)=0
virtual bool reset(const std::vector< double > &joint_positions)=0
virtual ~SmoothingBaseClass()
MOVEIT_CLASS_FORWARD(JointModelGroup)
Main namespace for MoveIt.