41 #include <moveit/task_constructor/stage.h>
44 namespace task_constructor {
51 FixedState(
const std::string& name =
"initial state", planning_scene::PlanningScenePtr scene =
nullptr);
52 void setState(
const planning_scene::PlanningScenePtr& scene);
54 void setIgnoreCollisions(
bool ignore) {
setProperty(
"ignore_collisions", ignore); }
56 void reset()
override;
57 bool canCompute()
const override;
58 void compute()
override;
61 planning_scene::PlanningScenePtr scene_;
void setProperty(const std::string &name, const boost::any &value)
Set a previously declared property to a new value.
Definition: stage.cpp:448
Definition: fixed_state.h:49
void reset() override
reset stage, clearing all solutions, interfaces, inherited properties.
Definition: fixed_state.cpp:56