Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • sw/armarx/robot-api
  • uwkce_singer/robot-api
  • untcg_hofmann/robot-api
  • ulqba_korosakov/RobotAPI
4 results
Show changes
Commits on Source (51)
Showing
with 284 additions and 106 deletions
......@@ -107,9 +107,9 @@ namespace armarx::viz
float angle = std::acos(naturalDir.dot(dir));
if (cross.squaredNorm() < 1.0e-12f)
{
// Directions are almost colinear ==> Do no rotation
// Directions are almost colinear ==> Angle is either 0 or 180 deg
cross = Eigen::Vector3f::UnitX();
angle = 0.0f;
// Keep angle
}
Eigen::Vector3f axis = cross.normalized();
Eigen::Quaternionf ori(Eigen::AngleAxisf(angle, axis));
......
......@@ -275,13 +275,18 @@ namespace armarx
void fillExampleLayer(viz::Layer& layer, double timeInSeconds)
{
for (int i = 0; i < 6; ++i)
{
Eigen::Vector3f pos = Eigen::Vector3f::Zero();
pos.z() = +300.0f;
Eigen::Vector3f pos = Eigen::Vector3f(-200.0, 200.0, 300);
pos.x() += -300 * i;
Eigen::Vector3f normal = Eigen::Vector3f::Zero();
normal(i / 2) = (i % 2 == 0 ? 1.0 : -1.0);
viz::ArrowCircle circle = viz::ArrowCircle("circle")
viz::ArrowCircle circle = viz::ArrowCircle("circle " + std::to_string(i))
.position(pos)
.radius(100.0f)
.normal(normal)
.width(10.0f)
.color(viz::Color::fromRGBA(255, 0, 255));
......
......@@ -47,6 +47,7 @@ namespace armarx::armem::server::robot_state
RobotStateMemory::RobotStateMemory() :
descriptionSegment(iceAdapter()),
proprioceptionSegment(iceAdapter()),
exteroceptionSegment(iceAdapter()),
localizationSegment(iceAdapter()),
commonVisu(descriptionSegment, proprioceptionSegment, localizationSegment)
{
......@@ -86,6 +87,7 @@ namespace armarx::armem::server::robot_state
setMemoryName(armem::robot_state::memoryID.memoryName);
descriptionSegment.defineProperties(defs, prefix + "desc.");
exteroceptionSegment.defineProperties(defs, prefix + "ext.");
proprioceptionSegment.defineProperties(defs, prefix + "prop.");
localizationSegment.defineProperties(defs, prefix + "loc.");
commonVisu.defineProperties(defs, prefix + "visu.");
......@@ -104,6 +106,7 @@ namespace armarx::armem::server::robot_state
{
descriptionSegment.init();
proprioceptionSegment.init();
exteroceptionSegment.init();
localizationSegment.init();
commonVisu.init();
......
......@@ -38,6 +38,7 @@
#include <RobotAPI/libraries/armem_robot_state/server/proprioception/RobotUnitData.h>
#include <RobotAPI/libraries/armem_robot_state/server/proprioception/RobotUnitReader.h>
#include <RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.h>
#include <RobotAPI/libraries/armem_robot_state/server/exteroception/Segment.h>
namespace armarx::plugins
......@@ -105,6 +106,9 @@ namespace armarx::armem::server::robot_state
proprioception::Segment proprioceptionSegment;
armem::data::MemoryID robotUnitProviderID;
// - exteroception
exteroception::Segment exteroceptionSegment;
// - localization
localization::Segment localizationSegment;
......
......@@ -172,7 +172,7 @@ namespace armarx
// HandUnitInterface interface
public:
std::string getHandName(const Ice::Current&) override;
std::string getHandName(const Ice::Current& = Ice::emptyCurrent) override;
void setJointForces(const NameValueMap& targetJointForces, const Ice::Current&) override;
void sendJointCommands(const NameCommandMap& targetJointCommands, const Ice::Current&) override;
};
......
......@@ -108,6 +108,7 @@ set(SLICE_FILES
aron.ice
aron/Aron.ice
aron/test/AronConversionTestInterface.ice
armem.ice
......
/*
* This file is part of ArmarX.
*
* ArmarX is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 as
* published by the Free Software Foundation.
*
* ArmarX is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* package SpeechX::aron_cpp_to_python_conv_test
* author Rainer Kartmann ( rainer dot kartmann at kit dot edu )
* date 2023
* copyright http://www.gnu.org/licenses/gpl-2.0.txt
* GNU General Public License
*/
#pragma once
#include <RobotAPI/interface/aron/Aron.ice>
module armarx { module aron { module test
{
module dto
{
struct TestAronConversionRequest
{
string aronClassName;
::armarx::aron::data::dto::Dict probe;
};
struct TestAronConversionResponse
{
bool success;
string errorMessage;
::armarx::aron::data::dto::Dict probe;
};
};
module dti
{
interface AronConversionTestInterface
{
dto::TestAronConversionResponse testAronConversion(dto::TestAronConversionRequest req);
};
};
};};};
......@@ -104,6 +104,7 @@ namespace armarx
{
return findObject(id.dataset(), id.className());
}
std::optional<ObjectInfo> ObjectFinder::findObject(const objpose::ObjectPose& obj) const
{
return findObject(obj.objectID);
......
......@@ -59,12 +59,17 @@ namespace armarx
return _id.str();
}
ObjectInfo::path ObjectInfo::objectDirectory() const
ObjectInfo::path ObjectInfo::objectDirectory(const bool fixDataPath) const
{
if(fixDataPath)
{
return _relObjectsPath / _id.dataset() / _id.className();
}
return path(_packageName) / _relObjectsPath / _id.dataset() / _id.className();
}
PackageFileLocation ObjectInfo::file(const std::string& _extension, const std::string& suffix) const
PackageFileLocation ObjectInfo::file(const std::string& _extension, const std::string& suffix, const bool fixDataPath) const
{
std::string extension = _extension;
if (extension.at(0) != '.')
......@@ -75,8 +80,8 @@ namespace armarx
PackageFileLocation loc;
loc.package = _packageName;
loc.relativePath = objectDirectory() / filename;
loc.absolutePath = _absPackageDataDir / loc.relativePath;
loc.relativePath = objectDirectory(fixDataPath) / filename;
loc.absolutePath = _absPackageDataDir / objectDirectory(false) / filename;
return loc;
}
......@@ -86,14 +91,49 @@ namespace armarx
return file(".xml");
}
PackageFileLocation ObjectInfo::urdf() const
{
return file(".urdf");
}
PackageFileLocation ObjectInfo::sdf() const
{
return file(".sdf");
}
std::optional<PackageFileLocation> ObjectInfo::getModel() const
{
if (fs::is_regular_file(simoxXML().absolutePath))
{
return simoxXML();
}
else if (fs::is_regular_file(urdf().absolutePath))
{
return urdf();
}
else if (fs::is_regular_file(sdf().absolutePath))
{
return sdf();
}
else
{
return std::nullopt;
}
}
PackageFileLocation ObjectInfo::articulatedSimoxXML() const
{
return file(".xml", "_articulated");
return file(".xml", "_articulated", true);
}
PackageFileLocation ObjectInfo::articulatedUrdf() const
{
return file(".urdf", "_articulated");
return file(".urdf", "_articulated", true);
}
PackageFileLocation ObjectInfo::articulatedSdf() const
{
return file(".sdf", "_articulated");
}
std::optional<PackageFileLocation> ObjectInfo::getArticulatedModel() const
......@@ -106,6 +146,10 @@ namespace armarx
{
return articulatedUrdf();
}
else if (fs::is_regular_file(articulatedSdf().absolutePath))
{
return articulatedSdf();
}
else
{
return std::nullopt;
......@@ -293,5 +337,3 @@ std::ostream& armarx::operator<<(std::ostream& os, const ObjectInfo& rhs)
{
return os << rhs.id();
}
......@@ -76,14 +76,19 @@ namespace armarx
std::string idStr() const;
PackageFileLocation file(const std::string& extension, const std::string& suffix = "") const;
PackageFileLocation file(const std::string& extension, const std::string& suffix = "", bool fixDataPath = false) const;
PackageFileLocation simoxXML() const;
PackageFileLocation urdf() const;
PackageFileLocation sdf() const;
/// Return the Simox XML, URDF or SDF, if one exists.
std::optional<PackageFileLocation> getModel() const;
PackageFileLocation articulatedSimoxXML() const;
PackageFileLocation articulatedUrdf() const;
/// Return the articulated Simox XML or URDF, if one exists.
PackageFileLocation articulatedSdf() const;
/// Return the articulated Simox XML, URDF or SDF, if one exists.
std::optional<PackageFileLocation> getArticulatedModel() const;
......@@ -131,7 +136,7 @@ namespace armarx
private:
path objectDirectory() const;
path objectDirectory(bool fixDataPath) const;
std::optional<std::vector<std::string>> loadNames(const std::string& jsonKey) const;
......
......@@ -83,7 +83,7 @@ void armarx::objects::to_json(simox::json::json& j, const SceneObject& rhs)
j["instanceName"] = rhs.instanceName;
j["collection"] = rhs.collection;
j["position"] = rhs.position;
j["orientation"] = rhs.orientation;
j["orientation"] = rhs.orientation.normalized();
if (rhs.isStatic.has_value())
{
j["isStatic"] = rhs.isStatic.value();
......@@ -106,6 +106,7 @@ void armarx::objects::from_json(const simox::json::json& j, SceneObject& rhs)
j.at("collection").get_to(rhs.collection);
j.at("position").get_to(rhs.position);
j.at("orientation").get_to(rhs.orientation);
rhs.orientation.normalize();
if (j.count("isStatic"))
{
......
......@@ -63,12 +63,16 @@ namespace armarx::armem::client::util
};
subscribe(subscriptionID, cb);
}
template <class CalleeT>
void subscribe(const MemoryID& subscriptionID, CalleeT* callee, MemberCallbackUpdatedOnly<CalleeT> callback)
{
auto cb = [callee, callback](const MemoryID&, const std::vector<MemoryID>& updatedSnapshotIDs)
{
(callee->*callback)(updatedSnapshotIDs);
if(callee)
{
(callee->*callback)(updatedSnapshotIDs);
}
};
subscribe(subscriptionID, cb);
}
......
......@@ -6,11 +6,10 @@
#include <map>
#include <optional>
#include <ostream>
#include <type_traits>
#include <utility>
#include <vector>
#include <type_traits>
// ICE
#include <IceUtil/Handle.h>
#include <IceUtil/Time.h>
......@@ -34,15 +33,13 @@
#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
// RobotAPI Armem
#include <RobotAPI/libraries/armem/core/error.h>
#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
#include <RobotAPI/libraries/armem/util/util.h>
#include <RobotAPI/libraries/armem/client/Query.h>
#include <RobotAPI/libraries/armem/client/Reader.h>
#include <RobotAPI/libraries/armem/client/query/Builder.h>
#include <RobotAPI/libraries/armem/client/query/selectors.h>
#include <RobotAPI/libraries/armem/core/error.h>
#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
#include <RobotAPI/libraries/armem/util/util.h>
#include <RobotAPI/libraries/armem_laser_scans/aron/LaserScan.aron.generated.h>
#include <RobotAPI/libraries/armem_laser_scans/aron_conversions.h>
#include <RobotAPI/libraries/armem_laser_scans/types.h>
......@@ -62,21 +59,22 @@ namespace armarx::armem::laser_scans::client
Reader::registerPropertyDefinitions(armarx::PropertyDefinitionsPtr& def)
{
ARMARX_DEBUG << "TransformReader: registerPropertyDefinitions";
registerPropertyDefinitions(def);
const std::string prefix = propertyPrefix;
}
void Reader::connect()
void
Reader::connect()
{
// Wait for the memory to become available and add it as dependency.
ARMARX_IMPORTANT << "MappingDataReader: Waiting for memory '"
<< constants::memoryName << "' ...";
ARMARX_IMPORTANT << "MappingDataReader: Waiting for memory '" << constants::memoryName
<< "' ...";
try
{
memoryReader = memoryNameSystem.useReader(MemoryID().withMemoryName(constants::memoryName));
ARMARX_IMPORTANT << "MappingDataReader: Connected to memory '" << constants::memoryName << "'";
memoryReader =
memoryNameSystem.useReader(MemoryID().withMemoryName(constants::memoryName));
ARMARX_IMPORTANT << "MappingDataReader: Connected to memory '" << constants::memoryName
<< "'";
}
catch (const armem::error::CouldNotResolveMemoryServer& e)
{
......@@ -91,27 +89,43 @@ namespace armarx::armem::laser_scans::client
armarx::armem::client::query::Builder qb;
ARMARX_VERBOSE << "Query for agent: " << query.agent
<< " memory name: " << constants::memoryName;
<< " memory name: " << constants::memoryName;
if (query.sensorList.empty()) // all sensors
{
// clang-format off
qb
auto& snapshots = qb
.coreSegments().withName(constants::memoryName)
.providerSegments().withName(query.agent)
.entities().all()
.snapshots().timeRange(query.timeRange.min, query.timeRange.max);
.snapshots();
// clang-format on
if (query.timeRange.has_value())
{
snapshots.timeRange(query.timeRange->min, query.timeRange->max);
}
else
{
snapshots.latest();
}
}
else
{
// clang-format off
qb
auto& snapshots = qb
.coreSegments().withName(constants::memoryName)
.providerSegments().withName(query.agent)
.entities().withNames(query.sensorList)
.snapshots().timeRange(query.timeRange.min, query.timeRange.max);
.snapshots();
// clang-format on
if (query.timeRange.has_value())
{
snapshots.timeRange(query.timeRange->min, query.timeRange->max);
}
else
{
snapshots.latest();
}
}
return qb;
......@@ -126,16 +140,14 @@ namespace armarx::armem::laser_scans::client
ARMARX_WARNING << "No entities!";
}
const auto convert =
[](const auto& aronLaserScanStamped,
const wm::EntityInstance & ei) -> LaserScanStamped
const auto convert = [](const auto& aronLaserScanStamped,
const wm::EntityInstance& ei) -> LaserScanStamped
{
LaserScanStamped laserScanStamped;
fromAron(aronLaserScanStamped, laserScanStamped);
const auto ndArrayNavigator =
aron::data::NDArray::DynamicCast(
ei.data()->getElement("scan"));
aron::data::NDArray::DynamicCast(ei.data()->getElement("scan"));
ARMARX_CHECK_NOT_NULL(ndArrayNavigator);
......@@ -145,47 +157,48 @@ namespace armarx::armem::laser_scans::client
};
// loop over all entities and their snapshots
providerSegment.forEachEntity([&outV, &convert](const wm::Entity & entity)
{
// If we don't need this warning, we could directly iterate over the snapshots.
if (entity.empty())
providerSegment.forEachEntity(
[&outV, &convert](const wm::Entity& entity)
{
ARMARX_WARNING << "Empty history for " << entity.id();
}
ARMARX_DEBUG << "History size: " << entity.size();
entity.forEachInstance([&outV, &convert](const wm::EntityInstance & entityInstance)
{
if (const auto o = tryCast<arondto::LaserScanStamped>(entityInstance))
// If we don't need this warning, we could directly iterate over the snapshots.
if (entity.empty())
{
outV.push_back(convert(*o, entityInstance));
ARMARX_WARNING << "Empty history for " << entity.id();
}
ARMARX_DEBUG << "History size: " << entity.size();
entity.forEachInstance(
[&outV, &convert](const wm::EntityInstance& entityInstance)
{
if (const auto o = tryCast<arondto::LaserScanStamped>(entityInstance))
{
outV.push_back(convert(*o, entityInstance));
}
return true;
});
return true;
});
return true;
});
return outV;
}
Reader::Result Reader::queryData(const Query& query) const
Reader::Result
Reader::queryData(const Query& query) const
{
const auto qb = buildQuery(query);
ARMARX_DEBUG << "[MappingDataReader] query ... ";
const armem::client::QueryResult qResult =
memoryReader.query(qb.buildQueryInput());
const armem::client::QueryResult qResult = memoryReader.query(qb.buildQueryInput());
ARMARX_DEBUG << "[MappingDataReader] result: " << qResult;
if (not qResult.success)
{
ARMARX_WARNING << "Failed to query data from memory: "
<< qResult.errorMessage;
return {.laserScans = {},
.sensors = {},
.status = Result::Status::Error,
ARMARX_WARNING << "Failed to query data from memory: " << qResult.errorMessage;
return {.laserScans = {},
.sensors = {},
.status = Result::Status::Error,
.errorMessage = qResult.errorMessage};
}
......@@ -195,16 +208,17 @@ namespace armarx::armem::laser_scans::client
const auto laserScans = asLaserScans(providerSegment);
std::vector<std::string> sensors;
providerSegment.forEachEntity([&sensors](const wm::Entity & entity)
{
sensors.push_back(entity.name());
return true;
});
providerSegment.forEachEntity(
[&sensors](const wm::Entity& entity)
{
sensors.push_back(entity.name());
return true;
});
return {.laserScans = laserScans,
.sensors = sensors,
.status = Result::Status::Success,
return {.laserScans = laserScans,
.sensors = sensors,
.status = Result::Status::Success,
.errorMessage = ""};
}
} // namespace armarx::armem::vision::laser_scans::client
} // namespace armarx::armem::laser_scans::client
......@@ -72,7 +72,8 @@ namespace armarx::armem::laser_scans::client
{
std::string agent;
TimeRange timeRange;
// if not provided, only latest is queried
std::optional<TimeRange> timeRange;
// if empty, all sensors will be queried
std::vector<std::string> sensorList;
......
......@@ -301,8 +301,7 @@ namespace armarx::armem::server::laser_scans
if (robots.count(name) == 0)
{
ARMARX_CHECK_NOT_NULL(virtualRobotReader);
const auto robot = virtualRobotReader->getRobot(
name, timestamp, VirtualRobot::RobotIO::RobotDescription::eStructure);
const auto robot = virtualRobotReader->getRobot(name);
if (robot)
{
......@@ -324,7 +323,7 @@ namespace armarx::armem::server::laser_scans
}
else
{
ARMARX_VERBOSE << "Faield to synchronize robot `" << name << "`";
ARMARX_INFO << deactivateSpam(10) << "Failed to synchronize robot `" << name << "`";
}
}
return entry.first;
......
......@@ -27,6 +27,22 @@ Core segment type of Object/Class.
<armarx::arondto::PackagePath />
</ObjectChild>
<ObjectChild key="urdfPath">
<armarx::arondto::PackagePath />
</ObjectChild>
<ObjectChild key="articulatedUrdfPath">
<armarx::arondto::PackagePath />
</ObjectChild>
<ObjectChild key="sdfPath">
<armarx::arondto::PackagePath />
</ObjectChild>
<ObjectChild key="articulatedSdfPath">
<armarx::arondto::PackagePath />
</ObjectChild>
<ObjectChild key="meshWrlPath">
<armarx::arondto::PackagePath />
</ObjectChild>
......
......@@ -47,7 +47,7 @@ namespace armarx::armem::articulated_object
ARMARX_DEBUG << "Object " << name << " available";
auto obj = VirtualRobot::RobotIO::loadRobot(
ArmarXDataPath::resolvePath(it->xml.serialize().path),
it->xml.toSystemPath(),
VirtualRobot::RobotIO::eStructure);
if (not obj)
......
......@@ -3,44 +3,53 @@
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <VirtualRobot/Robot.h>
#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
#include <ArmarXCore/core/logging/Logging.h>
#include <ArmarXCore/core/system/ArmarXDataPath.h>
#include <VirtualRobot/Robot.h>
#include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
namespace armarx::armem::articulated_object
{
armem::articulated_object::ArticulatedObject convert(
const VirtualRobot::Robot& obj,
const armem::Time& timestamp)
armem::articulated_object::ArticulatedObject
convert(const VirtualRobot::Robot& obj, const armem::Time& timestamp)
{
ARMARX_DEBUG << "Filename is " << obj.getFilename();
// TODO(fabian.reister): remove "PriorKnowledgeData" below
const std::vector<std::string> packages =
armarx::CMakePackageFinder::FindAllArmarXSourcePackages();
const std::string package = armarx::ArmarXDataPath::getProject(packages, obj.getFilename());
return armem::articulated_object::ArticulatedObject
// make sure that the relative path is without the 'package/' prefix
const std::string fileRelPath = [&obj, &package]() -> std::string
{
.description = {
.name = obj.getType(),
.xml = PackagePath(armarx::ArmarXDataPath::getProject(
{"PriorKnowledgeData"}, obj.getFilename()),
obj.getFilename())
},
.instance = obj.getName(),
.config = {
.timestamp = timestamp,
.globalPose = Eigen::Affine3f(obj.getRootNode()->getGlobalPose()),
.jointMap = obj.getJointValues()
},
.timestamp = timestamp};
if (simox::alg::starts_with(obj.getFilename(), package))
{
// remove "package" + "/"
const std::string fixedFilename = obj.getFilename().substr(package.size() + 1, -1);
return fixedFilename;
}
return obj.getFilename();
}();
return armem::articulated_object::ArticulatedObject{
.description = {.name = obj.getType(),
.xml = PackagePath(armarx::ArmarXDataPath::getProject(
{package}, fileRelPath),
obj.getFilename())},
.instance = obj.getName(),
.config = {.timestamp = timestamp,
.globalPose = Eigen::Affine3f(obj.getRootNode()->getGlobalPose()),
.jointMap = obj.getJointValues()},
.timestamp = timestamp};
}
bool
ArticulatedObjectWriter::storeArticulatedObject(
const VirtualRobot::RobotPtr& articulatedObject,
const armem::Time& timestamp)
ArticulatedObjectWriter::storeArticulatedObject(const VirtualRobot::RobotPtr& articulatedObject,
const armem::Time& timestamp)
{
ARMARX_CHECK_NOT_NULL(articulatedObject);
......
......@@ -191,7 +191,11 @@ namespace armarx::armem::server::obj::clazz
}
};
setPathIfExists(data.simoxXmlPath, info.simoxXML());
setPathIfExists(data.urdfPath, info.urdf());
setPathIfExists(data.sdfPath, info.sdf());
setPathIfExists(data.articulatedSimoxXmlPath, info.articulatedSimoxXML());
setPathIfExists(data.articulatedUrdfPath, info.articulatedUrdf());
setPathIfExists(data.articulatedSdfPath, info.articulatedSdf());
setPathIfExists(data.meshObjPath, info.wavefrontObj());
setPathIfExists(data.meshWrlPath, info.meshWrl());
......
......@@ -222,12 +222,21 @@ namespace armarx::armem::server::obj::instance
stats.numUpdated++;
VirtualRobot::RobotPtr robot = robots.get(provided.robotName, provided.providerName);
if(not robot)
{
ARMARX_INFO << deactivateSpam(1) << "Failed to retrieve robot `" << provided.robotName << "`.";
}
// robot may be null!
// Update the robot to obtain correct local -> global transformation
if (robot and robotSyncTimestamp != timestamp)
{
ARMARX_CHECK(robots.reader->synchronizeRobot(*robot, timestamp));
ARMARX_CHECK(robots.reader->synchronizeRobot(*robot, timestamp))
<< "Failed to synchronize robot to timestamp " << timestamp
<< ". This is " << (Clock::Now() - timestamp).toSecondsDouble() << " seconds in the past.";
robotSyncTimestamp = timestamp;
......@@ -1302,14 +1311,13 @@ namespace armarx::armem::server::obj::instance
{
// Try to fetch the robot.
ARMARX_CHECK_NOT_NULL(reader);
bool warnings = false;
VirtualRobot::RobotPtr robot = reader->getRobot(
robotName, Clock::Now(),
VirtualRobot::RobotIO::RobotDescription::eStructure, warnings);
VirtualRobot::RobotIO::RobotDescription::eStructure);
if (robot)
{
reader->synchronizeRobot(*robot, Clock::Now());
ARMARX_CHECK(reader->synchronizeRobot(*robot, Clock::Now()));
// Store robot if valid.
loaded.emplace(robotName, robot);
}
......