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 addPose(
const geometry_msgs::PoseStamped& pose);
abstract base class for solutions (primitive and sequences)
Definition: storage.h:269
Definition: fixed_cartesian_poses.h:50
void onNewSolution(const SolutionBase &s) override
called by monitored stage when a new solution was generated
Definition: fixed_cartesian_poses.cpp:71
void reset() override
reset stage, clearing all solutions, interfaces, inherited properties.
Definition: fixed_cartesian_poses.cpp:66
ordered<ValueType> provides an adapter for a std::list to allow sorting.
Definition: cost_queue.h:30