6#include <SimoxUtility/math/convert/mat3f_to_rpy.h>
43 def->topic(reportTopic);
44 def->topic(globalRobotPoseTopic);
45 def->topic(gobalRobotPoseCorrectionTopic);
48 def->optional(properties.updateWorkingMemory,
49 "working_memory.update",
50 "If enabled, updates the global pose in the working memory");
51 def->optional(properties.workingMemoryUpdateFrequency,
"working_memory.update_frequency");
54 def->optional(properties.longtermMemoryName,
56 "Which legacy long-term memory to use if longterm_memory.update"
57 "or longterm_memory.retrieve_initial_pose are set");
58 def->optional(properties.updateLongTermMemory,
59 "longterm_memory.update",
60 "If enabled, updates the global pose in the longterm memory");
61 def->optional(properties.longtermMemoryUpdateFrequency,
"longterm_memory.update_frequency");
62 def->optional(properties.initialPoseFromLTM,
"longterm_memory.retrieve_initial_pose");
66 def->optional(properties.updateArMem,
"armem.update",
"If enabled, updates ArMem");
67 def->optional(properties.armMemUpdateFrequency,
"armem.update_frequency");
70 def->component(robotStateComponent,
71 "RobotStateComponent",
72 "robot_state_component",
73 "The name of the RobotStateComponent. Used to get local transformation of "
78 const std::string fullTypeName =
79 ::IceProxy::armarx::LocalizationUnitInterface::ice_staticId();
80 properties.localizationUnitName =
84 def->optional(properties.useLocalizationUnit,
85 "localizationUnit.use",
86 "If enabled, connects to the localization unit");
87 def->optional(properties.localizationUnitName,
88 "localizationUnit.proxyName",
89 "If enabled, connects to the localization unit");
99 if (not connected.load())
102 <<
"Will not publish self localization as some dependencies are not available.";
107 publishSelfLocalizationOnTopic(map_T_robot);
110 publishSelfLocalizationToArMem(map_T_robot);
113 ARMARX_DEBUG <<
"publishSelfLocalizationToWorkingMemory";
114 publishSelfLocalizationToWorkingMemory(map_T_robot);
116 ARMARX_DEBUG <<
"publishSelfLocalizationToLongtermMemory";
117 publishSelfLocalizationToLongtermMemory(map_T_robot);
124 if (properties.updateWorkingMemory)
128 if (properties.updateLongTermMemory or properties.initialPoseFromLTM)
133 if (properties.useLocalizationUnit)
143 connected.store(
false);
147 SelfLocalization::publishSelfLocalizationOnTopic(
const PoseStamped& map_T_robot)
151 const Eigen::Isometry3f globalPose = global_T_map * map_T_robot.
pose;
153 const float yaw = simox::math::mat3f_to_rpy(globalPose.linear()).z();
155 PlatformPose platformPose;
156 platformPose.x = globalPose.translation().x();
157 platformPose.y = globalPose.translation().y();
158 platformPose.rotationAroundZ = yaw;
159 platformPose.timestampInMicroSeconds =
164 globalRobotPoseTopic->reportGlobalRobotPose(toTransformStamped(globalPoseStamped));
170 .frame = robotRootFrame,
177 const auto odomLookupResult =
178 transformReaderPlugin->get().lookupTransform(odomQuery);
180 if (odomLookupResult.status ==
181 armem::robot_state::client::localization::TransformResult::Status::Success)
183 const Eigen::Isometry3f robot_T_odom =
184 odomLookupResult.transform.transform.inverse();
185 const Eigen::Isometry3f map_T_odom = map_T_robot.
pose * robot_T_odom;
186 const Eigen::Isometry3f global_T_odom = global_T_map * map_T_odom;
187 const PoseStamped globalOdomPoseStamped{.pose = global_T_odom,
190 gobalRobotPoseCorrectionTopic->reportGlobalRobotPoseCorrection(
191 toTransformStamped(globalOdomPoseStamped));
193 if (properties.useLocalizationUnit)
196 localizationUnitPrx->reportGlobalRobotPoseCorrection(
197 toTransformStamped(globalOdomPoseStamped));
208 <<
"Failed to publish global pose on topics as the following "
209 "exception occured: "
220 SelfLocalization::publishSelfLocalizationToWorkingMemory(
const PoseStamped& map_T_robot)
224 if (not properties.updateWorkingMemory or not workingMemory)
233 if (not skipper.checkFrequency(
"workingMemoryUpdate",
234 properties.workingMemoryUpdateFrequency))
239 const Eigen::Affine3f globalPose = global_T_map * map_T_robot.pose;
249 wmAgentInstance->setPose(reportPose);
250 const std::string robotAgentId =
251 wmAgentsMemory->upsertEntityByName(wmAgentInstance->getName(), wmAgentInstance);
252 wmAgentInstance->setId(robotAgentId);
254 catch (IceUtil::Exception
const& ex)
256 ARMARX_WARNING <<
"Caught exception while updating the working memory:\n" << ex;
261 SelfLocalization::publishSelfLocalizationToLongtermMemory(
const PoseStamped& map_T_robot)
265 if (not properties.updateLongTermMemory or not longtermMemory)
271 <<
"Self localisation memory segment is not set";
274 if (not skipper.checkFrequency(
"longtermMemoryUpdate",
275 properties.longtermMemoryUpdateFrequency))
280 if (not ltmPoseEntityId)
285 const Eigen::Affine3f globalPose = global_T_map * map_T_robot.pose;
293 poseEntity->setName(agentName);
294 poseEntity->putAttribute(
"pose", reportPose);
295 poseEntity->setId(*ltmPoseEntityId);
297 ltmSelfLocalisationSegment->upsertEntity(*ltmPoseEntityId, poseEntity);
299 catch (IceUtil::Exception
const& ex)
301 ARMARX_WARNING <<
"Caught exception while updating the longterm memory:\n" << ex;
306 SelfLocalization::toTransform(
const PoseStamped& poseStamped)
308 return {.header{.parentFrame =
MapFrame,
311 .timestamp = poseStamped.timestamp},
312 .transform = poseStamped.pose};
316 SelfLocalization::publishSelfLocalizationToArMem(
const PoseStamped& map_T_robot)
320 if (not properties.updateArMem)
326 if (not skipper.checkFrequency(
"armMemUpdateFrequency", properties.armMemUpdateFrequency))
331 const armem::robot_state::client::localization::TransformQuery odomQuery{
333 .frame = robotRootFrame,
335 .timestamp = map_T_robot.timestamp}};
337 const auto odomLookupResult = transformReaderPlugin->get().lookupTransform(odomQuery);
339 if (odomLookupResult.status !=
340 armem::robot_state::client::localization::TransformResult::Status::Success)
346 const Eigen::Isometry3f robot_T_odom = odomLookupResult.
transform.transform.inverse();
347 const Eigen::Isometry3f map_T_odom = map_T_robot.pose * robot_T_odom;
349 const armem::robot_state::localization::Transform mapToOdomTransform{
353 .timestamp = map_T_robot.timestamp},
354 .transform = map_T_odom};
356 const auto status = transformWriterPlugin->get().commitTransform(mapToOdomTransform);
365 SelfLocalization::toTransformStamped(
const PoseStamped& poseStamped)
369 header.frame = robotRootFrame;
370 header.agent = agentName;
371 header.timestampInMicroSeconds = poseStamped.timestamp.toMicroSecondsSinceEpoch();
375 transform.transform = poseStamped.pose.matrix();
381 SelfLocalization::setupArMem()
385 if (not properties.updateArMem)
395 ARMARX_INFO <<
"Publishing world to map transform";
402 .transform = global_T_map,
408 <<
"Something went wrong during setupArMem. Updating ArMem will be deactivated";
409 properties.updateArMem =
false;
414 SelfLocalization::setupWorkingMemory()
418 if (not properties.updateWorkingMemory or not workingMemory)
425 wmAgentsMemory = workingMemory->getAgentInstancesSegment();
427 wmAgentInstance =
new memoryx::AgentInstance();
428 wmAgentInstance->setSharedRobot(robotStateComponent->getSynchronizedRobot());
429 wmAgentInstance->setAgentFilePath(robotStateComponent->getRobotFilename());
430 wmAgentInstance->setName(agentName);
434 SelfLocalization::setupLongTermMemory()
438 if (not longtermMemory)
444 ltmSelfLocalisationSegment = longtermMemory->getSelfLocalisationSegment();
446 if (not properties.updateLongTermMemory)
453 const auto getOrCreatePoseEntityID = [&]() -> std::string
455 const memoryx::EntityBasePtr existingPoseEntity =
456 ltmSelfLocalisationSegment->getEntityByName(agentName);
458 if (existingPoseEntity)
460 return existingPoseEntity->getId();
464 ARMARX_WARNING <<
"No pose in longterm memory found for agent: " << agentName;
471 poseEntity->setName(agentName);
472 poseEntity->putAttribute(
"pose", pose);
474 return ltmSelfLocalisationSegment->addEntity(poseEntity);
479 ltmPoseEntityId = getOrCreatePoseEntityID();
485 <<
"Could not setup LongTermMemory. Updating LongTermMemory will be deactivated.";
486 properties.updateLongTermMemory =
false;
496 if (properties.useLocalizationUnit)
498 getProxy(localizationUnitPrx, properties.localizationUnitName);
514 agentName = robotStateComponent->getRobotName();
515 robotRootFrame = armarx::armem::robot_state::constants::
521 if (properties.updateWorkingMemory)
523 getProxy(workingMemory,
"WorkingMemory");
525 <<
"but working memory is not available.";
526 setupWorkingMemory();
528 if (properties.updateLongTermMemory or properties.initialPoseFromLTM)
530 getProxy(longtermMemory, properties.longtermMemoryName);
532 <<
"Long-term memory updates or pose retrieval are enabled, "
533 <<
"but long-term memory is not available.";
535 setupLongTermMemory();
540 connected.store(
true);
541 onConnectCalled =
true;
550 ARMARX_INFO <<
"SelfLocalization::onReconnectComponent";
554 setupWorkingMemory();
555 setupLongTermMemory();
557 connected.store(
true);
562 std::optional<Eigen::Affine3f>
567 if (not properties.initialPoseFromLTM or not longtermMemory)
572 ARMARX_INFO <<
"Querying initial pose from long term memory";
574 if (not ltmSelfLocalisationSegment)
576 ARMARX_FATAL <<
"Could not retrieve global pose from long-term memory."
577 <<
"Reason: Self-localization segment not available.";
586 const memoryx::EntityBasePtr poseEntity =
587 ltmSelfLocalisationSegment->getEntityByName(agentName);
590 ARMARX_FATAL <<
"Could not retrieve global pose from long-term memory."
591 <<
"Reason: Pose entity not available.";
595 const auto poseEntityId = poseEntity->getId();
596 ARMARX_DEBUG <<
"Using pose entity from LTM with ID: " << poseEntityId;
597 const memoryx::EntityAttributeBasePtr poseAttribute = poseEntity->getAttribute(
"pose");
599 if (not poseAttribute)
601 ARMARX_FATAL <<
"Could not retrieve global pose from long-term memory."
602 <<
"Reason: Pose attribute not available.";
608 armarx::VariantPtr::dynamicCast(poseAttribute->getValueAt(0))
613 ARMARX_FATAL <<
"Could not retrieve global pose from long-term memory."
614 <<
"Reason: Casting to framed pose failed.";
618 const Eigen::Affine3f pose(framedPose->toGlobalEigen(robot));
619 ARMARX_INFO <<
"Long-term memory global pose prior: " << pose.matrix();
625 ARMARX_FATAL <<
"Could not retrieve global pose from long-term memory."
626 <<
"Reason: unknown.";
641 return robotRootFrame;
653 return transformWriterPlugin->get();
659 return transformReaderPlugin->get();
static DateTime Now()
Current time on the virtual clock.
Default component property definition container.
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
PluginT * addPlugin(const std::string prefix="", ParamsT &&... params)
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
VirtualRobot::RobotPtr createLocalClone()
Clones the structure of this remote robot to a local instance.
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
virtual ~SelfLocalization()
void onInitComponent() override
const armem::robot_state::client::localization::TransformReaderInterface & getTransformReader() const
void onReconnectComponent()
void onDisconnectComponent() override
std::optional< Eigen::Affine3f > globalPoseFromLongTermMemory() const
const std::string & getAgentName() const noexcept
const std::string & getRobotRootFrame() const noexcept
armem::robot_state::client::localization::TransformWriterInterface & getTransformWriter() const
void onConnectComponent() override
PropertyDefinitionsPtr createPropertyDefinitions() override
virtual Eigen::Isometry3f worldToMapTransform() const =0
static transformation from world to map
const std::shared_ptr< VirtualRobot::Robot > & getRobot() const noexcept
void publishSelfLocalization(const PoseStamped &map_T_robot)
Duration toDurationSinceEpoch() const
std::int64_t toMicroSeconds() const
Returns the amount of microseconds.
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
#define ARMARX_INFO
The normal logging level.
#define ARMARX_FATAL
The logging level for unexpected behaviour, that will lead to a seriously malfunctioning program and ...
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
std::string const GlobalFrame
Variable of the global coordinate system.
std::shared_ptr< class Robot > RobotPtr
const VariantTypeId FramedPose
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::string GetHandledExceptionString()
std::string const OdometryFrame
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
std::string const MapFrame
std::string PropertyDefinitionContainer_ice_class_name(std::string const &full_type_name)
IceInternal::Handle< FramedPose > FramedPosePtr
IceInternal::Handle< SimpleEntity > SimpleEntityPtr
armarx::DateTime timestamp
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Isometry3f pose