MTC
Public Types | Public Member Functions | Protected Member Functions | List of all members
moveit::task_constructor::Task Class Reference

#include <task.h>

Inheritance diagram for moveit::task_constructor::Task:
Inheritance graph
[legend]
Collaboration diagram for moveit::task_constructor::Task:
Collaboration graph
[legend]

Public Types

using TaskCallback = std::function< void(const Task &t)>
 
using TaskCallbackList = std::list< TaskCallback >
 

Public Member Functions

 Task (const std::string &ns="", bool introspection=true, ContainerBase::pointer &&container=std::make_unique< SerialContainer >("task pipeline"))
 
 Task (Task &&other)
 
Taskoperator= (Task &&other)
 
const std::string & name () const
 
void setName (const std::string &name)
 
StagefindChild (const std::string &name) const
 
Stageoperator[] (int index) const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
void setRobotModel (const moveit::core::RobotModelConstPtr &robot_model)
 setting the robot model also resets the task
 
void loadRobotModel (const std::string &robot_description="robot_description")
 load robot model from given parameter
 
void add (Stage::pointer &&stage)
 
void insert (Stage::pointer &&stage, int before=-1) override
 insertion is only allowed if children() is empty
 
void clear () final
 
void enableIntrospection (bool enable=true)
 enable introspection publishing for use with rviz
 
Introspectionintrospection ()
 
TaskCallbackList::const_iterator addTaskCallback (TaskCallback &&cb)
 add function to be called after each top-level iteration
 
void eraseTaskCallback (TaskCallbackList::const_iterator which)
 remove function callback
 
void reset () final
 reset all stages
 
void init ()
 initialize all stages with given scene
 
moveit::core::MoveItErrorCode plan (size_t max_solutions=0)
 reset, init scene (if not yet done), and init all stages, then start planning
 
void preempt ()
 interrupt current planning
 
void resetPreemptRequest ()
 
moveit::core::MoveItErrorCode execute (const SolutionBase &s)
 execute solution, return the result
 
void printState (std::ostream &os=std::cout) const
 print current task state (number of found solutions and propagated states) to std::cout
 
void explainFailure (std::ostream &os=std::cout) const override
 print an explanation for a planning failure to os
 
size_t numSolutions () const
 
const ordered< SolutionBaseConstPtr > & solutions () const
 
const std::list< SolutionBaseConstPtr > & failures () const
 
void publishAllSolutions (bool wait=true)
 publish all top-level solutions
 
ContainerBasestages ()
 access stage tree
 
const ContainerBasestages () const
 
PropertyMapproperties ()
 properties access
 
const PropertyMapproperties () const
 
void setProperty (const std::string &name, const boost::any &value)
 
void setProperty (const std::string &name, const char *value)
 overload: const char* values are stored as std::string
 

Protected Member Functions

bool canCompute () const override
 
void compute () override
 
void onNewSolution (const SolutionBase &s) override
 called by a (direct) child when a new solution becomes available
 
- Protected Member Functions inherited from moveit::task_constructor::WrapperBase
 WrapperBase (WrapperBasePrivate *impl, Stage::pointer &&child=Stage::pointer())
 
 WrapperBase (const std::string &name="wrapper", Stage::pointer &&child=Stage::pointer())
 
Stagewrapped ()
 access the single wrapped child, NULL if still empty
 
const Stagewrapped () const
 
- Protected Member Functions inherited from moveit::task_constructor::ParallelContainerBase
 ParallelContainerBase (ParallelContainerBasePrivate *impl)
 
void liftSolution (const SolutionBase &solution)
 lift unmodified child solution (useful for simple filtering)
 
void liftSolution (const SolutionBase &solution, double cost)
 lift child solution to external interface, adapting the costs
 
void liftSolution (const SolutionBase &solution, double cost, std::string comment)
 lift child solution to external interface, adapting the costs and comment
 
void spawn (InterfaceState &&state, SubTrajectory &&trajectory)
 spawn a new solution with given state as start and end
 
void sendForward (const InterfaceState &from, InterfaceState &&to, SubTrajectory &&trajectory)
 propagate a solution forwards
 
void sendBackward (InterfaceState &&from, const InterfaceState &to, SubTrajectory &&trajectory)
 propagate a solution backwards
 
 ParallelContainerBase (const std::string &name="parallel container")
 
- Protected Member Functions inherited from moveit::task_constructor::ContainerBase
 ContainerBase (ContainerBasePrivate *impl)
 
void setPruning (bool pruning)
 Explicitly enable/disable pruning.
 
bool pruning () const
 
size_t numChildren () const
 
StagefindChild (const std::string &name) const
 
Stageoperator[] (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 Stage::pointer remove (int pos)
 
virtual Stage::pointer remove (Stage *child)
 
void init (const moveit::core::RobotModelConstPtr &robot_model) override
 
- 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.
 
const ContainerBaseparent () const
 
const std::string & name () const
 
void setName (const std::string &name)
 
uint32_t introspectionId () const
 
Introspectionintrospection () 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!
 
PropertyMapproperties ()
 Get the stage's property map.
 
const PropertyMapproperties () 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
 

Additional Inherited Members

- Protected Types inherited from moveit::task_constructor::ContainerBase
using pointer = std::unique_ptr< ContainerBase >
 
using StageCallback = std::function< bool(const Stage &, unsigned int)>
 
- Protected 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 >
 
- Protected Attributes inherited from moveit::task_constructor::Stage
StagePrivate * pimpl_
 

Detailed Description

A Task is the root of a tree of stages.

Actually a tasks wraps a single container (by default a SerialContainer), which serves as the root of all stages.


The documentation for this class was generated from the following files: