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