Task Class Reference

#include <RobotComponents/components/MotionPlanning/Tasks/RRTConnect/Task.h>

+ Inheritance diagram for Task:

Public Member Functions

void abortTask (const Ice::Current &=Ice::emptyCurrent) override
 Aborts planning. More...
 
Path getPath (const Ice::Current &=Ice::emptyCurrent) const override
 
void postEnqueueing () override
 Called by the planning server after the task was enqueued. More...
 
void run (const RemoteObjectNodePrxList &remoteNodes, const Ice::Current &=Ice::emptyCurrent) override
 Runs the task. More...
 
void setPath (const Path &path, const Ice::Current &=Ice::emptyCurrent) override
 
 Task (const CSpaceBasePtr &cspace, const VectorXf &startCfg, const VectorXf &goalCfg, const std::string &taskName="RRTConnectTask", Ice::Long maximalPlanningTimeInSeconds=300, float dcdStep=0.01f, Ice::Long workerCount=4)
 A task using the rrtconnect algorithm. More...
 
void workerHasAborted (Ice::Long workerId, const Ice::Current &=Ice::emptyCurrent) override
 
- Public Member Functions inherited from MotionPlanningTaskWithDefaultMembers
CSpaceBasePtr getCSpace (const Ice::Current &=Ice::emptyCurrent) const override
 
float getDcdStep (const Ice::Current &=Ice::emptyCurrent) const override
 
VectorXf getGoal (const Ice::Current &=Ice::emptyCurrent) const override
 
Ice::Long getMaximalPlanningTimeInSeconds (const Ice::Current &=Ice::emptyCurrent) const override
 
VectorXf getStart (const Ice::Current &=Ice::emptyCurrent) const override
 
 MotionPlanningTaskWithDefaultMembers (const VectorXf &startCfg, const VectorXf &goalCfg, const CSpaceBasePtr &cspace, Ice::Float dcdStep, Ice::Long maximalPlanningTimeInSeconds, const std::string &taskName)
 ctor More...
 
- Public Member Functions inherited from MotionPlanningTask
void addTaskStatusCallback (std::function< void(TaskStatus::Status)> cb)
 
Ice::Long getPlanningTime (const Ice::Current &) const override
 
MotionPlanningTaskBasePrx & getProxy ()
 
Ice::Long getRefiningTime (const Ice::Current &) const override
 
Ice::Long getRunningTime (const Ice::Current &) const override
 
std::string getTaskName (const Ice::Current &=Ice::emptyCurrent) const override
 
TaskStatus::Status getTaskStatus (const Ice::Current &=Ice::emptyCurrent) const override
 
 MotionPlanningTask ()=default
 
virtual void onPlanningDone ()
 
virtual void onRefiningDone ()
 
virtual void registerAtIceAdapter (Ice::ObjectAdapterPtr &adapter, const Ice::Identity ident)
 
bool setTaskStatus (TaskStatus::Status newTaskStatus, const Ice::Current &=Ice::emptyCurrent) override
 
 ~MotionPlanningTask () override=default
 
- Public Member Functions inherited from MotionPlanningTaskCI
bool finishedRunning (const Ice::Current &=Ice::emptyCurrent) const override
 Returns whether the task has finished planning. More...
 
bool isRunning (const Ice::Current &=Ice::emptyCurrent) const override
 Returns whether the task is currently planning. More...
 
void waitForFinishedPlanning_async (const AMD_MotionPlanningTaskControlInterface_waitForFinishedPlanningPtr &cb, const Ice::Current &=Ice::emptyCurrent) override
 
void waitForFinishedRunning_async (const AMD_MotionPlanningTaskControlInterface_waitForFinishedRunningPtr &cb, const Ice::Current &=Ice::emptyCurrent) override
 

Protected Member Functions

void checkParameters ()
 Checks for illegal parameters. More...
 
 Task ()=default
 Ctor used by object factories. More...
 
- Protected Member Functions inherited from MotionPlanningTaskWithDefaultMembers
 MotionPlanningTaskWithDefaultMembers ()=default
 

Protected Attributes

std::condition_variable doneCV
 
std::mutex mtx
 
Path solution
 
std::vector< bool > workerAbortedFlags
 
- Protected Attributes inherited from MotionPlanningTask
Ice::Long planningTime = 0
 The planning time in microseconds. More...
 
Ice::Long refiningTime = 0
 The refining time in microseconds. More...
 
- Protected Attributes inherited from MotionPlanningTaskCI
AMDCallbackCollection waitForFinishedPlanning
 
AMDCallbackCollection waitForFinishedRunning
 

Friends

template<class Base , class Derived >
class ::armarx::GenericFactory
 

Detailed Description

Definition at line 47 of file Task.h.

Constructor & Destructor Documentation

◆ Task() [1/2]

Task ( const CSpaceBasePtr &  cspace,
const VectorXf &  startCfg,
const VectorXf &  goalCfg,
const std::string &  taskName = "RRTConnectTask",
Ice::Long  maximalPlanningTimeInSeconds = 300,
float  dcdStep = 0.01f,
Ice::Long  workerCount = 4 
)

A task using the rrtconnect algorithm.

Parameters
cspaceThe used cspace.
startCfgThe start configuration.
goalCfgThe goal configuration.
dcdStepThe step size used for discrete collision checking.
maximalPlanningTimeInSecondsThe maximal planning time in seconds.
workerCountThe maximal number of computation nodes used.

Definition at line 31 of file Task.cpp.

◆ Task() [2/2]

Task ( )
protecteddefault

Ctor used by object factories.

Member Function Documentation

◆ abortTask()

void abortTask ( const Ice::Current &  = Ice::emptyCurrent)
override

Aborts planning.

Definition at line 42 of file Task.cpp.

+ Here is the call graph for this function:

◆ checkParameters()

void checkParameters ( )
protected

Checks for illegal parameters.

◆ getPath()

Path getPath ( const Ice::Current &  = Ice::emptyCurrent) const
override
Returns
The found path. (empty if no path is found)

Definition at line 50 of file Task.cpp.

◆ postEnqueueing()

void postEnqueueing ( )
overridevirtual

Called by the planning server after the task was enqueued.

Override this function to prepare some work (e.g. setting the status from eNew to eQueued)

Reimplemented from MotionPlanningTask.

Definition at line 183 of file Task.cpp.

+ Here is the call graph for this function:

◆ run()

void run ( const RemoteObjectNodePrxList &  remoteNodes,
const Ice::Current &  = Ice::emptyCurrent 
)
override

Runs the task.

Parameters
remoteNodesThe list of RemoteObjectNodeInterfacePrx used to distribute work to computers.

Definition at line 63 of file Task.cpp.

+ Here is the call graph for this function:

◆ setPath()

void setPath ( const Path &  path,
const Ice::Current &  = Ice::emptyCurrent 
)
override

Definition at line 174 of file Task.cpp.

+ Here is the call graph for this function:

◆ workerHasAborted()

void workerHasAborted ( Ice::Long  workerId,
const Ice::Current &  = Ice::emptyCurrent 
)
override

Definition at line 56 of file Task.cpp.

Friends And Related Function Documentation

◆ ::armarx::GenericFactory

friend class ::armarx::GenericFactory
friend

Definition at line 117 of file Task.h.

Member Data Documentation

◆ doneCV

std::condition_variable doneCV
mutableprotected

Definition at line 110 of file Task.h.

◆ mtx

std::mutex mtx
mutableprotected

Definition at line 109 of file Task.h.

◆ solution

Path solution
protected

Definition at line 112 of file Task.h.

◆ workerAbortedFlags

std::vector<bool> workerAbortedFlags
protected

Definition at line 114 of file Task.h.


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