41 #include <moveit/task_constructor/solvers/planner_interface.h>
42 #include <moveit/macros/class_forward.h>
45 namespace task_constructor {
48 MOVEIT_CLASS_FORWARD(JointInterpolationPlanner);
59 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
61 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const planning_scene::PlanningSceneConstPtr& to,
62 const core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
63 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
65 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const moveit::core::LinkModel& link,
66 const Eigen::Isometry3d& offset,
const Eigen::Isometry3d& target,
67 const moveit::core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
68 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
Definition: joint_interpolation.h:55
Definition: planner_interface.h:69
Definition: planner_interface.h:75