ObjectInfo.cpp
Go to the documentation of this file.
1#include "ObjectInfo.h"
2
3#include <filesystem>
4#include <optional>
5
6#include <SimoxUtility/algorithm/string.h>
7#include <SimoxUtility/json.h>
8#include <SimoxUtility/shapes/AxisAlignedBoundingBox.h>
9#include <SimoxUtility/shapes/OrientedBox.h>
10
15
16namespace armarx
17{
18 namespace fs = std::filesystem;
19
20 ObjectInfo::ObjectInfo(const std::string& packageName,
21 const ObjectInfo::path& packageDataDir,
22 const path& relObjectsPath,
23 const ObjectID& id) :
24 _packageName(packageName),
25 _absPackageDataDir(packageDataDir),
26 _relObjectsPath(relObjectsPath),
27 _id(id)
28 {
29 }
30
31 ObjectInfo::ObjectInfo(const std::string& packageName,
32 const ObjectInfo::path& packageDataDir,
33 const path& relObjectsPath,
34 const std::string& dataset,
35 const std::string& className) :
36 _packageName(packageName),
37 _absPackageDataDir(packageDataDir),
38 _relObjectsPath(relObjectsPath),
39 _id(dataset, className)
40 {
41 }
42
43 void
45 {
46 this->_logError = enabled;
47 }
48
49 std::string
51 {
52 return _packageName;
53 }
54
55 std::string
57 {
58 return _id.dataset();
59 }
60
61 std::string
63 {
64 return _id.className();
65 }
66
69 {
70 return _id;
71 }
72
73 std::string
75 {
76 return _id.str();
77 }
78
80 ObjectInfo::objectDirectory(const bool fixDataPath) const
81 {
82 if (fixDataPath)
83 {
84 return _relObjectsPath / _id.dataset() / _id.className();
85 }
86
87 return path(_packageName) / _relObjectsPath / _id.dataset() / _id.className();
88 }
89
91 ObjectInfo::file(const std::string& _extension,
92 const std::string& suffix,
93 const bool fixDataPath) const
94 {
95 std::string extension = _extension;
96 if (extension.at(0) != '.')
97 {
98 extension = "." + extension;
99 }
100 std::string filename = _id.className() + suffix + extension;
101
103 loc.package = _packageName;
104 loc.relativePath = objectDirectory(fixDataPath) / filename;
105 loc.absolutePath = _absPackageDataDir / objectDirectory(false) / filename;
106 return loc;
107 }
108
111 {
112 return file(".xml");
113 }
114
117 {
118 return file(".urdf");
119 }
120
123 {
124 return file(".sdf");
125 }
126
127 std::optional<PackageFileLocation>
129 {
130 if (fs::is_regular_file(simoxXML().absolutePath))
131 {
132 return simoxXML();
133 }
134 else if (fs::is_regular_file(urdf().absolutePath))
135 {
136 return urdf();
137 }
138 else if (fs::is_regular_file(sdf().absolutePath))
139 {
140 return sdf();
141 }
142 else
143 {
144 return std::nullopt;
145 }
146 }
147
150 {
151 return file(".xml", "_articulated", true);
152 }
153
156 {
157 return file(".urdf", "_articulated", true);
158 }
159
162 {
163 return file(".sdf", "_articulated");
164 }
165
166 std::optional<PackageFileLocation>
168 {
169 if (fs::is_regular_file(articulatedSimoxXML().absolutePath))
170 {
171 return articulatedSimoxXML();
172 }
173 else if (fs::is_regular_file(articulatedUrdf().absolutePath))
174 {
175 return articulatedUrdf();
176 }
177 else if (fs::is_regular_file(articulatedSdf().absolutePath))
178 {
179 return articulatedSdf();
180 }
181 else
182 {
183 return std::nullopt;
184 }
185 }
186
189 {
190 return file(".wrl");
191 }
192
195 {
196 return file(".obj");
197 }
198
201 {
202 return file(".json", "_bb");
203 }
204
207 {
208 return file(".json", "_names");
209 }
210
211 std::optional<simox::AxisAlignedBoundingBox>
213 {
214 nlohmann::json j;
215 try
216 {
217 ARMARX_CHECK(std::filesystem::exists(boundingBoxJson().absolutePath));
218 j = nlohmann::read_json(boundingBoxJson().absolutePath);
219 }
220 catch (const std::exception& e)
221 {
222 if (_logError)
223 {
224 ARMARX_ERROR << e.what();
225 }
226 return std::nullopt;
227 }
228
229 try
230 {
231
232 nlohmann::json jaabb = j.at("aabb");
233 auto center = jaabb.at("center").get<Eigen::Vector3f>();
234 auto extents = jaabb.at("extents").get<Eigen::Vector3f>();
235 auto min = jaabb.at("min").get<Eigen::Vector3f>();
236 auto max = jaabb.at("max").get<Eigen::Vector3f>();
237
238 simox::AxisAlignedBoundingBox aabb(min, max);
239
240 static const float prec = 1e-2f;
241 ARMARX_CHECK_LESS_EQUAL((aabb.center() - center).norm(), prec)
242 << aabb.center().transpose() << "\n"
243 << center.transpose() << "\n"
244 << id();
245 ARMARX_CHECK_LESS_EQUAL((aabb.extents() - extents).norm(), prec)
246 << aabb.extents().transpose() << "\n"
247 << extents.transpose() << "\n"
248 << id();
249 ARMARX_CHECK_LESS_EQUAL((aabb.min() - min).norm(), prec)
250 << aabb.min().transpose() << "\n"
251 << min.transpose() << "\n"
252 << id();
253 ARMARX_CHECK_LESS_EQUAL((aabb.max() - max).norm(), prec)
254 << aabb.max().transpose() << "\n"
255 << max.transpose() << "\n"
256 << id();
257
258 return aabb;
259 }
260 catch (...)
261 {
263 }
264
265 return std::nullopt;
266 }
267
268 std::optional<simox::OrientedBox<float>>
270 {
271 nlohmann::json j;
272 try
273 {
274 ARMARX_CHECK(std::filesystem::exists(boundingBoxJson().absolutePath));
275 j = nlohmann::read_json(boundingBoxJson().absolutePath);
276 }
277 catch (const std::exception& e)
278 {
279 if (_logError)
280 {
281 ARMARX_ERROR << e.what();
282 }
283 return std::nullopt;
284 }
285
286 try
287 {
288 nlohmann::json joobb = j.at("oobb");
289 auto pos = joobb.at("pos").get<Eigen::Vector3f>();
290 auto ori = joobb.at("ori").get<Eigen::Quaternionf>().toRotationMatrix();
291 auto extents = joobb.at("extents").get<Eigen::Vector3f>();
292
293 Eigen::Vector3f corner = pos - ori * extents / 2;
294
296 corner, ori.col(0) * extents(0), ori.col(1) * extents(1), ori.col(2) * extents(2));
297
298 static const float prec = 1e-2f;
299 ARMARX_CHECK(oobb.rotation().isApprox(ori, prec)) << oobb.rotation() << "\n"
300 << ori << "\n"
301 << id();
302 // If the object is too large, the above precision will trigger a false positive.
303 if (extents.squaredNorm() < 1e5f * 1e5f)
304 {
305 ARMARX_CHECK_LESS_EQUAL((oobb.center() - pos).norm(), prec)
306 << VAROUT(oobb.center().transpose()) << "\n"
307 << VAROUT(pos.transpose()) << "\n"
308 << VAROUT(extents.norm()) << "\n"
309 << VAROUT(id());
310 ARMARX_CHECK_LESS_EQUAL((oobb.dimensions() - extents).norm(), prec)
311 << VAROUT(oobb.dimensions().transpose()) << "\n"
312 << VAROUT(extents.transpose()) << "\n"
313 << VAROUT(extents.norm()) << "\n"
314 << VAROUT(id());
315 }
316 return oobb;
317 }
318 catch (...)
319 {
320 ARMARX_WARNING << "File " << QUOTED(boundingBoxJson().absolutePath) << "is faulty!";
322 }
323
324 return std::nullopt;
325 }
326
327 std::optional<std::vector<std::string>>
329 {
330 return loadNames("recognized_name");
331 }
332
333 std::optional<std::vector<std::string>>
335 {
336 return loadNames("spoken_name");
337 }
338
339 std::optional<std::vector<std::string>>
340 ObjectInfo::loadNames(const std::string& jsonKey) const
341 {
343 if (fs::is_regular_file(file.absolutePath))
344 {
345 nlohmann::json json;
346
347 try
348 {
349 json = nlohmann::read_json(file.absolutePath);
350 }
351 catch (const nlohmann::json::exception& e)
352 {
353 if (_logError)
354 {
355 ARMARX_WARNING << "Failed to parse JSON file " << file.absolutePath << ": \n"
356 << e.what();
357 }
358 return std::nullopt;
359 }
360 catch (const std::exception& e)
361 {
362 if (_logError)
363 {
364 ARMARX_WARNING << "Failed to read file " << file.absolutePath << ": \n"
365 << e.what();
366 }
367 return std::nullopt;
368 }
369
370 return json.at(jsonKey).get<std::vector<std::string>>();
371 }
372 else
373 {
374 return std::nullopt;
375 }
376 }
377
378 bool
380 {
381 namespace fs = std::filesystem;
382 bool result = true;
383
384 if (!fs::is_regular_file(simoxXML().absolutePath))
385 {
386 if (false and _logError)
387 {
388 ARMARX_WARNING << "Expected simox object file for object " << *this << ": "
390 }
391 result = false;
392 }
393 if (false and not fs::is_regular_file(wavefrontObj().absolutePath))
394 {
395 if (_logError)
396 {
397 ARMARX_WARNING << "Expected wavefront object file (.obj) for object " << *this
398 << ": " << wavefrontObj().absolutePath;
399 }
400 result = false;
401 }
402
403 return result;
404 }
405
406} // namespace armarx
407
408std::ostream&
409armarx::operator<<(std::ostream& os, const ObjectInfo& rhs)
410{
411 return os << rhs.id();
412}
#define VAROUT(x)
#define QUOTED(x)
A known object ID of the form "Dataset/ClassName" or "Dataset/ClassName/InstanceName".
Definition ObjectID.h:11
std::string className() const
Definition ObjectID.h:30
std::string dataset() const
Definition ObjectID.h:24
std::string str() const
Return "dataset/className" or "dataset/className/instanceName".
Definition ObjectID.cpp:60
Accessor for the object files.
Definition ObjectInfo.h:37
PackageFileLocation namesJson() const
File containing recognized and spoken names of objects.
PackageFileLocation wavefrontObj() const
virtual bool checkPaths() const
Checks the existence of expected files.
std::string className() const
std::optional< simox::AxisAlignedBoundingBox > loadAABB() const
Load the AABB (axis-aligned bounding-box) from the bounding box JSON file.
PackageFileLocation urdf() const
std::optional< simox::OrientedBox< float > > loadOOBB() const
Load the OOBB (object-oriented bounding box) from the bounding box JSON file.
std::string idStr() const
std::optional< std::vector< std::string > > loadSpokenNames() const
Load names to use when verbalizing an object name.
PackageFileLocation articulatedSdf() const
PackageFileLocation articulatedUrdf() const
std::string package() const
void setLogError(bool enabled)
PackageFileLocation sdf() const
std::filesystem::path path
Definition ObjectInfo.h:39
PackageFileLocation file(const std::string &extension, const std::string &suffix="", bool fixDataPath=false) const
PackageFileLocation boundingBoxJson() const
PackageFileLocation meshWrl() const
std::optional< PackageFileLocation > getArticulatedModel() const
Return the articulated Simox XML, URDF or SDF, if one exists.
ObjectInfo(const std::string &packageName, const path &absPackageDataDir, const path &relObjectsPath, const ObjectID &id)
ObjectInfo.
ObjectID id() const
Return "dataset/name".
std::optional< PackageFileLocation > getModel() const
Return the Simox XML, URDF or SDF, if one exists.
std::optional< std::vector< std::string > > loadRecognizedNames() const
Load names to use when matched when recognizing an object by name.
PackageFileLocation simoxXML() const
PackageFileLocation articulatedSimoxXML() const
std::string dataset() const
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_CHECK_LESS_EQUAL(lhs, rhs)
This macro evaluates whether lhs is less or equal (<=) rhs and if it turns out to be false it will th...
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
Quaternion< float, 0 > Quaternionf
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::ostream & operator<<(std::ostream &os, const PythonApplicationManager::Paths &paths)
std::string GetHandledExceptionString()
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
std::vector< T > min(const std::vector< T > &v1, const std::vector< T > &v2)
std::filesystem::path absolutePath
The absolute path (in the host's file system).
Definition ObjectInfo.h:30
std::string package
Name of the ArmarX package.
Definition ObjectInfo.h:25
std::string relativePath
Relative to the package's data directory.
Definition ObjectInfo.h:28