41 #include <moveit/task_constructor/solvers/planner_interface.h>
42 #include <moveit/robot_state/cartesian_interpolator.h>
45 namespace task_constructor {
48 MOVEIT_CLASS_FORWARD(CartesianPath);
56 void setIKFrame(
const geometry_msgs::PoseStamped& pose) { setProperty(
"ik_frame", pose); }
57 void setIKFrame(
const Eigen::Isometry3d& pose,
const std::string& link);
58 void setIKFrame(
const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
60 void setStepSize(
double step_size) { setProperty(
"step_size", step_size); }
61 void setPrecision(
const moveit::core::CartesianPrecision& precision) { setProperty(
"precision", precision); }
62 template <
typename T =
float>
63 void setJumpThreshold(
double ) {
64 static_assert(std::is_integral<T>::value,
"setJumpThreshold() is deprecated. Replace with setPrecision.");
66 void setMinFraction(
double min_fraction) { setProperty(
"min_fraction", min_fraction); }
68 [[deprecated(
"Replace with setMaxVelocityScalingFactor")]]
69 void setMaxVelocityScaling(
double factor) { setMaxVelocityScalingFactor(factor); }
70 [[deprecated(
"Replace with setMaxAccelerationScalingFactor")]]
71 void setMaxAccelerationScaling(
double factor) { setMaxAccelerationScalingFactor(factor); }
73 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
75 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const planning_scene::PlanningSceneConstPtr& to,
76 const moveit::core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
77 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
79 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const moveit::core::LinkModel& link,
80 const Eigen::Isometry3d& offset,
const Eigen::Isometry3d& target,
81 const moveit::core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
82 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
Definition: cartesian_path.h:52
Result plan(const planning_scene::PlanningSceneConstPtr &from, const planning_scene::PlanningSceneConstPtr &to, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints()) override
plan trajectory between to robot states
Definition: cartesian_path.cpp:73
Definition: planner_interface.h:69
Definition: planner_interface.h:75