RobotNameHelper.h
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
5 * Karlsruhe Institute of Technology (KIT), all rights reserved.
6 *
7 * ArmarX is free software; you can redistribute it and/or modify
8 * it under the terms of the GNU General Public License version 2 as
9 * published by the Free Software Foundation.
10 *
11 * ArmarX is distributed in the hope that it will be useful, but
12 * WITHOUT ANY WARRANTY; without even the implied warranty of
13 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 * GNU General Public License for more details.
15 *
16 * You should have received a copy of the GNU General Public License
17 * along with this program. If not, see <http://www.gnu.org/licenses/>.
18 *
19 * @author Simon Ottenhaus (simon dot ottenhaus at kit dot edu)
20 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21 * GNU General Public License
22 */
23
24#pragma once
25
26#include <VirtualRobot/VirtualRobot.h>
27
28#include <RobotAPI/interface/core/RobotState.h>
29
30namespace armarx
31{
32 using RobotNameHelperPtr = std::shared_ptr<class RobotNameHelper>;
33 using StatechartProfilePtr = std::shared_ptr<class StatechartProfile>;
34
36
37 struct RobotArm;
38
39 struct Arm
40 {
41 friend class RobotNameHelper;
42
43 public:
44 std::string getSide() const;
45
46 std::string getKinematicChain() const;
47
48 std::string getTorsoKinematicChain() const;
49
50 std::string getTCP() const;
51
52 std::string getForceTorqueSensor() const;
53
54 std::string getForceTorqueSensorFrame() const;
55
56 std::string getEndEffector() const;
57
58 std::string getMemoryHandName() const;
59
60 std::string getHandControllerName() const;
61
62 std::string getHandRootNode() const;
63
64 std::string getHandUnitName() const;
65
66 std::string getHandModelPath() const;
67
68 std::string getAbsoluteHandModelPath() const;
69
70 std::string getHandModelPackage() const;
71
72 std::string getPalmCollisionModel() const;
73
74 std::string getFullHandCollisionModel() const;
75
76 RobotArm addRobot(const VirtualRobot::RobotPtr& robot) const;
77
78 Arm(const std::shared_ptr<const RobotNameHelper>& rnh, const std::string& side);
79
80 Arm() = default;
81
82 Arm(Arm&&) = default;
83
84 Arm(const Arm&) = default;
85
86 Arm& operator=(Arm&&) = default;
87
88 Arm& operator=(const Arm&) = default;
89
90 std::shared_ptr<const RobotNameHelper> getRobotNameHelper() const;
91
92 std::string select(const std::string& path) const;
93
94 private:
95 std::shared_ptr<const RobotNameHelper> rnh;
96 std::string side;
97 };
98
99 struct RobotArm
100 {
101 friend class RobotNameHelper;
102
103 friend struct Arm;
104
105 public:
106 std::string getSide() const;
107
108 VirtualRobot::RobotNodeSetPtr getKinematicChain() const;
109
110 VirtualRobot::RobotNodeSetPtr getTorsoKinematicChain() const;
111
112 VirtualRobot::RobotNodePtr getTCP() const;
113
114 VirtualRobot::RobotNodePtr getHandRootNode() const;
115
116 VirtualRobot::RobotNodePtr getPalmCollisionModel() const;
117
118 VirtualRobot::TriMeshModelPtr getFullHandCollisionModel() const;
119
120 Eigen::Matrix4f getTcp2HandRootTransform() const;
121
122 const Arm& getArm() const;
123
124 const VirtualRobot::RobotPtr& getRobot() const;
125
126 RobotArm(const Arm& arm, const VirtualRobot::RobotPtr& robot);
127
128 RobotArm() = default;
129
130 RobotArm(RobotArm&&) = default;
131
132 RobotArm(const RobotArm&) = default;
133
135
136 RobotArm& operator=(const RobotArm&) = default;
137
138 private:
139 Arm arm;
141 };
142
143 class RobotNameHelper : public std::enable_shared_from_this<RobotNameHelper>
144 {
145 public:
146 static void writeRobotInfoNode(const RobotInfoNodePtr& n,
147 std::ostream& str,
148 std::size_t indent = 0,
149 char indentChar = ' ');
152
153 class Node
154 {
155 public:
156 Node(const RobotInfoNodePtr& robotInfo);
157
158 std::string value();
159
160 Node select(const std::string& name, const std::vector<std::string>& profiles);
161
162 bool isValid();
163
164 void checkValid();
165
166 private:
167 RobotInfoNodePtr robotInfo;
168 };
169
170 static const std::string LocationLeft;
171 static const std::string LocationRight;
172
173 std::string select(const std::string& path) const;
174
175 static RobotNameHelperPtr Create(const RobotInfoNodePtr& robotInfo,
176 const StatechartProfilePtr& profile);
177
178 static RobotNameHelperPtr Create(const std::string& robotXmlFilename,
179 const StatechartProfilePtr& profile = nullptr);
180
181 RobotNameHelper(const RobotInfoNodePtr& robotInfo,
182 const StatechartProfilePtr& profile = nullptr);
183
185
187
189
191
192 Arm getArm(const std::string& side) const;
193
194 RobotArm getRobotArm(const std::string& side, const VirtualRobot::RobotPtr& robot) const;
195
196 const std::vector<std::string>& getProfiles() const;
197
198 const RobotInfoNodePtr& getRobotInfoNodePtr() const;
199
200 private:
201 static RobotInfoNodePtr readRobotInfo(const RapidXmlReaderNode& infoNode);
202
204 self()
205 {
206 return *this;
207 }
208
209 Node root;
210 std::vector<std::string> profiles;
211 RobotInfoNodePtr robotInfo;
212 };
213} // namespace armarx
std::string str(const T &t)
Node(const RobotInfoNodePtr &robotInfo)
Node select(const std::string &name, const std::vector< std::string > &profiles)
armarx::RobotArm RobotArm
static const std::string LocationLeft
const RobotInfoNodePtr & getRobotInfoNodePtr() const
RobotNameHelper(const RobotNameHelper &)=default
RobotNameHelper(RobotNameHelper &&)=default
RobotNameHelper & operator=(const RobotNameHelper &)=default
Arm getArm(const std::string &side) const
RobotNameHelper & operator=(RobotNameHelper &&)=default
static RobotNameHelperPtr Create(const RobotInfoNodePtr &robotInfo, const StatechartProfilePtr &profile)
RobotArm getRobotArm(const std::string &side, const VirtualRobot::RobotPtr &robot) const
static const std::string LocationRight
static void writeRobotInfoNode(const RobotInfoNodePtr &n, std::ostream &str, std::size_t indent=0, char indentChar=' ')
RobotNameHelper(const RobotInfoNodePtr &robotInfo, const StatechartProfilePtr &profile=nullptr)
const std::vector< std::string > & getProfiles() const
std::string select(const std::string &path) const
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::shared_ptr< class StatechartProfile > StatechartProfilePtr
std::shared_ptr< class RobotNameHelper > RobotNameHelperPtr
Arm & operator=(Arm &&)=default
Arm & operator=(const Arm &)=default
std::string getHandRootNode() const
std::shared_ptr< const RobotNameHelper > getRobotNameHelper() const
std::string getSide() const
Arm()=default
std::string getTCP() const
std::string getAbsoluteHandModelPath() const
std::string getHandModelPath() const
std::string getKinematicChain() const
std::string getFullHandCollisionModel() const
std::string getTorsoKinematicChain() const
std::string getHandUnitName() const
Arm(const Arm &)=default
Arm(Arm &&)=default
std::string getPalmCollisionModel() const
std::string getEndEffector() const
friend class RobotNameHelper
std::string getForceTorqueSensor() const
std::string getForceTorqueSensorFrame() const
std::string getHandModelPackage() const
std::string getHandControllerName() const
RobotArm addRobot(const VirtualRobot::RobotPtr &robot) const
std::string select(const std::string &path) const
Arm(const std::shared_ptr< const RobotNameHelper > &rnh, const std::string &side)
std::string getMemoryHandName() const
RobotArm(const Arm &arm, const VirtualRobot::RobotPtr &robot)
Eigen::Matrix4f getTcp2HandRootTransform() const
RobotArm & operator=(RobotArm &&)=default
RobotArm(RobotArm &&)=default
friend struct Arm
std::string getSide() const
VirtualRobot::RobotNodePtr getPalmCollisionModel() const
RobotArm & operator=(const RobotArm &)=default
VirtualRobot::TriMeshModelPtr getFullHandCollisionModel() const
VirtualRobot::RobotNodeSetPtr getTorsoKinematicChain() const
const VirtualRobot::RobotPtr & getRobot() const
const Arm & getArm() const
friend class RobotNameHelper
VirtualRobot::RobotNodeSetPtr getKinematicChain() const
RobotArm(const RobotArm &)=default
RobotArm()=default
VirtualRobot::RobotNodePtr getHandRootNode() const
VirtualRobot::RobotNodePtr getTCP() const