Task.h
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5 *
6 * ArmarX is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License version 2 as
8 * published by the Free Software Foundation.
9 *
10 * ArmarX is distributed in the hope that it will be useful, but
11 * WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 * GNU General Public License for more details.
14 *
15 * You should have received a copy of the GNU General Public License
16 * along with this program. If not, see <http://www.gnu.org/licenses/>.
17 *
18 * @package RobotComponents
19 * @author Raphael Grimm ( raphael dot grimm at kit dot edu )
20 * @date 2015
21 * @copyright http://www.gnu.org/licenses/gpl.txt
22 * GNU General Public License
23 */
24#pragma once
25
26#include <chrono>
27#include <condition_variable>
28#include <mutex>
29
32#include <ArmarXCore/interface/core/RemoteObjectNode.h>
33
34#include <RobotComponents/interface/components/MotionPlanning/Tasks/RRTConnect/Task.h>
35
36#include "../../util/Metrics.h"
38#include "WorkerNode.h"
39
40namespace armarx::rrtconnect
41{
42 class Task;
44
45 class Task : public virtual MotionPlanningTaskWithDefaultMembers, public virtual TaskBase
46 {
47 public:
48 /**
49 * @brief A task using the rrtconnect algorithm.
50 * @param cspace The used cspace.
51 * @param startCfg The start configuration.
52 * @param goalCfg The goal configuration.
53 * @param dcdStep The step size used for discrete collision checking.
54 * @param maximalPlanningTimeInSeconds The maximal planning time in seconds.
55 * @param workerCount The maximal number of computation nodes used.
56 */
57 Task( //problem
58 const CSpaceBasePtr& cspace,
59 const VectorXf& startCfg,
60 const VectorXf& goalCfg,
61 const std::string& taskName = "RRTConnectTask",
62 //general
63 Ice::Long maximalPlanningTimeInSeconds = 300,
64 float dcdStep = 0.01f,
65 //management
66 Ice::Long workerCount = 4);
67
68 //PlanningControlInterface
69 /**
70 * @brief Aborts planning.
71 */
72 void abortTask(const Ice::Current& = Ice::emptyCurrent) override;
73 /**
74 * @return The found path. (empty if no path is found)
75 */
76 Path getPath(const Ice::Current& = Ice::emptyCurrent) const override;
77
78 void workerHasAborted(Ice::Long workerId, const Ice::Current& = Ice::emptyCurrent) override;
79
80 //PlanningTaskBase
81 /**
82 * @brief Runs the task.
83 * @param remoteNodes The list of \ref RemoteObjectNodeInterfacePrx used to distribute work to computers.
84 */
85 void run(const RemoteObjectNodePrxList& remoteNodes,
86 const Ice::Current& = Ice::emptyCurrent) override;
87
88 void setPath(const Path& path, const Ice::Current& = Ice::emptyCurrent) override;
89
90 void postEnqueueing() override;
91
92 protected:
93 /**
94 * @brief Checks for illegal parameters
95 */
97
98 /**
99 * @brief Ctor used by object factories.
100 */
101 Task() = default;
102
103 // TaskStatus::Status taskStatus = eNew;
104
105 mutable std::mutex mtx;
106 mutable std::condition_variable doneCV;
107
109
110 std::vector<bool> workerAbortedFlags;
111
112 private:
113 template <class Base, class Derived>
114 friend class ::armarx::GenericFactory;
115 };
116} // namespace armarx::rrtconnect
117
118namespace armarx
119{
123} // namespace armarx
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
Definition Task.cpp:59
std::vector< bool > workerAbortedFlags
Definition Task.h:110
void workerHasAborted(Ice::Long workerId, const Ice::Current &=Ice::emptyCurrent) override
Definition Task.cpp:66
std::condition_variable doneCV
Definition Task.h:106
void abortTask(const Ice::Current &=Ice::emptyCurrent) override
Aborts planning.
Definition Task.cpp:49
void setPath(const Path &path, const Ice::Current &=Ice::emptyCurrent) override
Definition Task.cpp:193
void postEnqueueing() override
Called by the planning server after the task was enqueued.
Definition Task.cpp:203
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.
Definition Task.cpp:31
void run(const RemoteObjectNodePrxList &remoteNodes, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
Definition Task.cpp:74
IceInternal::Handle< Task > TaskPtr
Definition Task.h:43
This file offers overloads of toIce() and fromIce() functions for STL container types.
RemoteHandle< MotionPlanningTaskControlInterfacePrx > RRTConnectTaskHandle
Definition Task.h:122
IceUtil::Handle< RRTConnectTask > RRTConnectTaskPtr
Definition Task.h:121
rrtconnect::Task RRTConnectTask
Definition Task.h:120