Task Class Reference

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

+ Inheritance diagram for Task:

Public Member Functions

void abortTask (const Ice::Current &=Ice::emptyCurrent) override
 Aborts planning. More...
 
std::pair< float, floatcalcOffsets (float length, std::mt19937 &gen)
 
PathWithCostSeq getAllPathsWithCost (const Ice::Current &=Ice::emptyCurrent) const override
 
PathWithCost getBestPath (const Ice::Current &=Ice::emptyCurrent) const override
 
Ice::Long getMaximalPlanningTimeInSeconds (const Ice::Current &=Ice::emptyCurrent) const override
 
Path getNthPath (Ice::Long n, const Ice::Current &=Ice::emptyCurrent) const override
 
PathWithCost getNthPathWithCost (Ice::Long n, const Ice::Current &=Ice::emptyCurrent) const override
 
Path getPath (const Ice::Current &=Ice::emptyCurrent) const override
 
Ice::Long getPathCount (const Ice::Current &=Ice::emptyCurrent) const override
 
PathWithCost getPathWithCost (const Ice::Current &=Ice::emptyCurrent) const override
 
bool isPathCollisionFree (const VectorXf &from, const VectorXf &to)
 
void run (const RemoteObjectNodePrxList &nodes, const Ice::Current &=Ice::emptyCurrent) override
 Runs the task. More...
 
 Task (MotionPlanningTaskBasePtr previousStep, const std::string &taskName="RandomShortcutPostprocessorTask", Ice::Long maxTimeForPostprocessingInSeconds=6000, Ice::Float dcdStep=0.01, Ice::Long maxTries=10000, Ice::Float minShortcutImprovementRatio=0.1, Ice::Float minPathImprovementRatio=0.01)
 
 ~Task () override=default
 
- Public Member Functions inherited from PostprocessingMotionPlanningTask
CSpaceBasePtr getCSpace (const Ice::Current &=Ice::emptyCurrent) const override
 
void postEnqueueing () override
 Called by the planning server after the task was enqueued. More...
 
 PostprocessingMotionPlanningTask (const MotionPlanningTaskBasePtr &previousStep, const std::string &taskName)
 
void registerAtIceAdapter (Ice::ObjectAdapterPtr &adapter, const Ice::Identity ident) override
 
- 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 ()
 
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
 
- Public Member Functions inherited from MotionPlanningMultiPathWithCostTaskCI
PathSeq getAllPaths (const Ice::Current &=Ice::emptyCurrent) const override
 
Path getNthPath (Ice::Long n, const Ice::Current &=Ice::emptyCurrent) const override
 
Path getPath (const Ice::Current &=Ice::emptyCurrent) const override
 
- Public Member Functions inherited from MotionPlanningMultiPathTaskCI
Path getPath (const Ice::Current &=Ice::emptyCurrent) const override
 
- Public Member Functions inherited from MotionPlanningWithCostTaskCI
Path getPath (const Ice::Current &=Ice::emptyCurrent) const override
 

Protected Member Functions

 Task ()=default
 Ctor used by object factories. More...
 
- Protected Member Functions inherited from PostprocessingMotionPlanningTask
 PostprocessingMotionPlanningTask ()=default
 

Protected Attributes

std::mutex mtx
 
PathWithCostSeq paths
 
Path postprocessedSolution
 
std::atomic_bool taskIsAborted {false}
 
- 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 46 of file Task.h.

Constructor & Destructor Documentation

◆ Task() [1/2]

Task ( MotionPlanningTaskBasePtr  previousStep,
const std::string &  taskName = "RandomShortcutPostprocessorTask",
Ice::Long  maxTimeForPostprocessingInSeconds = 6000,
Ice::Float  dcdStep = 0.01,
Ice::Long  maxTries = 10000,
Ice::Float  minShortcutImprovementRatio = 0.1,
Ice::Float  minPathImprovementRatio = 0.01 
)

Definition at line 33 of file Task.cpp.

◆ ~Task()

~Task ( )
overridedefault

◆ 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 77 of file Task.cpp.

◆ calcOffsets()

std::pair< float, float > calcOffsets ( float  length,
std::mt19937 &  gen 
)

Definition at line 382 of file Task.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getAllPathsWithCost()

PathWithCostSeq getAllPathsWithCost ( const Ice::Current &  = Ice::emptyCurrent) const
override

Definition at line 322 of file Task.cpp.

◆ getBestPath()

PathWithCost getBestPath ( const Ice::Current &  = Ice::emptyCurrent) const
override

Definition at line 311 of file Task.cpp.

+ Here is the call graph for this function:

◆ getMaximalPlanningTimeInSeconds()

Ice::Long getMaximalPlanningTimeInSeconds ( const Ice::Current &  = Ice::emptyCurrent) const
inlineoverride

Definition at line 91 of file Task.h.

+ Here is the caller graph for this function:

◆ getNthPath()

Path getNthPath ( Ice::Long  n,
const Ice::Current &  = Ice::emptyCurrent 
) const
inlineoverride

Definition at line 67 of file Task.h.

+ Here is the call graph for this function:

◆ getNthPathWithCost()

PathWithCost getNthPathWithCost ( Ice::Long  n,
const Ice::Current &  = Ice::emptyCurrent 
) const
override

Definition at line 316 of file Task.cpp.

+ Here is the caller graph for this function:

◆ getPath()

Path getPath ( const Ice::Current &  = Ice::emptyCurrent) const
inlineoverride

Definition at line 71 of file Task.h.

+ Here is the call graph for this function:

◆ getPathCount()

Ice::Long getPathCount ( const Ice::Current &  = Ice::emptyCurrent) const
override

Definition at line 305 of file Task.cpp.

◆ getPathWithCost()

PathWithCost getPathWithCost ( const Ice::Current &  = Ice::emptyCurrent) const
inlineoverridevirtual

Reimplemented from MotionPlanningMultiPathWithCostTaskCI.

Definition at line 63 of file Task.h.

+ Here is the call graph for this function:

◆ isPathCollisionFree()

bool isPathCollisionFree ( const VectorXf &  from,
const VectorXf &  to 
)

Definition at line 328 of file Task.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ run()

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

Runs the task.

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

Definition at line 86 of file Task.cpp.

+ Here is the call graph for this function:

Friends And Related Function Documentation

◆ ::armarx::GenericFactory

friend class ::armarx::GenericFactory
friend

Definition at line 116 of file Task.h.

Member Data Documentation

◆ mtx

std::mutex mtx
mutableprotected

Definition at line 111 of file Task.h.

◆ paths

PathWithCostSeq paths
protected

Definition at line 113 of file Task.h.

◆ postprocessedSolution

Path postprocessedSolution
protected

Definition at line 112 of file Task.h.

◆ taskIsAborted

std::atomic_bool taskIsAborted {false}
protected

Definition at line 114 of file Task.h.


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