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 2016
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<atomic>
29 
31 
33 #include <ArmarXCore/interface/core/RemoteObjectNode.h>
34 
35 #include <RobotComponents/interface/components/MotionPlanning/Tasks/AStar/Task.h>
36 #include "../../util/Metrics.h"
37 
38 #include "../MotionPlanningTask.h"
39 
40 namespace armarx::astar
41 {
42  class Task;
44 
45  class Task:
47  public virtual TaskBase
48  {
49  public:
50  /**
51  * @brief A task using the A* algorithm.
52  * @param cspace The used cspace.
53  * @param startCfg The start configuration.
54  * @param goalCfg The goal configuration.
55  * @param dcdStep The step size used for discrete collision checking.
56  * @param maximalPlanningTimeInSeconds The maximal planning time in seconds.
57  */
58  Task(//problem
59  const CSpaceBasePtr& cspace,
60  const VectorXf& startCfg,
61  const VectorXf& goalCfg,
62  const std::string& taskName = "AStarTask",
63  //general
64  float dcdStep = 0.01f,
65  float gridStepSize = 2.5f,
66  Ice::Long maximalPlanningTimeInSeconds = 300
67  );
68 
69  //PlanningControlInterface
70  /**
71  * @brief Aborts planning.
72  */
73  void abortTask(const Ice::Current& = Ice::emptyCurrent) override
74  {
75  taskIsAborted = true;
76  }
77  /**
78  * @return The found path. (empty if no path is found)
79  */
80  Path getPath(const Ice::Current& = Ice::emptyCurrent) const override;
81 
82 
83  //PlanningTaskBase
84  /**
85  * @brief Runs the task.
86  * @param remoteNodes The list of \ref RemoteObjectNodeInterfacePrx used to distribute work to computers.
87  */
88  void run(const RemoteObjectNodePrxList&, const Ice::Current& = Ice::emptyCurrent) override;
89 
90  bool isPathCollisionFree(const VectorXf& from, const VectorXf& to);
91  protected:
92  /**
93  * @brief Ctor used by object factories.
94  */
95  Task() = default;
96 
97  mutable std::mutex mtx;
98  Path solution = {{}, "Path"};
99  std::atomic_bool taskIsAborted {false};
100  private:
101  template<class Base, class Derived> friend class ::armarx::GenericFactory;
102  };
103 }
104 namespace armarx
105 {
109 }
armarx::astar::Task::run
void run(const RemoteObjectNodePrxList &, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
Definition: Task.cpp:61
armarx::astar::Task::solution
Path solution
Definition: Task.h:98
armarx::MotionPlanningTaskWithDefaultMembers
Definition: MotionPlanningTask.h:142
armarx::astar::Task::isPathCollisionFree
bool isPathCollisionFree(const VectorXf &from, const VectorXf &to)
Definition: Task.cpp:332
armarx::astar::Task::Task
Task()=default
Ctor used by object factories.
RemoteHandle.h
FactoryCollectionBase.h
armarx::astar::Task::abortTask
void abortTask(const Ice::Current &=Ice::emptyCurrent) override
Aborts planning.
Definition: Task.h:73
IceInternal::Handle
Definition: forward_declarations.h:8
armarx::VariantType::Long
const VariantTypeId Long
Definition: Variant.h:917
armarx::astar::Task::getPath
Path getPath(const Ice::Current &=Ice::emptyCurrent) const override
Definition: Task.cpp:55
armarx::astar::Task::taskIsAborted
std::atomic_bool taskIsAborted
Definition: Task.h:99
armarx::astar::Task
Definition: Task.h:45
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
armarx::armem::server::ltm::detail::mixin::Path
std::filesystem::path Path
Definition: DiskStorageMixin.h:17
armarx::astar
Definition: Task.cpp:30
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::astar::Task::mtx
std::mutex mtx
Definition: Task.h:97