36 #include <moveit/task_constructor/container.h>
39 namespace task_constructor {
50 LimitSolutions(
const std::string& name =
"LimitSolutions", Stage::pointer&& child = Stage::pointer());
52 void reset()
override;
53 bool canCompute()
const override;
54 void compute()
override;
57 void setMaxSolutions(uint32_t max_solutions) {
setProperty(
"max_solutions", max_solutions); }
61 uint32_t forwarded_solutions;
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: container.h:214
Definition: limit_solutions.h:48
void onNewSolution(const SolutionBase &s) override
called by a (direct) child when a new solution becomes available
Definition: limit_solutions.cpp:56
void reset() override
reset stage, clearing all solutions, interfaces, inherited properties.
Definition: limit_solutions.cpp:50
ordered<ValueType> provides an adapter for a std::list to allow sorting.
Definition: cost_queue.h:30