Task.cpp
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 
25 #include "Task.h"
26 
27 #include "../../util/PlanningUtil.h"
28 
30 {
31  Task::Task(const CSpaceBasePtr& cspace,
32  const VectorXf& startCfg,
33  const VectorXf& goalCfg,
34  const std::string& taskName,
35  Ice::Long maximalPlanningTimeInSeconds,
36  float dcdStep,
37  Ice::Long workerCount)
38  {
39  this->cspace = cspace;
40  this->startCfg = startCfg;
41  this->goalCfg = goalCfg;
42  this->dcdStep = dcdStep;
43  this->maximalPlanningTimeInSeconds = maximalPlanningTimeInSeconds;
44  this->workerCount = workerCount;
45  this->taskName = taskName;
46  }
47 
48  void
49  Task::abortTask(const Ice::Current&)
50  {
51  std::lock_guard<std::mutex> lock{mtx};
52  setTaskStatus((getTaskStatus() != TaskStatus::eDone) ? TaskStatus::ePlanningAborted
53  : TaskStatus::eDone);
54  //worker will be aborted in run()
55  doneCV.notify_all();
56  }
57 
58  Path
59  Task::getPath(const Ice::Current&) const
60  {
61  std::lock_guard<std::mutex> lock{mtx};
62  return solution;
63  }
64 
65  void
66  Task::workerHasAborted(Ice::Long workerId, const Ice::Current&)
67  {
68  std::lock_guard<std::mutex> lock{mtx};
69  ARMARX_CHECK_EXPRESSION(static_cast<std::size_t>(workerId) < workerAbortedFlags.size());
70  workerAbortedFlags.at(workerId) = true;
71  }
72 
73  void
74  Task::run(const RemoteObjectNodePrxList& remoteNodes, const Ice::Current&)
75  {
77  ARMARX_CHECK_EXPRESSION(std::all_of(remoteNodes.begin(),
78  remoteNodes.end(),
79  [](const RemoteObjectNodeInterfacePrx& n)
80  { return n; }));
81  //init
82  workerAbortedFlags.assign(workerCount, false);
83  setTaskStatus(TaskStatus::ePlanning);
84  const std::string topicName = "RRTConnectUpdateTopic:" + getProxy()->ice_getIdentity().name;
85  //check trivial cases
86 
87  const auto startIsCollisionFree =
88  cspace->isCollisionFree(std::pair<const Ice::Float*, const Ice::Float*>{
89  startCfg.data(), startCfg.data() + startCfg.size()});
90  if (!startIsCollisionFree)
91  {
92  setTaskStatus(TaskStatus::ePlanningFailed);
93  ARMARX_WARNING << "MotionPlanningTask " << taskName
94  << " trivially failed! start cfg in collision. start:\n"
95  << startCfg;
96  return;
97  }
98 
99  const auto goalIscollisionFree =
100  cspace->isCollisionFree(std::pair<const Ice::Float*, const Ice::Float*>{
101  goalCfg.data(), goalCfg.data() + goalCfg.size()});
102  if (!goalIscollisionFree)
103  {
104  setTaskStatus(TaskStatus::ePlanningFailed);
105  ARMARX_WARNING << "MotionPlanningTask " << taskName
106  << " trivially failed! goal cfg in collision. goal:\n"
107  << goalCfg;
108  return;
109  }
110 
111  if (euclideanDistance(startCfg.begin(), startCfg.end(), goalCfg.begin()) <= dcdStep)
112  {
113  solution.nodes.emplace_back(startCfg);
114  solution.nodes.emplace_back(goalCfg);
115  solution.pathName = taskName + "_trivialPath_" + ice_staticId();
117  << "MotionPlanningTask " << taskName
118  << " trivially succeeded! (start and goal less than dcd step size apart!)";
119  setTaskStatus(TaskStatus::eDone);
120  return;
121  }
122 
123  //start workers
124  std::unique_lock<std::mutex> lock{mtx};
125  std::vector<RemoteHandle<WorkerNodeBasePrx>> workers;
126  WorkerNodeBasePrxList workerProxies;
127 
128  workers.reserve(workerCount);
129  auto workerToStart = workerCount;
130  const auto taskName = getProxy()->ice_getIdentity().name;
131  for (auto& ron : remoteNodes)
132  {
133  auto maxWorkerForNode = ron->getNumberOfCores();
134  for (Ice::Long i = 0; i < maxWorkerForNode && workerToStart; ++i)
135  {
136  WorkerNodeBasePtr worker{new WorkerNode{cspace->clone(),
137  startCfg,
138  goalCfg,
139  dcdStep,
140  TaskBasePrx::uncheckedCast(getProxy()),
141  topicName,
142  static_cast<Ice::Long>(workers.size()),
143  workerCount}};
144  const std::string workerName = ManagedIceObject::generateSubObjectName(
145  taskName, "RRTConnectWorker:" + to_string(workers.size()));
146  workers.emplace_back(ron->registerRemoteHandledObject(workerName, worker));
147  workerProxies.emplace_back(*(workers.back()));
148  --workerToStart;
149  }
150  if (!workerToStart)
151  {
152  break;
153  }
154  }
155 
156  //distribute worker proxy
157  for (auto& w : workers)
158  {
159  w->setWorkerNodes(workerProxies);
160  }
161 
162  //wait for done or timeout
163  const auto endTime =
164  std::chrono::system_clock::now() + std::chrono::seconds{maximalPlanningTimeInSeconds};
165 
166  while (true)
167  {
168  doneCV.wait_for(lock, std::chrono::milliseconds{10});
169  if (endTime < std::chrono::system_clock::now())
170  {
171  setTaskStatus(TaskStatus::ePlanningFailed);
172  break;
173  }
174  if (getTaskStatus() != TaskStatus::ePlanning)
175  {
176  break;
177  }
178  }
179 
180  //wait for all stopped
181  while (std::any_of(
182  workerAbortedFlags.begin(), workerAbortedFlags.end(), [](bool b) { return !b; }))
183  {
184  for (auto& w : workers)
185  {
186  w->abort();
187  }
188  doneCV.wait_for(lock, std::chrono::milliseconds{10});
189  }
190  }
191 
192  void
193  Task::setPath(const Path& path, const Ice::Current&)
194  {
195  std::lock_guard<std::mutex> lock{mtx};
196  solution = path;
197  solution.pathName = taskName + "_path_" + ice_staticId();
198  setTaskStatus(TaskStatus::eDone);
199  doneCV.notify_all();
200  }
201 
202  void
204  {
206  cspace->initCollisionTest();
207  }
208 } // namespace armarx::rrtconnect
armarx::rrtconnect::Task::mtx
std::mutex mtx
Definition: Task.h:105
armarx::rrtconnect::Task::setPath
void setPath(const Path &path, const Ice::Current &=Ice::emptyCurrent) override
Definition: Task.cpp:193
armarx::rrtconnect::Task::abortTask
void abortTask(const Ice::Current &=Ice::emptyCurrent) override
Aborts planning.
Definition: Task.cpp:49
armarx::MotionPlanningTask::getProxy
MotionPlanningTaskBasePrx & getProxy()
Definition: MotionPlanningTask.h:92
armarx::MotionPlanningTask::postEnqueueing
virtual void postEnqueueing()
Called by the planning server after the task was enqueued.
Definition: MotionPlanningTask.h:76
armarx::MotionPlanningTask::getTaskStatus
TaskStatus::Status getTaskStatus(const Ice::Current &=Ice::emptyCurrent) const override
Definition: MotionPlanningTask.h:101
armarx::rrtconnect::Task::workerHasAborted
void workerHasAborted(Ice::Long workerId, const Ice::Current &=Ice::emptyCurrent) override
Definition: Task.cpp:66
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:203
armarx::rrtconnect::Task::solution
Path solution
Definition: Task.h:108
armarx::rrtconnect
Definition: Task.cpp:29
armarx::ManagedIceObject::generateSubObjectName
static std::string generateSubObjectName(const std::string &superObjectName, const std::string &subObjectName)
Generates a unique name for a sub object from a general name and unique name.
Definition: ManagedIceObject.cpp:119
armarx::VariantType::Long
const VariantTypeId Long
Definition: Variant.h:918
Task.h
armarx::rrtconnect::WorkerNode
Definition: WorkerNode.h:55
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:41
armarx::rrtconnect::Task::getPath
Path getPath(const Ice::Current &=Ice::emptyCurrent) const override
Definition: Task.cpp:59
armarx::euclideanDistance
float euclideanDistance(IteratorType1 first1, IteratorType1 last1, IteratorType2 first2)
Returns the euclidean distance.
Definition: Metrics.h:104
armarx::rrtconnect::Task::workerAbortedFlags
std::vector< bool > workerAbortedFlags
Definition: Task.h:110
armarx::rrtconnect::Task::run
void run(const RemoteObjectNodePrxList &remoteNodes, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
Definition: Task.cpp:74
ARMARX_CHECK_EXPRESSION
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
Definition: ExpressionException.h:73
armarx::MotionPlanningTask::setTaskStatus
bool setTaskStatus(TaskStatus::Status newTaskStatus, const Ice::Current &=Ice::emptyCurrent) override
Definition: MotionPlanningTask.cpp:32
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:106
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:193