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
30
#include <
ArmarXCore/core/system/FactoryCollectionBase.h
>
31
#include <
ArmarXCore/core/util/distributed/RemoteHandle/RemoteHandle.h
>
32
#include <ArmarXCore/interface/core/RemoteObjectNode.h>
33
34
#include <RobotComponents/interface/components/MotionPlanning/Tasks/AStar/Task.h>
35
36
#include "../../util/Metrics.h"
37
#include "../MotionPlanningTask.h"
38
39
namespace
armarx::astar
40
{
41
class
Task;
42
using
TaskPtr
=
IceInternal::Handle<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
106
namespace
armarx
107
{
108
using
AStarTask
=
astar::Task
;
109
using
AStarTaskPtr
=
IceUtil::Handle<AStarTask>
;
110
using
AStarTaskHandle
=
RemoteHandle<MotionPlanningTaskControlInterfacePrx>
;
111
}
// namespace armarx
armarx::astar::Task::run
void run(const RemoteObjectNodePrxList &, const Ice::Current &=Ice::emptyCurrent) override
Runs the task.
Definition:
Task.cpp:71
armarx::astar::Task::solution
Path solution
Definition:
Task.h:97
armarx::MotionPlanningTaskWithDefaultMembers
Definition:
MotionPlanningTask.h:167
armarx::astar::Task::isPathCollisionFree
bool isPathCollisionFree(const VectorXf &from, const VectorXf &to)
Definition:
Task.cpp:346
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:70
IceInternal::Handle
Definition:
forward_declarations.h:8
armarx::VariantType::Long
const VariantTypeId Long
Definition:
Variant.h:918
armarx::astar::Task::getPath
Path getPath(const Ice::Current &=Ice::emptyCurrent) const override
Definition:
Task.cpp:64
armarx::astar::Task::taskIsAborted
std::atomic_bool taskIsAborted
Definition:
Task.h:98
armarx::astar::Task
Definition:
Task.h:44
IceUtil::Handle
Definition:
forward_declarations.h:30
armarx::RemoteHandle
The RemoteHandle class wrapps a ClientSideRemoteHandleControlBlock and can be used just as a Ice prox...
Definition:
RemoteHandle.h:46
armarx::armem::server::ltm::detail::mixin::Path
std::filesystem::path Path
Definition:
DiskStorageMixin.h:17
armarx::astar
Definition:
Task.cpp:31
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition:
ArmarXTimeserver.cpp:27
armarx::astar::Task::mtx
std::mutex mtx
Definition:
Task.h:96
RobotComponents
components
MotionPlanning
Tasks
AStar
Task.h
Generated on Sat Mar 29 2025 09:17:32 for armarx_documentation by
1.8.17