27#include <condition_variable>
32#include <ArmarXCore/interface/core/RemoteObjectNode.h>
34#include <RobotComponents/interface/components/MotionPlanning/Tasks/RRTConnect/Task.h>
58 const CSpaceBasePtr& cspace,
59 const VectorXf& startCfg,
60 const VectorXf& goalCfg,
61 const std::string& taskName =
"RRTConnectTask",
63 Ice::Long maximalPlanningTimeInSeconds = 300,
64 float dcdStep = 0.01f,
66 Ice::Long workerCount = 4);
72 void abortTask(
const Ice::Current& = Ice::emptyCurrent)
override;
76 Path
getPath(
const Ice::Current& = Ice::emptyCurrent)
const override;
78 void workerHasAborted(Ice::Long workerId,
const Ice::Current& = Ice::emptyCurrent)
override;
85 void run(
const RemoteObjectNodePrxList& remoteNodes,
86 const Ice::Current& = Ice::emptyCurrent)
override;
88 void setPath(
const Path& path,
const Ice::Current& = Ice::emptyCurrent)
override;
113 template <
class Base,
class Derived>
114 friend class ::armarx::GenericFactory;
MotionPlanningTaskWithDefaultMembers(const VectorXf &startCfg, const VectorXf &goalCfg, const CSpaceBasePtr &cspace, Ice::Float dcdStep, Ice::Long maximalPlanningTimeInSeconds, const std::string &taskName)
ctor
The RemoteHandle class wrapps a ClientSideRemoteHandleControlBlock and can be used just as a Ice prox...
Task()=default
Ctor used by object factories.
Path getPath(const Ice::Current &=Ice::emptyCurrent) const override
std::vector< bool > workerAbortedFlags
void workerHasAborted(Ice::Long workerId, const Ice::Current &=Ice::emptyCurrent) override
std::condition_variable doneCV
void abortTask(const Ice::Current &=Ice::emptyCurrent) override
Aborts planning.
void setPath(const Path &path, const Ice::Current &=Ice::emptyCurrent) override
void postEnqueueing() override
Called by the planning server after the task was enqueued.
void checkParameters()
Checks for illegal parameters.
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.
void run(const RemoteObjectNodePrxList &remoteNodes, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
IceInternal::Handle< Task > TaskPtr
This file offers overloads of toIce() and fromIce() functions for STL container types.
RemoteHandle< MotionPlanningTaskControlInterfacePrx > RRTConnectTaskHandle
IceUtil::Handle< RRTConnectTask > RRTConnectTaskPtr
rrtconnect::Task RRTConnectTask