RobotStateComponent.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package RobotStateComponent::
19  * @author ( at kit dot edu)
20  * @date
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #include "RobotStateComponent.h"
26 
27 #include <Ice/ObjectAdapter.h>
28 
29 #include <VirtualRobot/RobotNodeSet.h>
30 #include <VirtualRobot/math/Helpers.h>
31 #include <VirtualRobot/Nodes/RobotNode.h>
32 #include <VirtualRobot/XML/RobotIO.h>
33 
42 
43 
44 using namespace Eigen;
45 using namespace Ice;
46 using namespace VirtualRobot;
47 
48 
49 namespace armarx
50 {
51  RobotStateComponent::~RobotStateComponent()
52  {
53  try
54  {
55  if (_synchronizedPrx)
56  {
57  _synchronizedPrx->unref();
58  }
59  }
60  catch (...)
61  {}
62  }
63 
64 
65  RobotStatePropertyDefinitions::RobotStatePropertyDefinitions(std::string prefix) :
67  {
68  defineRequiredProperty<std::string>("RobotNodeSetName", "Set of nodes that is controlled by the KinematicUnit");
69  defineRequiredProperty<std::string>("RobotFileName", "Filename of VirtualRobot robot model (e.g. robot_model.xml)");
70  defineRequiredProperty<std::string>("AgentName", "Name of the agent for which the sensor values are provided");
71  defineOptionalProperty<std::string>("RobotStateReportingTopic", "RobotStateUpdates", "Name of the topic on which updates of the robot state are reported.");
72  defineOptionalProperty<int>("HistoryLength", 10000, "Number of entries in the robot state history").setMin(0);
73  defineOptionalProperty<float>("RobotModelScaling", 1.0f, "Scaling of the robot model");
74  defineOptionalProperty<std::string>("TopicPrefix", "", "Prefix for the sensor value topic name.");
75  defineOptionalProperty<std::string>("GlobalRobotPoseLocalizationTopicName", "GlobalRobotPoseLocalization", "Topic where the global robot pose can be reported.");
76  }
77 
78 
80  {
81  return "RobotStateComponent";
82  }
83 
84 
86  {
87  robotStateTopicName = getProperty<std::string>("RobotStateReportingTopic").getValue();
88  offeringTopic(getProperty<std::string>("RobotStateReportingTopic"));
89  const std::size_t historyLength = static_cast<std::size_t>(getProperty<int>("HistoryLength").getValue());
90 
91  jointHistory.clear();
92  jointHistoryLength = historyLength;
93 
94  poseHistory.clear();
95  poseHistoryLength = historyLength;
96 
97  relativeRobotFile = getProperty<std::string>("RobotFileName").getValue();
98 
99  if (!ArmarXDataPath::getAbsolutePath(relativeRobotFile, robotFile))
100  {
101  throw UserException("Could not find robot file " + robotFile);
102  }
103 
104  this->_synchronized = VirtualRobot::RobotIO::loadRobot(robotFile, VirtualRobot::RobotIO::eStructure);
105  _synchronized->setName(getProperty<std::string>("AgentName").getValue());
106 
107  robotModelScaling = getProperty<float>("RobotModelScaling").getValue();
108  ARMARX_INFO << "scale factor: " << robotModelScaling;
109  if (robotModelScaling != 1.0f)
110  {
111  ARMARX_INFO << "Scaling robot model with scale factor " << robotModelScaling;
112  _synchronized = _synchronized->clone(_synchronized->getName(), _synchronized->getCollisionChecker(), robotModelScaling);
113  }
114 
115  if (this->_synchronized)
116  {
117  ARMARX_VERBOSE << "Loaded robot from file " << robotFile << ". Robot name: " << this->_synchronized->getName();
118  this->_synchronized->setPropagatingJointValuesEnabled(false);
119  }
120  else
121  {
122  ARMARX_VERBOSE << "Failed loading robot from file " << robotFile;
123  }
124 
125  robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();
126 
127 
128  if (robotNodeSetName.empty())
129  {
130  throw UserException("RobotNodeSet not defined");
131  }
132 
133  VirtualRobot::RobotNodeSetPtr rns = this->_synchronized->getRobotNodeSet(robotNodeSetName);
134 
135  if (!rns)
136  {
137  throw UserException("RobotNodeSet not defined");
138  }
139 
140  std::vector<RobotNodePtr> nodes = rns->getAllRobotNodes();
141 
142  ARMARX_VERBOSE << "Using RobotNodeSet " << robotNodeSetName << " with " << nodes.size() << " robot nodes.";
143  for (const RobotNodePtr& node : nodes)
144  {
145  ARMARX_VERBOSE << "Node: " << node->getName();
146  }
147  const auto topicPrefix = getProperty<std::string>("TopicPrefix").getValue();
148  usingTopic(topicPrefix + robotNodeSetName + "State");
149 
150  usingTopic(topicPrefix + getProperty<std::string>("GlobalRobotPoseLocalizationTopicName").getValue());
151 
152  try
153  {
154  readRobotInfo(robotFile);
155  }
156  catch (const std::exception& e)
157  {
158  ARMARX_WARNING << "Failed to read robot info from file: " << robotFile << ".\nReason: " << e.what();
159  }
160  catch (...)
161  {
162  ARMARX_WARNING << "Failed to read robot info from file: " << robotFile << " for unknown reason.";
163  }
164  usingTopic("SimulatorResetEvent");
165  }
166 
167  void RobotStateComponent::readRobotInfo(const std::string& robotFile)
168  {
169  RapidXmlReaderPtr reader = RapidXmlReader::FromFile(robotFile);
170  RapidXmlReaderNode robotNode = reader->getRoot("Robot");
171  robotInfo = readRobotInfo(robotNode.first_node("RobotInfo"));
172  }
173 
174  RobotInfoNodePtr RobotStateComponent::readRobotInfo(const RapidXmlReaderNode& infoNode)
175  {
176  std::string name = infoNode.name();
177  std::string profile = infoNode.attribute_value_or_default("profile", "");
178  std::string value = infoNode.attribute_value_or_default("value", "");
179  //ARMARX_IMPORTANT << "name: " << name << "; profile: " << profile << "; value: " << value;
180  std::vector<RobotInfoNodePtr> children;
181  for (const RapidXmlReaderNode& childNode : infoNode.nodes())
182  {
183  children.push_back(readRobotInfo(childNode));
184  }
185  return new RobotInfoNode(name, profile, value, children);
186  }
187 
188 
190  {
191  robotStateListenerPrx = getTopic<RobotStateListenerInterfacePrx>(getProperty<std::string>("RobotStateReportingTopic"));
192  _sharedRobotServant = new SharedRobotServant(this->_synchronized, RobotStateComponentInterfacePrx::uncheckedCast(getProxy()), robotStateListenerPrx);
193  _sharedRobotServant->ref();
194 
195  _sharedRobotServant->setRobotStateComponent(RobotStateComponentInterfacePrx::uncheckedCast(getProxy()));
196  this->_synchronizedPrx = SharedRobotInterfacePrx::uncheckedCast(getObjectAdapter()->addWithUUID(_sharedRobotServant));
197  ARMARX_INFO << "Started RobotStateComponent" << flush;
198  if (robotStateObs)
199  {
200  robotStateObs->setRobot(_synchronized);
201  }
202  }
203 
205  {
206  }
207 
208 
210  {
211  if (!this->_synchronizedPrx)
212  {
213  throw NotInitializedException("Shared Robot is NULL", "getSynchronizedRobot");
214  }
215  return this->_synchronizedPrx;
216  }
217 
218 
219  SharedRobotInterfacePrx RobotStateComponent::getRobotSnapshot(const std::string& deprecated, const Current&)
220  {
221  (void) deprecated;
222 
223  if (!_synchronized)
224  {
225  throw NotInitializedException("Shared Robot is NULL", "getRobotSnapshot");
226  }
227 
228  auto clone = this->_synchronized->clone(_synchronized->getName());
229 
230  SharedRobotServantPtr p = new SharedRobotServant(clone, RobotStateComponentInterfacePrx::uncheckedCast(getProxy()), nullptr);
231  p->setTimestamp(IceUtil::Time::microSecondsDouble(_sharedRobotServant->getTimestamp()->timestamp));
232  auto result = getObjectAdapter()->addWithUUID(p);
233  // virtal robot clone is buggy -> set global pose here
234  p->setGlobalPose(new Pose(_synchronized->getGlobalPose()));
235  return SharedRobotInterfacePrx::uncheckedCast(result);
236  }
237 
239  {
240  const IceUtil::Time time = IceUtil::Time::microSecondsDouble(_time);
241 
242  if (!_synchronized)
243  {
244  throw NotInitializedException("Shared Robot is NULL", "getRobotSnapshot");
245  }
246 
247  VirtualRobot::RobotPtr clone = this->_synchronized->clone(_synchronized->getName());
248  auto config = interpolate(time);
249  if (!config)
250  {
251  ARMARX_WARNING << "Could not find or interpolate a robot state for time " << time.toDateTime();
252  return nullptr;
253  }
254 
255  clone->setJointValues(config->jointMap);
256  SharedRobotServantPtr p = new SharedRobotServant(clone, RobotStateComponentInterfacePrx::uncheckedCast(getProxy()), nullptr);
257  p->setTimestamp(time);
258  auto result = getObjectAdapter()->addWithUUID(p);
259  // Virtal robot clone is buggy -> set global pose here.
260  p->setGlobalPose(config->globalPose);
261 
262  return SharedRobotInterfacePrx::uncheckedCast(result);
263  }
264 
265 
266  NameValueMap RobotStateComponent::getJointConfigAtTimestamp(double timestamp, const Current&) const
267  {
268  auto jointAngles = interpolateJoints(IceUtil::Time::microSecondsDouble(timestamp));
269  return jointAngles ? jointAngles->value : NameValueMap();
270  }
271 
272 
273  RobotStateConfig RobotStateComponent::getRobotStateAtTimestamp(double timestamp, const Current&) const
274  {
275  auto config = interpolate(IceUtil::Time::microSecondsDouble(timestamp));
276  return config ? *config : RobotStateConfig();
277  }
278 
279 
280  std::string RobotStateComponent::getRobotFilename(const Ice::Current&) const
281  {
282  return relativeRobotFile;
283  }
284 
285  float RobotStateComponent::getScaling(const Ice::Current&) const
286  {
287  return robotModelScaling;
288  }
289 
290  RobotInfoNodePtr RobotStateComponent::getRobotInfo(const Ice::Current&) const
291  {
292  return robotInfo;
293  }
294 
295 
297  const NameValueMap& jointAngles, Ice::Long timestamp, bool aValueChanged, const Current&)
298  {
299  if (timestamp <= 0)
300  {
301  timestamp = armarx::rtNow().toMicroSeconds();
302  }
303 
304  IceUtil::Time time = mapRtTimestampToNonRtTimestamp(IceUtil::Time::microSeconds(timestamp));
305 
306  ARMARX_DEBUG << deactivateSpam(1) << "Got new jointangles: " << jointAngles
307  << " from timestamp " << time.toDateTime()
308  << " a value changed: " << aValueChanged;
309 
310  if (aValueChanged)
311  {
312  {
313  WriteLockPtr lock = _synchronized->getWriteLock();
314 
315  _synchronized->setJointValues(jointAngles);
316  }
317 
318  if (robotStateObs)
319  {
320  robotStateObs->updatePoses();
321  }
322  }
323  if (_sharedRobotServant)
324  {
325  _sharedRobotServant->setTimestamp(time);
326  }
327 
328  {
329  std::unique_lock lock(jointHistoryMutex);
330  jointHistory.emplace_hint(jointHistory.end(), time, jointAngles);
331 
332  if (jointHistory.size() > jointHistoryLength)
333  {
334  jointHistory.erase(jointHistory.begin());
335  }
336  }
337 
338  robotStateListenerPrx->reportJointValues(jointAngles, timestamp, aValueChanged);
339  }
340 
341 
342  void
344  const TransformStamped& globalRobotPose,
345  const Ice::Current&)
346  {
347  if (_synchronized)
348  {
349  std::string localRobotName = _synchronized->getName();
350  ARMARX_DEBUG << "Comparing " << localRobotName << " and " << globalRobotPose.header.agent << ".";
351  if (localRobotName == globalRobotPose.header.agent)
352  {
353  const IceUtil::Time time = IceUtil::Time::microSeconds(globalRobotPose.header.timestampInMicroSeconds);
354 
355  insertPose(time, globalRobotPose.transform);
356  _synchronized->setGlobalPose(globalRobotPose.transform);
357 
358  if (_sharedRobotServant)
359  {
360  _sharedRobotServant->setGlobalPose(new Pose(globalRobotPose.transform));
361  _sharedRobotServant->setTimestamp(time);
362  }
363  }
364  }
365  else
366  {
367  throw NotInitializedException("Robot Ptr is NULL", "reportGlobalRobotPose");
368  }
369  }
370 
371 
372  std::vector<std::string> RobotStateComponent::getArmarXPackages(const Current&) const
373  {
374  std::vector<std::string> result;
376  packages.push_back(Application::GetProjectName());
377 
378  for (const std::string& projectName : packages)
379  {
380  if (projectName.empty())
381  {
382  continue;
383  }
384 
385  result.push_back(projectName);
386  }
387 
388  return result;
389  }
390 
391  void RobotStateComponent::reportControlModeChanged(const NameControlModeMap& jointModes, Ice::Long timestamp, bool aValueChanged, const Current&)
392  {
393  // Unused.
394  (void) jointModes, (void) timestamp, (void) aValueChanged;
395  }
396  void RobotStateComponent::reportJointVelocities(const NameValueMap& jointVelocities, Ice::Long timestamp, bool aValueChanged, const Current&)
397  {
398  // Unused.
399  (void) aValueChanged;
400  if (robotStateObs)
401  {
402  robotStateObs->updateNodeVelocities(jointVelocities, timestamp);
403  }
404  }
405  void RobotStateComponent::reportJointTorques(const NameValueMap& jointTorques, Ice::Long timestamp, bool aValueChanged, const Current&)
406  {
407  // Unused.
408  (void) jointTorques, (void) timestamp, (void) aValueChanged;
409  }
410 
411  void RobotStateComponent::reportJointAccelerations(const NameValueMap& jointAccelerations, Ice::Long timestamp, bool aValueChanged, const Current&)
412  {
413  // Unused.
414  (void) jointAccelerations, (void) timestamp, (void) aValueChanged;
415  }
416  void RobotStateComponent::reportJointCurrents(const NameValueMap& jointCurrents, Ice::Long timestamp, bool aValueChanged, const Current&)
417  {
418  // Unused.
419  (void) jointCurrents, (void) timestamp, (void) aValueChanged;
420  }
421  void RobotStateComponent::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, Ice::Long timestamp, bool aValueChanged, const Current&)
422  {
423  // Unused.
424  (void) jointMotorTemperatures, (void) timestamp, (void) aValueChanged;
425  }
426  void RobotStateComponent::reportJointStatuses(const NameStatusMap& jointStatuses, Ice::Long timestamp, bool aValueChanged, const Current&)
427  {
428  // Unused.
429  (void) jointStatuses, (void) timestamp, (void) aValueChanged;
430  }
431 
433  {
434  {
435  std::lock_guard lock(poseHistoryMutex);
436  poseHistory.clear();
437  }
438  {
439  std::lock_guard lock(jointHistoryMutex);
440  jointHistory.clear();
441  }
442  }
443 
445  {
448  }
449 
451  {
452  robotStateObs = observer;
453  }
454 
455  std::string RobotStateComponent::getRobotName(const Current&) const
456  {
457  if (_synchronized)
458  {
459  return _synchronized->getName(); // _synchronizedPrx->getName();
460  }
461  else
462  {
463  throw NotInitializedException("Robot Ptr is NULL", "getName");
464  }
465 
466  }
467 
468  std::string RobotStateComponent::getRobotNodeSetName(const Current&) const
469  {
470  if (robotNodeSetName.empty())
471  {
472  throw NotInitializedException("RobotNodeSetName is empty", "getRobotNodeSetName");
473  }
474  return robotNodeSetName;
475  }
476 
477  std::string RobotStateComponent::getRobotStateTopicName(const Current&) const
478  {
479  return robotStateTopicName;
480  }
481 
482 
483  void RobotStateComponent::insertPose(IceUtil::Time timestamp, const Matrix4f& globalPose)
484  {
485  IceUtil::Time duration;
486  {
487  IceUtil::Time start = IceUtil::Time::now();
488  std::unique_lock lock(poseHistoryMutex);
489  duration = IceUtil::Time::now() - start;
490 
491  poseHistory.emplace_hint(poseHistory.end(),
492  timestamp, new FramedPose(globalPose, GlobalFrame, ""));
493 
494  if (poseHistory.size() > poseHistoryLength)
495  {
496  poseHistory.erase(poseHistory.begin());
497  }
498  }
499 
500  if (robotStateObs)
501  {
502  robotStateObs->updatePoses();
503  }
504  }
505 
506  std::optional<RobotStateConfig> RobotStateComponent::interpolate(IceUtil::Time time) const
507  {
508  auto joints = interpolateJoints(time);
509  auto globalPose = interpolatePose(time);
510 
511  if (joints && globalPose)
512  {
513  RobotStateConfig config;
514  // Use time stamp from interpolation.
515  // config.timestamp = time.toMicroSeconds();
516  config.timestamp = std::min(joints->timestamp, globalPose->timestamp).toMicroSeconds();
517  config.jointMap = joints->value;
518  config.globalPose = globalPose->value;
519  return config;
520  }
521  else
522  {
523  return std::nullopt;
524  }
525  }
526 
527  auto RobotStateComponent::interpolateJoints(IceUtil::Time time) const -> std::optional<Timestamped<NameValueMap>>
528  {
529  std::shared_lock lock(jointHistoryMutex);
530  if (jointHistory.empty())
531  {
532  ARMARX_WARNING << deactivateSpam(1) << "Joint history of robot state component is empty!";
533  return std::nullopt;
534  }
535 
536  const IceUtil::Time newestTimeInHistory = jointHistory.rbegin()->first;
537  if (time > newestTimeInHistory)
538  {
539  const IceUtil::Time minOffset = IceUtil::Time::milliSeconds(25);
540  const IceUtil::Time maxOffset = IceUtil::Time::seconds(2);
541  if (time > newestTimeInHistory + maxOffset)
542  {
543  ARMARX_WARNING << deactivateSpam(5) << "Requested joint timestamp is substantially newer (>"
544  << maxOffset.toSecondsDouble() << " sec) than newest available timestamp!"
545  << "\n- requested timestamp: \t" << time.toDateTime()
546  << "\n- newest timestamp: \t" << newestTimeInHistory.toDateTime();
547  return std::nullopt;
548  }
549  else if (time > newestTimeInHistory + minOffset)
550  {
552  << "Requested joint timestamp is newer than newest available timestamp!"
553  << "\n- requested timestamp: \t" << time.toDateTime()
554  << "\n- newest timestamp: \t" << newestTimeInHistory.toDateTime()
555  << "\n- difference: \t" << (time - newestTimeInHistory).toMicroSeconds() << " us";
556  }
557 
558  return Timestamped<NameValueMap> {jointHistory.rbegin()->first, jointHistory.rbegin()->second};
559  }
560 
561  // Get the oldest entry whose time >= time.
562  auto nextIt = jointHistory.lower_bound(time);
563  if (nextIt == jointHistory.end())
564  {
566  << "Could not find or interpolate a robot joint angles for time " << time.toDateTime()
567  << "\n- oldest available value: " << jointHistory.begin()->first.toDateTime()
568  << "\n- newest available value: " << newestTimeInHistory.toDateTime();
569  return std::nullopt;
570  }
571 
572  if (nextIt == jointHistory.begin())
573  {
574  // Next was oldest entry.
575  return Timestamped<NameValueMap> {nextIt->first, nextIt->second};
576  }
577 
578  const NameValueMap& next = nextIt->second;
579  auto prevIt = std::prev(nextIt);
580 
581 
582  // Interpolate.
583 
584  IceUtil::Time prevTime = prevIt->first;
585  IceUtil::Time nextTime = nextIt->first;
586 
587  float t = static_cast<float>((time - prevTime).toSecondsDouble()
588  / (nextTime - prevTime).toSecondsDouble());
589 
591  auto prevJointIt = prevIt->second.begin();
592  for (const auto& [name, nextAngle] : next)
593  {
594  float value = (1 - t) * prevJointIt->second + t * nextAngle;
595  prevJointIt++;
596 
597  jointAngles.emplace(name, value);
598  }
599 
600  return Timestamped<NameValueMap> {time, std::move(jointAngles)};
601  }
602 
603  auto RobotStateComponent::interpolatePose(IceUtil::Time time) const -> std::optional<Timestamped<FramedPosePtr>>
604  {
605  std::shared_lock lock(poseHistoryMutex);
606 
607  if (poseHistory.empty())
608  {
610  << "Pose history is empty. This can happen if there is no platform unit.";
611 
612  ReadLockPtr readLock = _synchronized->getReadLock();
613 
614  FramedPosePtr pose = new FramedPose(_synchronized->getGlobalPose(), armarx::GlobalFrame, "");
615  return Timestamped<FramedPosePtr> {IceUtil::Time::seconds(0), pose};
616  }
617 
618 
619  const IceUtil::Time newestTimeInHistory = poseHistory.rbegin()->first;
620  if (time > newestTimeInHistory)
621  {
622  IceUtil::Time maxOffset = IceUtil::Time::seconds(2);
623  if (time <= newestTimeInHistory + maxOffset)
624  {
626  << "Requested pose timestamp is newer than newest available timestamp!"
627  << "\n- requested timestamp: \t" << time.toDateTime()
628  << "\n- newest timestamp: \t" << newestTimeInHistory.toDateTime()
629  << "\n- difference: \t" << (time - newestTimeInHistory).toMicroSeconds() << " us";
630  }
631  else
632  {
633  ARMARX_WARNING << deactivateSpam(1) << "Requested pose timestamp is substantially newer (>"
634  << maxOffset.toSecondsDouble() << " sec) than newest available timestamp!"
635  << "\n- requested timestamp: \t" << time.toDateTime()
636  << "\n- newest timestamp: \t" << newestTimeInHistory.toDateTime();
637  return std::nullopt;
638  }
639  return Timestamped<FramedPosePtr> {poseHistory.rbegin()->first, poseHistory.rbegin()->second};
640  }
641 
642 
643  auto nextIt = poseHistory.lower_bound(time);
644  if (nextIt == poseHistory.end())
645  {
647  << "Could not find or interpolate platform pose for time " << time.toDateTime()
648  << "\n- oldest available value: " << jointHistory.begin()->first.toDateTime()
649  << "\n- newest available value: " << newestTimeInHistory.toDateTime();
650  return std::nullopt;
651  }
652 
653 
654  if (nextIt == poseHistory.begin())
655  {
656  // Next was oldest entry.
657  return Timestamped<FramedPosePtr> {nextIt->first, nextIt->second};
658  }
659 
660  auto prevIt = std::prev(nextIt);
661  ARMARX_CHECK_EXPRESSION(prevIt->second);
662 
663  const FramedPosePtr& next = nextIt->second;
664  const FramedPosePtr& prev = prevIt->second;
665 
666 
667  // Interpolate.
668 
669  IceUtil::Time prevTime = prevIt->first;
670  IceUtil::Time nextTime = nextIt->first;
671 
672  float t = static_cast<float>((time - prevTime).toSecondsDouble()
673  / (nextTime - prevTime).toSecondsDouble());
674 
675  Eigen::Matrix4f globalPoseNext = next->toEigen();
676  Eigen::Matrix4f globalPosePrev = prev->toEigen();
677 
678 
679  Eigen::Matrix4f globalPose;
680 
681  math::Helpers::Position(globalPose) =
682  (1 - t) * math::Helpers::Position(globalPosePrev) + t * math::Helpers::Position(globalPoseNext);
683 
684  Eigen::Quaternionf rotNext(math::Helpers::Orientation(globalPoseNext));
685  Eigen::Quaternionf rotPrev(math::Helpers::Orientation(globalPosePrev));
686  Eigen::Quaternionf rotNew = rotPrev.slerp(t, rotNext);
687 
688  math::Helpers::Orientation(globalPose) = rotNew.toRotationMatrix();
689 
690  return Timestamped<FramedPosePtr> {time, new FramedPose(globalPose, armarx::GlobalFrame, "")};
691  }
692 
693 }
armarx::RapidXmlReaderPtr
std::shared_ptr< RapidXmlReader > RapidXmlReaderPtr
Definition: RapidXmlReader.h:66
armarx::RapidXmlReader::FromFile
static RapidXmlReaderPtr FromFile(const std::string &path)
Definition: RapidXmlReader.h:497
armarx::RobotStateComponent::reportJointAccelerations
void reportJointAccelerations(const NameValueMap &jointAccelerations, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c) override
Does nothing.
Definition: RobotStateComponent.cpp:411
armarx::RobotStateComponent::onInitComponent
void onInitComponent() override
Load and create a VirtualRobot::Robot instance from the RobotFileName property.
Definition: RobotStateComponent.cpp:85
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
Eigen
Definition: Elements.h:36
armarx::Application::GetProjectName
static const std::string & GetProjectName()
Definition: Application.cpp:861
armarx::RobotStateComponent::getSynchronizedRobot
SharedRobotInterfacePrx getSynchronizedRobot(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:209
armarx::RobotStateComponent::getRobotSnapshotAtTimestamp
SharedRobotInterfacePrx getRobotSnapshotAtTimestamp(double time, const Ice::Current &current) override
Definition: RobotStateComponent.cpp:238
GfxTL::Orientation
ScalarT Orientation(const VectorXD< 2, ScalarT > &p1, const VectorXD< 2, ScalarT > &p2, const VectorXD< 2, ScalarT > &c)
Definition: Orientation.h:9
armarx::navigation::core::Pose
Eigen::Isometry3f Pose
Definition: basic_types.h:31
armarx::ManagedIceObject::getObjectAdapter
Ice::ObjectAdapterPtr getObjectAdapter() const
Returns object's Ice adapter.
Definition: ManagedIceObject.cpp:140
armarx::RobotStateComponent::reportJointStatuses
void reportJointStatuses(const NameStatusMap &jointStatuses, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Does nothing.
Definition: RobotStateComponent.cpp:426
RtTiming.h
armarx::FramedPose
The FramedPose class.
Definition: FramedPose.h:258
armarx::VariantType::FramedPose
const VariantTypeId FramedPose
Definition: FramedPose.h:37
ArmarXManager.h
VirtualRobot
Definition: FramedPose.h:43
armarx::RobotStateComponent::getJointConfigAtTimestamp
NameValueMap getJointConfigAtTimestamp(double timestamp, const Ice::Current &) const override
Definition: RobotStateComponent.cpp:266
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:62
armarx::FramedPosePtr
IceInternal::Handle< FramedPose > FramedPosePtr
Definition: FramedPose.h:250
armarx::SharedRobotServant
The SharedRobotNodeServant class is a remote represenation of a Simox VirtualRobot::Robot.
Definition: SharedRobotServants.h:110
armarx::navigation::platform_controller::platform_global_trajectory::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformGlobalTrajectoryController.h:93
armarx::RobotStatePropertyDefinitions
Definition: RobotStateComponent.h:51
armarx::RobotStateComponent::reportGlobalRobotPose
void reportGlobalRobotPose(const TransformStamped &globalRobotPose, const Ice::Current &=Ice::Current()) override
Definition: RobotStateComponent.cpp:343
armarx::RobotStateComponent::setRobotStateObserver
void setRobotStateObserver(RobotStateObserverPtr observer)
Definition: RobotStateComponent.cpp:450
IceInternal::Handle< SharedRobotServant >
armarx::RobotStateComponent::getRobotInfo
RobotInfoNodePtr getRobotInfo(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:290
armarx::Quaternion::slerp
Eigen::Matrix3f slerp(float, const Eigen::Matrix3f &)
Definition: Pose.cpp:233
armarx::RobotStateComponent::simulatorWasReset
void simulatorWasReset(const Ice::Current &=Ice::emptyCurrent) override
Definition: RobotStateComponent.cpp:432
deactivateSpam
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition: Logging.cpp:72
NonRtTiming.h
armarx::RobotStateComponent::getDefaultName
std::string getDefaultName() const override
Retrieve default name of component.
Definition: RobotStateComponent.cpp:79
armarx::RobotStateComponent::reportJointAngles
void reportJointAngles(const NameValueMap &jointAngles, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Stores the reported joint angles in the joint history and publishes the new joint angles.
Definition: RobotStateComponent.cpp:296
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
armarx::flush
const LogSender::manipulator flush
Definition: LogSender.h:251
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::RobotStateComponent::getRobotName
std::string getRobotName(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:455
armarx::VariantType::Long
const VariantTypeId Long
Definition: Variant.h:917
armarx::RobotStateComponent::getRobotStateAtTimestamp
RobotStateConfig getRobotStateAtTimestamp(double timestamp, const Ice::Current &) const override
Definition: RobotStateComponent.cpp:273
armarx::RapidXmlReaderNode
Definition: RapidXmlReader.h:68
ArmarXObjectScheduler.h
armarx::channels::KinematicUnitObserver::jointVelocities
const KinematicUnitDatafieldCreator jointVelocities("jointVelocities")
armarx::RobotStateComponent::reportJointMotorTemperatures
void reportJointMotorTemperatures(const NameValueMap &jointMotorTemperatures, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Does nothing.
Definition: RobotStateComponent.cpp:421
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::RobotStateComponent::getRobotFilename
std::string getRobotFilename(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:280
armarx::RobotStateComponent::getArmarXPackages
std::vector< std::string > getArmarXPackages(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:372
armarx::RobotStateComponent::reportJointCurrents
void reportJointCurrents(const NameValueMap &jointCurrents, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Does nothing.
Definition: RobotStateComponent.cpp:416
armarx::RobotStateComponent::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: RobotStateComponent.cpp:204
armarx::RobotStateComponent::onConnectComponent
void onConnectComponent() override
Setup RobotStateObjectFactories needed for creating RemoteRobot instances.
Definition: RobotStateComponent.cpp:189
armarx::channels::KinematicUnitObserver::jointAngles
const KinematicUnitDatafieldCreator jointAngles("jointAngles")
armarx::ManagedIceObject::usingTopic
void usingTopic(const std::string &name, bool orderedPublishing=false)
Registers a proxy for subscription after initialization.
Definition: ManagedIceObject.cpp:248
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:74
armarx::channels::KinematicUnitObserver::jointCurrents
const KinematicUnitDatafieldCreator jointCurrents("jointCurrents")
Ice
Definition: DBTypes.cpp:64
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
ARMARX_CHECK_EXPRESSION
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
Definition: ExpressionException.h:73
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:70
TimeUtil.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::RobotStateComponent::reportJointVelocities
void reportJointVelocities(const NameValueMap &jointVelocities, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Sends the joint velocities to the robot state observer.
Definition: RobotStateComponent.cpp:396
armarx::Quaternion< float, 0 >
armarx::ManagedIceObject::offeringTopic
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
Definition: ManagedIceObject.cpp:290
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::RobotStateComponent::reportJointTorques
void reportJointTorques(const NameValueMap &jointTorques, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Does nothing.
Definition: RobotStateComponent.cpp:405
IceInternal::ProxyHandle< ::IceProxy::armarx::SharedRobotInterface >
RapidXmlReader.h
armarx::RobotStateComponent::getRobotSnapshot
SharedRobotInterfacePrx getRobotSnapshot(const std::string &deprecated, const Ice::Current &) override
Creates a snapshot of the robot state at this moment in time.
Definition: RobotStateComponent.cpp:219
armarx::RobotStateComponent::getRobotNodeSetName
std::string getRobotNodeSetName(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:468
armarx::RobotStateComponent::createPropertyDefinitions
PropertyDefinitionsPtr createPropertyDefinitions() override
Create an instance of RobotStatePropertyDefinitions.
Definition: RobotStateComponent.cpp:444
armarx::Logging::deactivateSpam
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:92
armarx::RobotStateComponent::getRobotStateTopicName
std::string getRobotStateTopicName(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:477
armarx::ArmarXDataPath::getAbsolutePath
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
Definition: ArmarXDataPath.cpp:111
armarx::mapRtTimestampToNonRtTimestamp
IceUtil::Time mapRtTimestampToNonRtTimestamp(const IceUtil::Time &time_monotic_raw)
Definition: NonRtTiming.h:46
armarx::navigation::core::Position
Eigen::Vector3f Position
Definition: basic_types.h:36
min
T min(T t1, T t2)
Definition: gdiam.h:42
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::channels::KinematicUnitObserver::jointTorques
const KinematicUnitDatafieldCreator jointTorques("jointTorques")
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:34
armarx::ManagedIceObject::getProxy
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
Definition: ManagedIceObject.cpp:393
ArmarXDataPath.h
armarx::RapidXmlReaderNode::first_node
RapidXmlReaderNode first_node(const char *name=nullptr) const
Definition: RapidXmlReader.h:140
armarx::RobotStateComponent::reportControlModeChanged
void reportControlModeChanged(const NameControlModeMap &jointModes, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c=Ice::emptyCurrent) override
Does nothing.
Definition: RobotStateComponent.cpp:391
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::Application::GetProjectDependencies
static const Ice::StringSeq & GetProjectDependencies()
Definition: Application.cpp:868
armarx::RobotStateComponent::getScaling
float getScaling(const Ice::Current &) const override
Definition: RobotStateComponent.cpp:285
Application.h
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
RobotStateComponent.h
armarx::rtNow
IceUtil::Time rtNow()
Definition: RtTiming.h:40