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]

Public Types

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

Public Member Functions

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

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 More...
 
- Protected Member Functions inherited from moveit::task_constructor::WrapperBase
 WrapperBase (WrapperBasePrivate *impl, Stage::pointer &&child=Stage::pointer())
 
Stagewrapped ()
 access the single wrapped child, NULL if still empty More...
 
const Stagewrapped () const
 
 WrapperBase (const std::string &name="wrapper", 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...
 
 ParallelContainerBase (const std::string &name="parallel container")
 
- Protected Member Functions inherited from moveit::task_constructor::ContainerBase
 ContainerBase (ContainerBasePrivate *impl)
 
void add (Stage::pointer &&stage)
 
StagefindChild (const std::string &name) const
 
void init (const moveit::core::RobotModelConstPtr &robot_model) override
 
size_t numChildren () const
 
Stageoperator[] (int index) const
 
bool pruning () const
 
virtual Stage::pointer remove (int pos)
 
virtual Stage::pointer remove (Stage *child)
 
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...
 
- 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...
 
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
 
Introspectionintrospection () 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 ContainerBaseparent () const
 
PropertyMapproperties ()
 Get the stage's property map. More...
 
const PropertyMapproperties () 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 ()
 

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
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_
 

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.

Definition at line 72 of file task.h.

Member Typedef Documentation

◆ TaskCallback

using moveit::task_constructor::Task::TaskCallback = std::function<void(const Task& t)>

Definition at line 105 of file task.h.

◆ TaskCallbackList

Definition at line 106 of file task.h.

Constructor & Destructor Documentation

◆ Task() [1/2]

moveit::task_constructor::Task::Task ( const std::string &  ns = "",
bool  introspection = true,
ContainerBase::pointer &&  container = std::make_unique<SerialContainer>("task pipeline") 
)

Definition at line 95 of file task.cpp.

◆ Task() [2/2]

moveit::task_constructor::Task::Task ( Task &&  other)

Definition at line 107 of file task.cpp.

◆ ~Task()

moveit::task_constructor::Task::~Task ( )
override

Definition at line 118 of file task.cpp.

Member Function Documentation

◆ add()

void moveit::task_constructor::Task::add ( Stage::pointer &&  stage)

Definition at line 146 of file task.cpp.

◆ addTaskCallback()

Task::TaskCallbackList::const_iterator moveit::task_constructor::Task::addTaskCallback ( TaskCallback &&  cb)

add function to be called after each top-level iteration

Definition at line 182 of file task.cpp.

◆ canCompute()

bool moveit::task_constructor::Task::canCompute ( ) const
overrideprotectedvirtual

Reimplemented from moveit::task_constructor::WrapperBase.

Definition at line 231 of file task.cpp.

◆ clear()

void moveit::task_constructor::Task::clear ( )
finalvirtual

Reimplemented from moveit::task_constructor::ContainerBase.

Definition at line 154 of file task.cpp.

◆ compute()

void moveit::task_constructor::Task::compute ( )
overrideprotectedvirtual

Reimplemented from moveit::task_constructor::WrapperBase.

Definition at line 235 of file task.cpp.

◆ enableIntrospection()

void moveit::task_constructor::Task::enableIntrospection ( bool  enable = true)

enable introspection publishing for use with rviz

Definition at line 159 of file task.cpp.

◆ eraseTaskCallback()

void moveit::task_constructor::Task::eraseTaskCallback ( TaskCallbackList::const_iterator  which)

remove function callback

Definition at line 188 of file task.cpp.

◆ execute()

moveit::core::MoveItErrorCode moveit::task_constructor::Task::execute ( const SolutionBase s)

execute solution, return the result

Definition at line 282 of file task.cpp.

◆ explainFailure()

bool moveit::task_constructor::Task::explainFailure ( std::ostream &  os = std::cout) const
overridevirtual

print an explanation for a planning failure to os

Reimplemented from moveit::task_constructor::ContainerBase.

Definition at line 336 of file task.cpp.

◆ failures()

const std::list<SolutionBaseConstPtr>& moveit::task_constructor::Task::failures ( ) const
inline

Definition at line 144 of file task.h.

◆ findChild()

Stage* moveit::task_constructor::Task::findChild ( const std::string &  name) const
inline

Definition at line 88 of file task.h.

◆ getRobotModel()

const core::RobotModelConstPtr & moveit::task_constructor::Task::getRobotModel ( ) const

Definition at line 327 of file task.cpp.

◆ init()

void moveit::task_constructor::Task::init ( )

initialize all stages with given scene

Definition at line 201 of file task.cpp.

◆ insert()

void moveit::task_constructor::Task::insert ( Stage::pointer &&  stage,
int  before = -1 
)
overridevirtual

insertion is only allowed if children() is empty

Reimplemented from moveit::task_constructor::WrapperBase.

Definition at line 150 of file task.cpp.

◆ introspection()

Introspection & moveit::task_constructor::Task::introspection ( )

Definition at line 176 of file task.cpp.

◆ loadRobotModel()

void moveit::task_constructor::Task::loadRobotModel ( const std::string &  robot_description = "robot_description")

load robot model from given parameter

Definition at line 138 of file task.cpp.

◆ name()

const std::string& moveit::task_constructor::Task::name ( ) const
inline

Definition at line 85 of file task.h.

◆ numSolutions()

size_t moveit::task_constructor::Task::numSolutions ( ) const
inline

Definition at line 142 of file task.h.

◆ onNewSolution()

void moveit::task_constructor::Task::onNewSolution ( const SolutionBase s)
overrideprotectedvirtual

called by a (direct) child when a new solution becomes available

Implements moveit::task_constructor::ContainerBase.

Definition at line 302 of file task.cpp.

◆ operator=()

Task & moveit::task_constructor::Task::operator= ( Task &&  other)

Definition at line 112 of file task.cpp.

◆ operator[]()

Stage* moveit::task_constructor::Task::operator[] ( int  index) const
inline

Definition at line 89 of file task.h.

◆ plan()

moveit::core::MoveItErrorCode moveit::task_constructor::Task::plan ( size_t  max_solutions = 0)

reset, init scene (if not yet done), and init all stages, then start planning

Definition at line 243 of file task.cpp.

◆ preempt()

void moveit::task_constructor::Task::preempt ( )

interrupt current planning

Definition at line 274 of file task.cpp.

◆ printState()

void moveit::task_constructor::Task::printState ( std::ostream &  os = std::cout) const

print current task state (number of found solutions and propagated states) to std::cout

Definition at line 332 of file task.cpp.

◆ properties() [1/2]

PropertyMap & moveit::task_constructor::Task::properties ( )

properties access

Definition at line 317 of file task.cpp.

◆ properties() [2/2]

const PropertyMap& moveit::task_constructor::Task::properties ( ) const
inline

Definition at line 156 of file task.h.

◆ publishAllSolutions()

void moveit::task_constructor::Task::publishAllSolutions ( bool  wait = true)

publish all top-level solutions

Definition at line 297 of file task.cpp.

◆ reset()

void moveit::task_constructor::Task::reset ( )
finalvirtual

reset all stages

Reimplemented from moveit::task_constructor::ContainerBase.

Definition at line 192 of file task.cpp.

◆ resetPreemptRequest()

void moveit::task_constructor::Task::resetPreemptRequest ( )

Definition at line 278 of file task.cpp.

◆ setName()

void moveit::task_constructor::Task::setName ( const std::string &  name)
inline

Definition at line 86 of file task.h.

◆ setProperty() [1/2]

void moveit::task_constructor::Task::setProperty ( const std::string &  name,
const boost::any &  value 
)

Definition at line 322 of file task.cpp.

◆ setProperty() [2/2]

void moveit::task_constructor::Task::setProperty ( const std::string &  name,
const char *  value 
)
inline

overload: const char* values are stored as std::string

Definition at line 159 of file task.h.

◆ setRobotModel()

void moveit::task_constructor::Task::setRobotModel ( const moveit::core::RobotModelConstPtr &  robot_model)

setting the robot model also resets the task

Definition at line 127 of file task.cpp.

◆ solutions()

const ordered<SolutionBaseConstPtr>& moveit::task_constructor::Task::solutions ( ) const
inline

Definition at line 143 of file task.h.

◆ stages() [1/2]

const ContainerBase * moveit::task_constructor::Task::stages ( )

access stage tree

Definition at line 309 of file task.cpp.

◆ stages() [2/2]

const ContainerBase* moveit::task_constructor::Task::stages ( ) const

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


core
Author(s):
autogenerated on Sat May 3 2025 02:40:11