Go to the documentation of this file.
27 #include <condition_variable>
32 #include <ArmarXCore/interface/core/RemoteObjectNode.h>
34 #include <RobotComponents/interface/components/MotionPlanning/Tasks/RRTConnect/Task.h>
36 #include "../../util/Metrics.h"
37 #include "../MotionPlanningTask.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,
72 void abortTask(
const Ice::Current& = Ice::emptyCurrent)
override;
76 Path getPath(
const Ice::Current& = Ice::emptyCurrent)
const 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;
void setPath(const Path &path, const Ice::Current &=Ice::emptyCurrent) override
void abortTask(const Ice::Current &=Ice::emptyCurrent) override
Aborts planning.
void workerHasAborted(Ice::Long workerId, const Ice::Current &=Ice::emptyCurrent) override
Task()=default
Ctor used by object factories.
void postEnqueueing() override
Called by the planning server after the task was enqueued.
Path getPath(const Ice::Current &=Ice::emptyCurrent) const override
std::vector< bool > workerAbortedFlags
void run(const RemoteObjectNodePrxList &remoteNodes, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
void checkParameters()
Checks for illegal parameters.
The RemoteHandle class wrapps a ClientSideRemoteHandleControlBlock and can be used just as a Ice prox...
std::filesystem::path Path
std::condition_variable doneCV
This file offers overloads of toIce() and fromIce() functions for STL container types.