41 #include <moveit/macros/class_forward.h>
42 #include <moveit_msgs/Constraints.h>
43 #include <moveit/task_constructor/properties.h>
44 #include <Eigen/Geometry>
46 namespace planning_scene {
47 MOVEIT_CLASS_FORWARD(PlanningScene);
49 namespace robot_trajectory {
50 MOVEIT_CLASS_FORWARD(RobotTrajectory);
52 namespace trajectory_processing {
53 MOVEIT_CLASS_FORWARD(TimeParameterization);
57 MOVEIT_CLASS_FORWARD(LinkModel);
58 MOVEIT_CLASS_FORWARD(RobotModel);
59 MOVEIT_CLASS_FORWARD(JointModelGroup);
64 namespace task_constructor {
67 MOVEIT_CLASS_FORWARD(PlannerInterface);
79 operator bool()
const {
return success; }
86 const PropertyMap& properties()
const {
return properties_; }
88 void setProperty(
const std::string& name,
const boost::any& value) { properties_.
set(name, value); }
89 void setTimeout(
double timeout) { properties_.
set(
"timeout", timeout); }
90 void setMaxVelocityScalingFactor(
double factor) { properties_.
set(
"max_velocity_scaling_factor", factor); }
91 void setMaxAccelerationScalingFactor(
double factor) { properties_.
set(
"max_acceleration_scaling_factor", factor); }
92 void setTimeParameterization(
const trajectory_processing::TimeParameterizationPtr& tp) {
93 properties_.
set(
"time_parameterization", tp);
96 virtual void init(
const moveit::core::RobotModelConstPtr& robot_model) = 0;
99 virtual Result plan(
const planning_scene::PlanningSceneConstPtr& from,
100 const planning_scene::PlanningSceneConstPtr& to,
const moveit::core::JointModelGroup* jmg,
101 double timeout, robot_trajectory::RobotTrajectoryPtr& result,
102 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) = 0;
105 virtual Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const moveit::core::LinkModel& link,
106 const Eigen::Isometry3d& offset,
const Eigen::Isometry3d& target,
107 const moveit::core::JointModelGroup* jmg,
double timeout,
108 robot_trajectory::RobotTrajectoryPtr& result,
109 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) = 0;
Definition: properties.h:257
void set(const std::string &name, const T &value)
set (and, if neccessary, declare) the value of a property
Definition: properties.h:304
Definition: planner_interface.h:69
virtual Result plan(const planning_scene::PlanningSceneConstPtr &from, const moveit::core::LinkModel &link, const Eigen::Isometry3d &offset, const Eigen::Isometry3d &target, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints())=0
plan trajectory from current robot state to Cartesian target, such that pose(link)*offset == target
virtual 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())=0
plan trajectory between to robot states
Definition: planner_interface.h:75