#include <container.h>

Public Member Functions | |
| bool | canCompute () const override |
| void | compute () override |
| void | insert (Stage::pointer &&stage, int before=-1) override |
| insertion is only allowed if children() is empty More... | |
| Stage * | wrapped () |
| access the single wrapped child, NULL if still empty More... | |
| const Stage * | wrapped () const |
| WrapperBase (const std::string &name="wrapper", Stage::pointer &&child=Stage::pointer()) | |
Public Member Functions inherited from moveit::task_constructor::ParallelContainerBase | |
| ParallelContainerBase (const std::string &name="parallel container") | |
Public Member Functions inherited from moveit::task_constructor::ContainerBase | |
| void | add (Stage::pointer &&stage) |
| virtual void | clear () |
| bool | explainFailure (std::ostream &os) const override |
| Stage * | findChild (const std::string &name) const |
| void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
| size_t | numChildren () const |
| virtual void | onNewSolution (const SolutionBase &s)=0 |
| called by a (direct) child when a new solution becomes available More... | |
| Stage * | operator[] (int index) const |
| bool | pruning () const |
| virtual Stage::pointer | remove (int pos) |
| virtual Stage::pointer | remove (Stage *child) |
| void | reset () override |
| reset stage, clearing all solutions, interfaces, inherited properties. More... | |
| void | setPruning (bool pruning) |
| Explicitly enable/disable pruning. More... | |
| bool | traverseChildren (const StageCallback &processor) const |
| traverse direct children of this container, calling the callback for each of them More... | |
| bool | traverseRecursively (const StageCallback &processor) const |
| traverse all children of this container recursively More... | |
Public Member Functions inherited from moveit::task_constructor::Stage | |
| SolutionCallbackList::const_iterator | addSolutionCallback (SolutionCallback &&cb) |
| add function to be called for every newly found solution or failure More... | |
| const std::list< SolutionBaseConstPtr > & | failures () const |
| std::set< std::string > | forwardedProperties () const |
| void | forwardProperties (const InterfaceState &source, InterfaceState &dest) |
| forwarding of properties between interface states More... | |
| double | getTotalComputeTime () const |
| Introspection * | introspection () const |
| uint32_t | introspectionId () const |
| const std::string & | markerNS () |
| marker namespace of solution markers More... | |
| const std::string & | name () const |
| size_t | numFailures () const |
| const ContainerBase * | parent () const |
| PropertyMap & | properties () |
| Get the stage's property map. More... | |
| const PropertyMap & | properties () const |
| void | removeSolutionCallback (SolutionCallbackList::const_iterator which) |
| remove function callback More... | |
| void | reportPropertyError (const Property::error &e) |
| Analyze source of error and report accordingly. More... | |
| void | setCostTerm (const CostTermConstPtr &term) |
| template<typename T , typename = std::enable_if_t<std::is_constructible<LambdaCostTerm, T>::value>> | |
| void | setCostTerm (T term) |
| void | setForwardedProperties (const std::set< std::string > &names) |
| void | setMarkerNS (const std::string &marker_ns) |
| void | setName (const std::string &name) |
| void | setProperty (const std::string &name, const boost::any &value) |
| Set a previously declared property to a new value. More... | |
| void | setProperty (const std::string &name, const char *value) |
| overload: const char* values are stored as std::string More... | |
| void | setTimeout (double timeout) |
| void | setTrajectoryExecutionInfo (TrajectoryExecutionInfo trajectory_execution_info) |
| Set and get info to use when executing the stage's trajectory. More... | |
| void | silentFailure () |
| Call to increase number of failures w/o storing a (failure) trajectory. More... | |
| const ordered< SolutionBaseConstPtr > & | solutions () const |
| bool | storeFailures () const |
| Should we generate failure solutions? Note: Always report a failure! More... | |
| double | timeout () const |
| timeout of stage per computation More... | |
| TrajectoryExecutionInfo | trajectoryExecutionInfo () const |
| virtual | ~Stage () |
Protected Member Functions | |
| WrapperBase (WrapperBasePrivate *impl, Stage::pointer &&child=Stage::pointer()) | |
Protected Member Functions inherited from moveit::task_constructor::ParallelContainerBase | |
| void | liftSolution (const SolutionBase &solution) |
| lift unmodified child solution (useful for simple filtering) More... | |
| void | liftSolution (const SolutionBase &solution, double cost) |
| lift child solution to external interface, adapting the costs More... | |
| void | liftSolution (const SolutionBase &solution, double cost, std::string comment) |
| lift child solution to external interface, adapting the costs and comment More... | |
| ParallelContainerBase (ParallelContainerBasePrivate *impl) | |
| void | sendBackward (InterfaceState &&from, const InterfaceState &to, SubTrajectory &&trajectory) |
| propagate a solution backwards More... | |
| void | sendForward (const InterfaceState &from, InterfaceState &&to, SubTrajectory &&trajectory) |
| propagate a solution forwards More... | |
| void | spawn (InterfaceState &&state, SubTrajectory &&trajectory) |
| spawn a new solution with given state as start and end More... | |
Protected Member Functions inherited from moveit::task_constructor::ContainerBase | |
| ContainerBase (ContainerBasePrivate *impl) | |
Protected Member Functions inherited from moveit::task_constructor::Stage | |
| Stage (const Stage &)=delete | |
| Stage cannot be copied. More... | |
| Stage (StagePrivate *impl) | |
| Stage can only be instantiated through derived classes. More... | |
Additional Inherited Members | |
Public Types inherited from moveit::task_constructor::ContainerBase | |
| using | pointer = std::unique_ptr< ContainerBase > |
| using | StageCallback = std::function< bool(const Stage &, unsigned int)> |
Public Types inherited from moveit::task_constructor::Stage | |
| using | pointer = std::unique_ptr< Stage > |
| enum | PropertyInitializerSource : uint8_t { DEFAULT = 0, MANUAL = 1, PARENT = 2, INTERFACE = 4 } |
| using | SolutionCallback = std::function< void(const SolutionBase &)> |
| using | SolutionCallbackList = std::list< SolutionCallback > |
Protected Attributes inherited from moveit::task_constructor::Stage | |
| StagePrivate * | pimpl_ |
A wrapper wraps a single child stage, which can be accessed via wrapped().
Implementations of this interface need to implement onNewSolution(), which is called when the child has generated a new solution. The wrapper may reject the solution or create one or multiple derived solutions, potentially adapting the cost, as well as its start and end states.
Definition at line 277 of file container.h.
| moveit::task_constructor::WrapperBase::WrapperBase | ( | const std::string & | name = "wrapper", |
| Stage::pointer && | child = Stage::pointer() |
||
| ) |
Definition at line 821 of file container.cpp.
|
protected |
Definition at line 824 of file container.cpp.
|
overridevirtual |
Implements moveit::task_constructor::ContainerBase.
Reimplemented in moveit::task_constructor::Task, and moveit::task_constructor::stages::ComputeIK.
Definition at line 840 of file container.cpp.
|
overridevirtual |
Implements moveit::task_constructor::ContainerBase.
Reimplemented in moveit::task_constructor::Task, and moveit::task_constructor::stages::ComputeIK.
Definition at line 844 of file container.cpp.
|
overridevirtual |
insertion is only allowed if children() is empty
Reimplemented from moveit::task_constructor::ContainerBase.
Reimplemented in moveit::task_constructor::Task.
Definition at line 829 of file container.cpp.
| Stage * moveit::task_constructor::WrapperBase::wrapped | ( | ) |
access the single wrapped child, NULL if still empty
Definition at line 836 of file container.cpp.
|
inline |
Definition at line 288 of file container.h.