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 <mutex>
27 #include <chrono>
28 #include <condition_variable>
29 
31 
32 
34 #include <ArmarXCore/interface/core/RemoteObjectNode.h>
35 
36 #include <RobotComponents/interface/components/MotionPlanning/Tasks/RRTConnect/Task.h>
37 #include "../../util/Metrics.h"
38 
39 #include "WorkerNode.h"
40 #include "../MotionPlanningTask.h"
41 
42 namespace armarx::rrtconnect
43 {
44  class Task;
46 
47  class Task:
49  public virtual TaskBase
50  {
51  public:
52  /**
53  * @brief A task using the rrtconnect algorithm.
54  * @param cspace The used cspace.
55  * @param startCfg The start configuration.
56  * @param goalCfg The goal configuration.
57  * @param dcdStep The step size used for discrete collision checking.
58  * @param maximalPlanningTimeInSeconds The maximal planning time in seconds.
59  * @param workerCount The maximal number of computation nodes used.
60  */
61  Task(//problem
62  const CSpaceBasePtr& cspace,
63  const VectorXf& startCfg,
64  const VectorXf& goalCfg,
65  const std::string& taskName = "RRTConnectTask",
66  //general
67  Ice::Long maximalPlanningTimeInSeconds = 300,
68  float dcdStep = 0.01f,
69  //management
70  Ice::Long workerCount = 4
71  );
72 
73  //PlanningControlInterface
74  /**
75  * @brief Aborts planning.
76  */
77  void abortTask(const Ice::Current& = Ice::emptyCurrent) override;
78  /**
79  * @return The found path. (empty if no path is found)
80  */
81  Path getPath(const Ice::Current& = Ice::emptyCurrent) const override;
82 
83  void workerHasAborted(Ice::Long workerId, const Ice::Current& = Ice::emptyCurrent) override;
84 
85  //PlanningTaskBase
86  /**
87  * @brief Runs the task.
88  * @param remoteNodes The list of \ref RemoteObjectNodeInterfacePrx used to distribute work to computers.
89  */
90  void run(const RemoteObjectNodePrxList& remoteNodes, const Ice::Current& = Ice::emptyCurrent) override;
91 
92  void setPath(const Path& path, const Ice::Current& = Ice::emptyCurrent) override;
93 
94  void postEnqueueing() override;
95 
96  protected:
97  /**
98  * @brief Checks for illegal parameters
99  */
100  void checkParameters();
101 
102  /**
103  * @brief Ctor used by object factories.
104  */
105  Task() = default;
106 
107  // TaskStatus::Status taskStatus = eNew;
108 
109  mutable std::mutex mtx;
110  mutable std::condition_variable doneCV;
111 
113 
114  std::vector<bool> workerAbortedFlags;
115 
116  private:
117  template<class Base, class Derived> friend class ::armarx::GenericFactory;
118  };
119 }
120 
121 namespace armarx
122 {
126 }
armarx::rrtconnect::Task::mtx
std::mutex mtx
Definition: Task.h:109
armarx::MotionPlanningTaskWithDefaultMembers
Definition: MotionPlanningTask.h:142
armarx::rrtconnect::Task::setPath
void setPath(const Path &path, const Ice::Current &=Ice::emptyCurrent) override
Definition: Task.cpp:174
armarx::rrtconnect::Task::abortTask
void abortTask(const Ice::Current &=Ice::emptyCurrent) override
Aborts planning.
Definition: Task.cpp:42
RemoteHandle.h
FactoryCollectionBase.h
armarx::rrtconnect::Task::workerHasAborted
void workerHasAborted(Ice::Long workerId, const Ice::Current &=Ice::emptyCurrent) override
Definition: Task.cpp:56
armarx::rrtconnect::Task::Task
Task()=default
Ctor used by object factories.
armarx::rrtconnect::Task::postEnqueueing
void postEnqueueing() override
Called by the planning server after the task was enqueued.
Definition: Task.cpp:183
armarx::rrtconnect::Task::solution
Path solution
Definition: Task.h:112
IceInternal::Handle
Definition: forward_declarations.h:8
armarx::rrtconnect
Definition: Task.cpp:29
armarx::VariantType::Long
const VariantTypeId Long
Definition: Variant.h:917
armarx::rrtconnect::Task
Definition: Task.h:47
armarx::rrtconnect::Task::getPath
Path getPath(const Ice::Current &=Ice::emptyCurrent) const override
Definition: Task.cpp:50
armarx::rrtconnect::Task::workerAbortedFlags
std::vector< bool > workerAbortedFlags
Definition: Task.h:114
armarx::rrtconnect::Task::run
void run(const RemoteObjectNodePrxList &remoteNodes, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
Definition: Task.cpp:63
armarx::rrtconnect::Task::checkParameters
void checkParameters()
Checks for illegal parameters.
IceUtil::Handle
Definition: forward_declarations.h:29
armarx::RemoteHandle
The RemoteHandle class wrapps a ClientSideRemoteHandleControlBlock and can be used just as a Ice prox...
Definition: RemoteHandle.h:45
WorkerNode.h
armarx::armem::server::ltm::detail::mixin::Path
std::filesystem::path Path
Definition: DiskStorageMixin.h:17
armarx::rrtconnect::Task::doneCV
std::condition_variable doneCV
Definition: Task.h:110
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28