41 #include <moveit/task_constructor/stage.h>
42 #include <moveit/task_constructor/solvers/planner_interface.h>
44 #include <moveit_msgs/Constraints.h>
48 MOVEIT_CLASS_FORWARD(RobotState);
53 namespace task_constructor {
70 enum MergeMode : uint8_t
76 using GroupPlannerVector = std::vector<std::pair<std::string, solvers::PlannerInterfacePtr> >;
77 Connect(
const std::string& name =
"connect",
const GroupPlannerVector& planners = {});
79 void setMaxDistance(
double max_distance) {
setProperty(
"max_distance", max_distance); }
80 void setPathConstraints(moveit_msgs::Constraints path_constraints) {
81 setProperty(
"path_constraints", std::move(path_constraints));
84 void reset()
override;
85 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
89 SolutionSequencePtr makeSequential(
const std::vector<robot_trajectory::RobotTrajectoryConstPtr>& sub_trajectories,
90 const std::vector<planning_scene::PlanningSceneConstPtr>& intermediate_scenes,
92 SubTrajectoryPtr merge(
const std::vector<robot_trajectory::RobotTrajectoryConstPtr>& sub_trajectories,
93 const std::vector<planning_scene::PlanningSceneConstPtr>& intermediate_scenes,
94 const moveit::core::RobotState& state);
97 GroupPlannerVector planner_;
98 moveit::core::JointModelGroupPtr merged_jmg_;
99 std::list<SubTrajectory> subsolutions_;
100 std::list<InterfaceState> states_;
void setProperty(const std::string &name, const boost::any &value)
Set a previously declared property to a new value.
Definition: stage.cpp:448
bool compatible(const InterfaceState &from_state, const InterfaceState &to_state) const override
compare consistency of planning scenes
Definition: connect.cpp:107
void init(const moveit::core::RobotModelConstPtr &robot_model) override
Definition: connect.cpp:74
void reset() override
reset stage, clearing all solutions, interfaces, inherited properties.
Definition: connect.cpp:67