6#include <SimoxUtility/algorithm/string.h>
7#include <SimoxUtility/json.h>
8#include <SimoxUtility/shapes/AxisAlignedBoundingBox.h>
9#include <SimoxUtility/shapes/OrientedBox.h>
18 namespace fs = std::filesystem;
22 const path& relObjectsPath,
24 _packageName(packageName),
25 _absPackageDataDir(packageDataDir),
26 _relObjectsPath(relObjectsPath),
33 const path& relObjectsPath,
36 _packageName(packageName),
37 _absPackageDataDir(packageDataDir),
38 _relObjectsPath(relObjectsPath),
46 this->_logError = enabled;
64 return _id.className();
80 ObjectInfo::objectDirectory(
const bool fixDataPath)
const
92 const std::string& suffix,
93 const bool fixDataPath)
const
95 std::string extension = _extension;
96 if (extension.at(0) !=
'.')
98 extension =
"." + extension;
100 std::string filename = _id.className() + suffix + extension;
104 loc.
relativePath = objectDirectory(fixDataPath) / filename;
105 loc.
absolutePath = _absPackageDataDir / objectDirectory(
false) / filename;
118 return file(
".urdf");
127 std::optional<PackageFileLocation>
130 if (fs::is_regular_file(
simoxXML().absolutePath))
134 else if (fs::is_regular_file(
urdf().absolutePath))
138 else if (fs::is_regular_file(
sdf().absolutePath))
151 return file(
".xml",
"_articulated",
true);
157 return file(
".urdf",
"_articulated",
true);
163 return file(
".sdf",
"_articulated");
166 std::optional<PackageFileLocation>
202 return file(
".json",
"_bb");
208 return file(
".json",
"_names");
211 std::optional<simox::AxisAlignedBoundingBox>
220 catch (
const std::exception& e)
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>();
238 simox::AxisAlignedBoundingBox aabb(
min,
max);
240 static const float prec = 1e-2f;
242 << aabb.center().transpose() <<
"\n"
243 << center.transpose() <<
"\n"
246 << aabb.extents().transpose() <<
"\n"
247 << extents.transpose() <<
"\n"
250 << aabb.min().transpose() <<
"\n"
251 <<
min.transpose() <<
"\n"
254 << aabb.max().transpose() <<
"\n"
255 <<
max.transpose() <<
"\n"
268 std::optional<simox::OrientedBox<float>>
277 catch (
const std::exception& e)
288 nlohmann::json joobb = j.at(
"oobb");
289 auto pos = joobb.at(
"pos").get<Eigen::Vector3f>();
291 auto extents = joobb.at(
"extents").get<Eigen::Vector3f>();
293 Eigen::Vector3f corner = pos - ori * extents / 2;
296 corner, ori.col(0) * extents(0), ori.col(1) * extents(1), ori.col(2) * extents(2));
298 static const float prec = 1e-2f;
299 ARMARX_CHECK(oobb.rotation().isApprox(ori, prec)) << oobb.rotation() <<
"\n"
303 if (extents.squaredNorm() < 1e5f * 1e5f)
306 <<
VAROUT(oobb.center().transpose()) <<
"\n"
307 <<
VAROUT(pos.transpose()) <<
"\n"
308 <<
VAROUT(extents.norm()) <<
"\n"
311 <<
VAROUT(oobb.dimensions().transpose()) <<
"\n"
312 <<
VAROUT(extents.transpose()) <<
"\n"
313 <<
VAROUT(extents.norm()) <<
"\n"
327 std::optional<std::vector<std::string>>
330 return loadNames(
"recognized_name");
333 std::optional<std::vector<std::string>>
336 return loadNames(
"spoken_name");
339 std::optional<std::vector<std::string>>
340 ObjectInfo::loadNames(
const std::string& jsonKey)
const
351 catch (
const nlohmann::json::exception& e)
360 catch (
const std::exception& e)
370 return json.at(jsonKey).get<std::vector<std::string>>();
381 namespace fs = std::filesystem;
384 if (!fs::is_regular_file(
simoxXML().absolutePath))
386 if (
false and _logError)
388 ARMARX_WARNING <<
"Expected simox object file for object " << *
this <<
": "
393 if (
false and not fs::is_regular_file(
wavefrontObj().absolutePath))
397 ARMARX_WARNING <<
"Expected wavefront object file (.obj) for object " << *
this
411 return os << rhs.
id();
A known object ID of the form "Dataset/ClassName" or "Dataset/ClassName/InstanceName".
std::string className() const
std::string dataset() const
std::string str() const
Return "dataset/className" or "dataset/className/instanceName".
Accessor for the object files.
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
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.
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
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).
std::string package
Name of the ArmarX package.
std::string relativePath
Relative to the package's data directory.