41 #include <moveit/task_constructor/stage.h>
42 #include <moveit/task_constructor/cost_queue.h>
43 #include <geometry_msgs/PoseStamped.h>
46 namespace task_constructor {
54 void reset()
override;
55 bool canCompute()
const override;
56 void compute()
override;
58 void setPose(
const geometry_msgs::PoseStamped& pose) {
setProperty(
"pose", pose); }
abstract base class for solutions (primitive and sequences)
Definition: storage.h:269
void setProperty(const std::string &name, const boost::any &value)
Set a previously declared property to a new value.
Definition: stage.cpp:443
Definition: generate_pose.h:50
void reset() override
reset stage, clearing all solutions, interfaces, inherited properties.
Definition: generate_pose.cpp:56
void onNewSolution(const SolutionBase &s) override
called by monitored stage when a new solution was generated
Definition: generate_pose.cpp:61
ordered<ValueType> provides an adapter for a std::list to allow sorting.
Definition: cost_queue.h:30