MTC
|
#include <container.h>
Public Types | |
using | pointer = std::unique_ptr< ContainerBase > |
using | StageCallback = std::function< bool(const Stage &, unsigned int)> |
Public Types inherited from moveit::task_constructor::Stage | |
enum | PropertyInitializerSource : uint8_t { DEFAULT = 0 , MANUAL = 1 , PARENT = 2 , INTERFACE = 4 } |
using | pointer = std::unique_ptr< Stage > |
using | SolutionCallback = std::function< void(const SolutionBase &)> |
using | SolutionCallbackList = std::list< SolutionCallback > |
Public Member Functions | |
void | setPruning (bool pruning) |
Explicitly enable/disable pruning. | |
bool | pruning () const |
size_t | numChildren () const |
Stage * | findChild (const std::string &name) const |
Stage * | operator[] (int index) const |
bool | traverseChildren (const StageCallback &processor) const |
traverse direct children of this container, calling the callback for each of them | |
bool | traverseRecursively (const StageCallback &processor) const |
traverse all children of this container recursively | |
void | add (Stage::pointer &&stage) |
virtual void | insert (Stage::pointer &&stage, int before=-1) |
virtual Stage::pointer | remove (int pos) |
virtual Stage::pointer | remove (Stage *child) |
virtual void | clear () |
void | reset () override |
reset stage, clearing all solutions, interfaces, inherited properties. | |
void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
virtual bool | canCompute () const =0 |
virtual void | compute ()=0 |
void | explainFailure (std::ostream &os) const override |
virtual void | onNewSolution (const SolutionBase &s)=0 |
called by a (direct) child when a new solution becomes available | |
Public Member Functions inherited from moveit::task_constructor::Stage | |
const ContainerBase * | parent () const |
const std::string & | name () const |
void | setName (const std::string &name) |
uint32_t | introspectionId () const |
Introspection * | introspection () const |
void | setTimeout (double timeout) |
double | timeout () const |
timeout of stage per computation | |
void | setMarkerNS (const std::string &marker_ns) |
const std::string & | markerNS () |
marker namespace of solution markers | |
void | setTrajectoryExecutionInfo (TrajectoryExecutionInfo trajectory_execution_info) |
Set and get info to use when executing the stage's trajectory. | |
TrajectoryExecutionInfo | trajectoryExecutionInfo () const |
void | forwardProperties (const InterfaceState &source, InterfaceState &dest) |
forwarding of properties between interface states | |
std::set< std::string > | forwardedProperties () const |
void | setForwardedProperties (const std::set< std::string > &names) |
SolutionCallbackList::const_iterator | addSolutionCallback (SolutionCallback &&cb) |
add function to be called for every newly found solution or failure | |
void | removeSolutionCallback (SolutionCallbackList::const_iterator which) |
remove function callback | |
void | setCostTerm (const CostTermConstPtr &term) |
template<typename T , typename = std::enable_if_t<std::is_constructible<LambdaCostTerm, T>::value>> | |
void | setCostTerm (T term) |
const ordered< SolutionBaseConstPtr > & | solutions () const |
const std::list< SolutionBaseConstPtr > & | failures () const |
size_t | numFailures () const |
void | silentFailure () |
Call to increase number of failures w/o storing a (failure) trajectory. | |
bool | storeFailures () const |
Should we generate failure solutions? Note: Always report a failure! | |
PropertyMap & | properties () |
Get the stage's property map. | |
const PropertyMap & | properties () const |
void | setProperty (const std::string &name, const boost::any &value) |
Set a previously declared property to a new value. | |
void | setProperty (const std::string &name, const char *value) |
overload: const char* values are stored as std::string | |
void | reportPropertyError (const Property::error &e) |
Analyze source of error and report accordingly. | |
double | getTotalComputeTime () const |
Protected Member Functions | |
ContainerBase (ContainerBasePrivate *impl) | |
Protected Member Functions inherited from moveit::task_constructor::Stage | |
Stage (StagePrivate *impl) | |
Stage can only be instantiated through derived classes. | |
Stage (const Stage &)=delete | |
Stage cannot be copied. | |
Additional Inherited Members | |
Protected Attributes inherited from moveit::task_constructor::Stage | |
StagePrivate * | pimpl_ |
Base class for all container stages, i.e. ones that have one or more children
using moveit::task_constructor::ContainerBase::StageCallback = std::function<bool(const Stage&, unsigned int)> |
Callback function type used by traverse functions Receives currently visited Stage and current depth in hierarchy If callback returns false, traversal is stopped.
|
overridevirtual |
initialize stage once before planning
When called, properties configured for initialization from parent are already defined. Push interfaces are not yet defined!
Reimplemented from moveit::task_constructor::Stage.
Reimplemented in moveit::task_constructor::stages::SimpleGraspBase, moveit::task_constructor::stages::PredicateFilter, moveit::task_constructor::stages::PickPlaceBase, and moveit::task_constructor::Fallbacks.