-
Notifications
You must be signed in to change notification settings - Fork 65
/
ModelLoader.h
200 lines (171 loc) · 6.03 KB
/
ModelLoader.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
/*
* Copyright (C) 2016 Fondazione Istituto Italiano di Tecnologia
*
* Licensed under either the GNU Lesser General Public License v3.0 :
* https://www.gnu.org/licenses/lgpl-3.0.html
* or the GNU Lesser General Public License v2.1 :
* https://www.gnu.org/licenses/old-licenses/lgpl-2.1.html
* at your option.
*/
#ifndef IDYNTREE_MODEL_LOADER_H
#define IDYNTREE_MODEL_LOADER_H
#include <iDynTree/Model/Model.h>
#include <iDynTree/Sensors/Sensors.h>
#include <memory>
#include <string>
#include <vector>
namespace iDynTree
{
/**
* \ingroup iDynTreeModelIO
*
* Options for the iDynTree parser.
*/
struct ModelParserOptions
{
// TODO: migrate to set/get
// ???: what about adding a search dir instead of a filename?
public:
/**
* If true, add to the model the sensor frames
* as additional frames with the same name of the sensor.
* If there is already a link or additional frame with the same
* name of the sensor, a warning is printed and no frame is added.
*/
bool addSensorFramesAsAdditionalFrames;
/**
* Original filename of the URDF sensor parsed.
*
* This attribute is the original filename of the URDF sensor parsed.
* It is useful when loading a model from a string, if that URDF string
* has <geometry> tags that point to external meshes. To find the location
* of this external meshes, we need also the original filename of the URDF file.
*/
std::string originalFilename;
/** Default options
*
* - addSensorFramesAsAdditionalFrames = True
* - originalFilename = empty string
*/
ModelParserOptions();
};
/**
* \ingroup iDynTreeModelIO
*
* Helper class to load a model from a generic format.
*
*/
class ModelLoader
{
private:
class ModelLoaderPimpl;
std::unique_ptr<ModelLoaderPimpl> m_pimpl;
public:
/**
* @name Constructor/Destructor
*/
//@{
/**
* Constructor
*
*/
ModelLoader();
~ModelLoader();
//@}
/**
* @name Model loading and definition methods
* This methods are used to load the structure of your model.
*/
//@{
const ModelParserOptions& parsingOptions() const;
void setParsingOptions(const ModelParserOptions& options);
/**
* Load the model of the robot from a string.
*
* @param modelString string containg the model of the robot.
* @param filetype type of the file to load, currently supporting only urdf type.
*
*/
bool loadModelFromString(const std::string & modelString, const std::string & filetype="urdf");
/**
* Load the model of the robot from an external file.
*
* @param filename path to the file to load
* @param filetype type of the file to load, currently supporting only urdf type.
*
*/
bool loadModelFromFile(const std::string & filename, const std::string & filetype="urdf");
/**
* Load reduced model from another model, specifyng only the desired joints in the model.
*
* All other joints will be considered to be fixed to their default position,
* and their child links will be lumped together.
*
* @note the order of the degreese of freedom of the newly loaded model
* will be the one specified by the input joints serialization, i.e. consideredJoints
*
* @param[in] filename path to the file to load.
* @param[in] consideredJoints list of joints to consider in the model.
* @param[in] filetype (optional) explicit definition of the type of the loaded file. Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
* \note Until https://github.com/robotology/idyntree/issues/132 is fixed, this method does not
* accounts for sensors.
*
*/
bool loadReducedModelFromFullModel(const Model& fullModel,
const std::vector<std::string> & consideredJoints,
const std::string filetype="");
/**
* Load reduced model from string, specifyng only the desired joints in the model.
*
* All other joints will be considered to be fixed to their default position,
* and their child links will be lumped together.
*
* @param[in] modelString string containg the model of the robot.
* @param[in] consideredJoints list of joints to consider in the model.
* @param[in] filetype (optional) explicit definiton of the filetype to load.
* Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
*
*/
bool loadReducedModelFromString(const std::string modelString,
const std::vector<std::string> & consideredJoints,
const std::string filetype="");
/**
* Load reduced model from file, specifyng only the desired joints in the model.
*
* All other joints will be considered to be fixed to their default position,
* and their child links will be lumped together.
*
* @param[in] filename path to the file to load.
* @param[in] consideredJoints list of joints to consider in the model.
* @param[in] filetype (optional) explicit definiton of the filetype to load.
* Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
*
*/
bool loadReducedModelFromFile(const std::string filename,
const std::vector<std::string> & consideredJoints,
const std::string filetype="");
/**
* Get the loaded model.
*
*/
const Model & model();
/**
* Get the loaded sensors.
*/
const SensorsList & sensors();
/**
* Return true if the model have been correctly true.
*
* @return True if the model was loaded correctly.
*/
bool isValid();
//@}
};
}
#endif