SelfLocalization.cpp
Go to the documentation of this file.
1#include "SelfLocalization.h"
2
3#include <cmath>
4#include <optional>
5
6#include <SimoxUtility/math/convert/mat3f_to_rpy.h>
7
14
20
25
26namespace armarx
27{
28
30 {
31 addPlugin(transformReaderPlugin);
32 addPlugin(transformWriterPlugin);
33 }
34
36
39 {
42
43 def->topic(reportTopic);
44 def->topic(globalRobotPoseTopic);
45 def->topic(gobalRobotPoseCorrectionTopic);
46
47 // old working memory
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");
52
53 // old long-term memory
54 def->optional(properties.longtermMemoryName,
55 "longterm_memory",
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");
63
64
65 // armem
66 def->optional(properties.updateArMem, "armem.update", "If enabled, updates ArMem");
67 def->optional(properties.armMemUpdateFrequency, "armem.update_frequency");
68
69 // other components
70 def->component(robotStateComponent,
71 "RobotStateComponent",
72 "robot_state_component",
73 "The name of the RobotStateComponent. Used to get local transformation of "
74 "laser scanners");
75
76 // initialize properties: localization unit
77 {
78 const std::string fullTypeName =
79 ::IceProxy::armarx::LocalizationUnitInterface::ice_staticId();
80 properties.localizationUnitName =
82 }
83
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");
90
91 return def;
92 }
93
94 void
96 {
98
99 if (not connected.load())
100 {
102 << "Will not publish self localization as some dependencies are not available.";
103 return;
104 }
105
106 ARMARX_DEBUG << "publishSelfLocalizationOnTopic";
107 publishSelfLocalizationOnTopic(map_T_robot);
108
109 ARMARX_DEBUG << "publishSelfLocalizationToArMem";
110 publishSelfLocalizationToArMem(map_T_robot);
111
112 // legacy
113 ARMARX_DEBUG << "publishSelfLocalizationToWorkingMemory";
114 publishSelfLocalizationToWorkingMemory(map_T_robot);
115
116 ARMARX_DEBUG << "publishSelfLocalizationToLongtermMemory";
117 publishSelfLocalizationToLongtermMemory(map_T_robot);
118 }
119
120 void
122 {
123 // Legacy memory.
124 if (properties.updateWorkingMemory)
125 {
126 usingProxy("WorkingMemory");
127 }
128 if (properties.updateLongTermMemory or properties.initialPoseFromLTM)
129 {
130 usingProxy(properties.longtermMemoryName);
131 }
132
133 if (properties.useLocalizationUnit)
134 {
135 ARMARX_INFO << "Localization unit is enabled.";
136 usingProxy(properties.localizationUnitName);
137 }
138 }
139
140 void
142 {
143 connected.store(false);
144 }
145
146 void
147 SelfLocalization::publishSelfLocalizationOnTopic(const PoseStamped& map_T_robot)
148 {
150
151 const Eigen::Isometry3f globalPose = global_T_map * map_T_robot.pose;
152
153 const float yaw = simox::math::mat3f_to_rpy(globalPose.linear()).z();
154
155 PlatformPose platformPose;
156 platformPose.x = globalPose.translation().x();
157 platformPose.y = globalPose.translation().y();
158 platformPose.rotationAroundZ = yaw;
159 platformPose.timestampInMicroSeconds =
161
162 const PoseStamped globalPoseStamped{.pose = globalPose, .timestamp = map_T_robot.timestamp};
163
164 globalRobotPoseTopic->reportGlobalRobotPose(toTransformStamped(globalPoseStamped));
165
166
167 {
169 .header = {.parentFrame = OdometryFrame,
170 .frame = robotRootFrame,
171 .agent = agentName,
172 .timestamp = map_T_robot.timestamp}};
173
174 try
175 {
176
177 const auto odomLookupResult =
178 transformReaderPlugin->get().lookupTransform(odomQuery);
179
180 if (odomLookupResult.status ==
181 armem::robot_state::client::localization::TransformResult::Status::Success)
182 {
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,
188 .timestamp = map_T_robot.timestamp};
189
190 gobalRobotPoseCorrectionTopic->reportGlobalRobotPoseCorrection(
191 toTransformStamped(globalOdomPoseStamped));
192
193 if (properties.useLocalizationUnit)
194 {
195 ARMARX_CHECK_NOT_NULL(localizationUnitPrx);
196 localizationUnitPrx->reportGlobalRobotPoseCorrection(
197 toTransformStamped(globalOdomPoseStamped));
198 }
199 }
200 else
201 {
202 ARMARX_WARNING << deactivateSpam(60) << odomLookupResult.errorMessage;
203 }
204 }
205 catch (...)
206 {
208 << "Failed to publish global pose on topics as the following "
209 "exception occured: "
211 return;
212 }
213 }
214
215 // To my future me: publish 3D stamped pose
216 reportTopic->reportCorrectedPose(platformPose.x, platformPose.y, yaw);
217 }
218
219 void
220 SelfLocalization::publishSelfLocalizationToWorkingMemory(const PoseStamped& map_T_robot)
221 {
223
224 if (not properties.updateWorkingMemory or not workingMemory)
225 {
226 return;
227 }
228
229 ARMARX_CHECK_NOT_NULL(wmAgentsMemory) << "Agents memory not set";
230 ARMARX_CHECK_NOT_NULL(wmAgentInstance) << "Agent instance not set";
231
232 // check if enough time has passed since last update
233 if (not skipper.checkFrequency("workingMemoryUpdate",
234 properties.workingMemoryUpdateFrequency))
235 {
236 return;
237 }
238
239 const Eigen::Affine3f globalPose = global_T_map * map_T_robot.pose;
240
241 const FramedPosePtr reportPose =
242 new FramedPose(globalPose.linear(), globalPose.translation(), GlobalFrame, agentName);
243
244 try
245 {
246 // This seems to be the way to update the current pose
247 // Since in simulation another component (SelfLocalizationDynamicSimulation) updates this memory location
248 // it is a bad idea to enable the working memory update in simulation
249 wmAgentInstance->setPose(reportPose);
250 const std::string robotAgentId =
251 wmAgentsMemory->upsertEntityByName(wmAgentInstance->getName(), wmAgentInstance);
252 wmAgentInstance->setId(robotAgentId);
253 }
254 catch (IceUtil::Exception const& ex)
255 {
256 ARMARX_WARNING << "Caught exception while updating the working memory:\n" << ex;
257 }
258 }
259
260 void
261 SelfLocalization::publishSelfLocalizationToLongtermMemory(const PoseStamped& map_T_robot)
262 {
264
265 if (not properties.updateLongTermMemory or not longtermMemory)
266 {
267 return;
268 }
269
270 ARMARX_CHECK_NOT_NULL(ltmSelfLocalisationSegment)
271 << "Self localisation memory segment is not set";
272
273 // check if enough time has passed since last update
274 if (not skipper.checkFrequency("longtermMemoryUpdate",
275 properties.longtermMemoryUpdateFrequency))
276 {
277 return;
278 }
279
280 if (not ltmPoseEntityId)
281 {
282 ARMARX_WARNING << "Pose entity id not available";
283 }
284
285 const Eigen::Affine3f globalPose = global_T_map * map_T_robot.pose;
286
287 const FramedPosePtr reportPose =
288 new FramedPose(globalPose.linear(), globalPose.translation(), GlobalFrame, agentName);
289
290 try
291 {
292 memoryx::SimpleEntityPtr poseEntity = new memoryx::SimpleEntity();
293 poseEntity->setName(agentName);
294 poseEntity->putAttribute("pose", reportPose);
295 poseEntity->setId(*ltmPoseEntityId);
296 // We just update the 'pose' attribute since ID and name have been set by the inital insert
297 ltmSelfLocalisationSegment->upsertEntity(*ltmPoseEntityId, poseEntity);
298 }
299 catch (IceUtil::Exception const& ex)
300 {
301 ARMARX_WARNING << "Caught exception while updating the longterm memory:\n" << ex;
302 }
303 }
304
306 SelfLocalization::toTransform(const PoseStamped& poseStamped)
307 {
308 return {.header{.parentFrame = MapFrame,
309 .frame = OdometryFrame,
310 .agent = agentName,
311 .timestamp = poseStamped.timestamp},
312 .transform = poseStamped.pose};
313 }
314
315 void
316 SelfLocalization::publishSelfLocalizationToArMem(const PoseStamped& map_T_robot)
317 {
319
320 if (not properties.updateArMem)
321 {
322 return;
323 }
324
325 // check if enough time has passed since last update
326 if (not skipper.checkFrequency("armMemUpdateFrequency", properties.armMemUpdateFrequency))
327 {
328 return;
329 }
330
331 const armem::robot_state::client::localization::TransformQuery odomQuery{
332 .header = {.parentFrame = OdometryFrame,
333 .frame = robotRootFrame,
334 .agent = agentName,
335 .timestamp = map_T_robot.timestamp}};
336
337 const auto odomLookupResult = transformReaderPlugin->get().lookupTransform(odomQuery);
338
339 if (odomLookupResult.status !=
340 armem::robot_state::client::localization::TransformResult::Status::Success)
341 {
342 ARMARX_WARNING << deactivateSpam(60) << odomLookupResult.errorMessage;
343 return;
344 }
345
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;
348
349 const armem::robot_state::localization::Transform mapToOdomTransform{
350 .header = {.parentFrame = MapFrame,
351 .frame = OdometryFrame,
352 .agent = agentName,
353 .timestamp = map_T_robot.timestamp},
354 .transform = map_T_odom};
355
356 const auto status = transformWriterPlugin->get().commitTransform(mapToOdomTransform);
357
358 if (not status)
359 {
360 ARMARX_WARNING << "Failed to commit transform";
361 }
362 }
363
364 TransformStamped
365 SelfLocalization::toTransformStamped(const PoseStamped& poseStamped)
366 {
367 FrameHeader header;
368 header.parentFrame = GlobalFrame;
369 header.frame = robotRootFrame;
370 header.agent = agentName;
371 header.timestampInMicroSeconds = poseStamped.timestamp.toMicroSecondsSinceEpoch();
372
373 TransformStamped transform;
374 transform.header = header;
375 transform.transform = poseStamped.pose.matrix();
376
377 return transform;
378 }
379
380 void
381 SelfLocalization::setupArMem()
382 {
384
385 if (not properties.updateArMem)
386 {
387 return;
388 }
389
390 ARMARX_INFO << "setup ArMem ...";
391
392 // transformReader = std::make_unique<armem::client::robot_state::localization::TransformReader>(*this);
393 // transformWriter = std::make_unique<armem::client::robot_state::localization::TransformWriter>(*this);
394
395 ARMARX_INFO << "Publishing world to map transform";
396 // Publish World to Map transform (static transform)
397 const armem::robot_state::localization::Transform worldToMapTransform{
398 .header = {.parentFrame = GlobalFrame,
399 .frame = MapFrame,
400 .agent = getAgentName(),
401 .timestamp = Clock::Now()},
402 .transform = global_T_map,
403 };
404
405 if (not transformWriterPlugin->get().commitTransform(worldToMapTransform))
406 {
408 << "Something went wrong during setupArMem. Updating ArMem will be deactivated";
409 properties.updateArMem = false;
410 }
411 }
412
413 void
414 SelfLocalization::setupWorkingMemory()
415 {
417
418 if (not properties.updateWorkingMemory or not workingMemory)
419 {
420 return;
421 }
422
423 ARMARX_INFO << "setup WorkingMemory ...";
424
425 wmAgentsMemory = workingMemory->getAgentInstancesSegment();
426
427 wmAgentInstance = new memoryx::AgentInstance();
428 wmAgentInstance->setSharedRobot(robotStateComponent->getSynchronizedRobot());
429 wmAgentInstance->setAgentFilePath(robotStateComponent->getRobotFilename());
430 wmAgentInstance->setName(agentName);
431 }
432
433 void
434 SelfLocalization::setupLongTermMemory()
435 {
437
438 if (not longtermMemory)
439 {
440 return;
441 }
442
443 // Always initialize this segment variable. It is used in globalPoseFromLongTermMemory() as well.
444 ltmSelfLocalisationSegment = longtermMemory->getSelfLocalisationSegment();
445
446 if (not properties.updateLongTermMemory)
447 {
448 return;
449 }
450
451 ARMARX_INFO << "setup LongTermMemory ...";
452
453 const auto getOrCreatePoseEntityID = [&]() -> std::string
454 {
455 const memoryx::EntityBasePtr existingPoseEntity =
456 ltmSelfLocalisationSegment->getEntityByName(agentName);
457
458 if (existingPoseEntity)
459 {
460 return existingPoseEntity->getId();
461 }
462
463 // if poseEntity does not exist, create it ....
464 ARMARX_WARNING << "No pose in longterm memory found for agent: " << agentName;
465 ARMARX_WARNING << "Self localisation will start at origin";
466
467 FramedPosePtr pose =
468 new FramedPose(Eigen::Matrix4f::Identity(), GlobalFrame, agentName);
469
470 memoryx::SimpleEntityPtr poseEntity = new memoryx::SimpleEntity();
471 poseEntity->setName(agentName);
472 poseEntity->putAttribute("pose", pose);
473
474 return ltmSelfLocalisationSegment->addEntity(poseEntity);
475 };
476
477 try
478 {
479 ltmPoseEntityId = getOrCreatePoseEntityID();
480 ARMARX_INFO << "Entity ID: " << *ltmPoseEntityId;
481 }
482 catch (...)
483 {
485 << "Could not setup LongTermMemory. Updating LongTermMemory will be deactivated.";
486 properties.updateLongTermMemory = false;
487 }
488 }
489
490 void
492 {
494
495 // const bool reconnecting = robot == nullptr;
496 if (properties.useLocalizationUnit)
497 {
498 getProxy(localizationUnitPrx, properties.localizationUnitName);
499 }
500
501 if (onConnectCalled) // reconnecting
502 {
504 return;
505 }
506
507
508 ARMARX_INFO << "connecting ...";
509 global_T_map = worldToMapTransform();
510
511 robot = RemoteRobot::createLocalClone(robotStateComponent);
512 RemoteRobot::synchronizeLocalClone(robot, robotStateComponent);
513
514 agentName = robotStateComponent->getRobotName();
515 robotRootFrame = armarx::armem::robot_state::constants::
516 robotRootNodeName; // robot->getRootNode()->getName();
517
518 setupArMem();
519
520 // legacy
521 if (properties.updateWorkingMemory)
522 {
523 getProxy(workingMemory, "WorkingMemory");
524 ARMARX_CHECK_NOT_NULL(workingMemory) << "Working memory updates are enabled, "
525 << "but working memory is not available.";
526 setupWorkingMemory();
527 }
528 if (properties.updateLongTermMemory or properties.initialPoseFromLTM)
529 {
530 getProxy(longtermMemory, properties.longtermMemoryName);
531 ARMARX_CHECK_NOT_NULL(longtermMemory)
532 << "Long-term memory updates or pose retrieval are enabled, "
533 << "but long-term memory is not available.";
534
535 setupLongTermMemory();
536 }
537
539
540 connected.store(true);
541 onConnectCalled = true;
542 ARMARX_INFO << "... done.";
543 }
544
545 void
547 {
549
550 ARMARX_INFO << "SelfLocalization::onReconnectComponent";
551 setupArMem();
552
553 // legacy
554 setupWorkingMemory();
555 setupLongTermMemory();
556
557 connected.store(true);
558
559 ARMARX_INFO << "... done.";
560 }
561
562 std::optional<Eigen::Affine3f>
564 {
566
567 if (not properties.initialPoseFromLTM or not longtermMemory)
568 {
569 return std::nullopt;
570 }
571
572 ARMARX_INFO << "Querying initial pose from long term memory";
573
574 if (not ltmSelfLocalisationSegment)
575 {
576 ARMARX_FATAL << "Could not retrieve global pose from long-term memory."
577 << "Reason: Self-localization segment not available.";
578 return std::nullopt;
579 }
580
581 try
582 {
583 ARMARX_CHECK_NOT_NULL(ltmSelfLocalisationSegment);
584
585 // Load estimatedPose from longterm memory
586 const memoryx::EntityBasePtr poseEntity =
587 ltmSelfLocalisationSegment->getEntityByName(agentName);
588 if (not poseEntity)
589 {
590 ARMARX_FATAL << "Could not retrieve global pose from long-term memory."
591 << "Reason: Pose entity not available.";
592 return std::nullopt;
593 }
594
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");
598
599 if (not poseAttribute)
600 {
601 ARMARX_FATAL << "Could not retrieve global pose from long-term memory."
602 << "Reason: Pose attribute not available.";
603 return std::nullopt;
604 }
605
606 // So this is how you access a typed attribute, fancy
607 const FramedPosePtr framedPose =
608 armarx::VariantPtr::dynamicCast(poseAttribute->getValueAt(0))
609 ->getClass<armarx::FramedPose>();
610
611 if (not framedPose)
612 {
613 ARMARX_FATAL << "Could not retrieve global pose from long-term memory."
614 << "Reason: Casting to framed pose failed.";
615 return std::nullopt;
616 }
617
618 const Eigen::Affine3f pose(framedPose->toGlobalEigen(robot));
619 ARMARX_INFO << "Long-term memory global pose prior: " << pose.matrix();
620
621 return pose;
622 }
623 catch (...)
624 {
625 ARMARX_FATAL << "Could not retrieve global pose from long-term memory."
626 << "Reason: unknown.";
627 }
628
629 return std::nullopt;
630 }
631
632 const std::string&
634 {
635 return agentName;
636 }
637
638 const std::string&
640 {
641 return robotRootFrame;
642 }
643
646 {
647 return robot;
648 }
649
652 {
653 return transformWriterPlugin->get();
654 }
655
658 {
659 return transformReaderPlugin->get();
660 }
661
662} // namespace armarx
static DateTime Now()
Current time on the virtual clock.
Definition Clock.cpp:93
Default component property definition container.
Definition Component.h:70
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition Component.cpp:90
The FramedPose class.
Definition FramedPose.h:281
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.
Definition Logging.cpp:99
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)
const armem::robot_state::client::localization::TransformReaderInterface & getTransformReader() const
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
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
Definition DateTime.cpp:105
std::int64_t toMicroSeconds() const
Returns the amount of microseconds.
Definition Duration.cpp:36
#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.
Definition Logging.h:181
#define ARMARX_FATAL
The logging level for unexpected behaviour, that will lead to a seriously malfunctioning program and ...
Definition Logging.h:199
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
std::string const GlobalFrame
Variable of the global coordinate system.
Definition FramedPose.h:65
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
const VariantTypeId FramedPose
Definition FramedPose.h:36
const PlatformUnitDatafieldCreator platformPose("platformPose")
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::string GetHandledExceptionString()
std::string const OdometryFrame
Definition FramedPose.h:66
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...
Definition algorithm.h:351
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
std::string const MapFrame
Definition FramedPose.h:67
std::string PropertyDefinitionContainer_ice_class_name(std::string const &full_type_name)
IceInternal::Handle< FramedPose > FramedPosePtr
Definition FramedPose.h:272
IceInternal::Handle< SimpleEntity > SimpleEntityPtr
armarx::DateTime timestamp
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Isometry3f pose
#define ARMARX_TRACE
Definition trace.h:77