RobotUnitSimulation.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package ArmarXSimulation::ArmarXObjects::RobotUnitSimulation
17  * @author Raphael Grimm ( raphael dot grimm at kit dot edu )
18  * @date 2017
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #include "RobotUnitSimulation.h"
24 
27 
28 #include <VirtualRobot/MathTools.h>
29 #include <VirtualRobot/RobotNodeSet.h>
30 #include <VirtualRobot/Nodes/ForceTorqueSensor.h>
31 
32 #include <set>
33 #include <chrono>
34 
35 
36 using namespace armarx;
37 
39 {
40  robot = cloneRobot();
41  simulatorPrxName = getProperty<std::string>("SimulatorName").getValue();
43 
44  synchronizedSimulation = getProperty<bool>("SynchronizedSimulation").getValue();
45  simulatorRobotListenerInterfaceTopic = getProperty<std::string>("SimulatorRobotListenerInterfaceTopic").getValue();
46  if (simulatorRobotListenerInterfaceTopic.empty())
47  {
48  simulatorRobotListenerInterfaceTopic = "Simulator_Robot_" + getRobotName();
49  }
50  simulatorForceTorqueListenerInterfaceTopic = getProperty<std::string>("SimulatorForceTorqueListenerInterfaceTopic").getValue();
51  std::size_t controlIterationMsProp = getProperty<std::size_t>("ControlIterationMs").getValue();
52  if (!controlIterationMsProp)
53  {
54  ARMARX_WARNING << "the controll iteration was set to 0ms. detting it to 1ms";
55  controlIterationMsProp = 1;
56  }
57  controlIterationMs = IceUtil::Time::milliSeconds(controlIterationMsProp);
58  usingTopic(simulatorRobotListenerInterfaceTopic);
59  usingTopic(simulatorForceTorqueListenerInterfaceTopic);
60 
61  //ft mapping
62  {
63  const std::string mappingStr = getProperty<std::string>("ForceTorqueSensorMapping");
64  std::vector<std::string> entries;
65  if (mappingStr != "")
66  {
67  bool trimEntries = true;
68  entries = Split(mappingStr, ",", trimEntries);
69  }
70  for (std::string entry : entries)
71  {
72  ARMARX_CHECK_EXPRESSION(!entry.empty()) << "empty entry in ForceTorqueSensorMapping! entries:\n" << entries;
73  bool trimFields = true;
74  std::vector<std::string> fields = Split(entry, ":", trimFields);
76  fields.size() == 2 || fields.size() == 3) <<
77  "invalid entry in ForceTorqueSensorMapping! invalid entry:\n" << fields << "\nall entries:\n" << entries;
78  for (auto& field : fields)
79  {
81  !field.empty()) <<
82  "empty field in ForceTorqueSensorMapping entry! invalid entry:\n" << fields << "\nall entries:\n" << entries;
83  }
84  const VirtualRobot::ForceTorqueSensorPtr ftsensor = robot->getSensor<typename VirtualRobot::ForceTorqueSensor>(fields.at(0));
85  if (!ftsensor)
86  {
87  ARMARX_WARNING << "the robot has not ft sensor of name '" << fields.at(0)
88  << "' this ForceTorqueSensorMapping entry has no effect: " << entry;
89  continue;
90  }
92  fields.size() == 2 || robot->hasRobotNode(fields.at(2))) <<
93  VAROUT(fields.size()) << " " << (fields.size() != 2 ? VAROUT(fields.at(2)) : std::string {});
94  ARMARX_CHECK_EXPRESSION(!ftMappings.count(fields.at(0)));
95  FTMappingData& mapping = ftMappings[fields.at(0)];
96  mapping.originalReportFrame = ftsensor->getRobotNode()->getName();
97  mapping.reportFrame = mapping.originalReportFrame;
98  mapping.reportTransformation = Eigen::Matrix3f::Identity();
99  mapping.sensorName = fields.at(1);
100  if (fields.size() == 3)
101  {
102  mapping.reportFrame = fields.at(2);
103  //get rotation from original to target
104  const auto orig = robot->getRobotNode(mapping.originalReportFrame)->getGlobalPose();
105  const auto targ = robot->getRobotNode(mapping.reportFrame)->getGlobalPose();
106  mapping.reportTransformation = (targ.block<3, 3>(0, 0).inverse() * orig.block<3, 3>(0, 0));
107  }
108  }
109  }
110 
111  maxLinearPlatformVelocity = getProperty<float>("maxLinearPlatformVelocity").getValue();
113 
114  maxAngularPlatformVelocity = getProperty<float>("maxAngularPlatformVelocity").getValue();
116 
117  ARMARX_INFO << "using " << VAROUT(simulatorRobotListenerInterfaceTopic);
118  ARMARX_INFO << "using " << VAROUT(simulatorForceTorqueListenerInterfaceTopic);
119  ARMARX_INFO << "using " << VAROUT(controlIterationMs);
120 }
121 
123 {
124  simulatorPrx = getProxy<SimulatorInterfacePrx>(simulatorPrxName);
125  if (!rtThread.joinable())
126  {
127  rtThread = std::thread {[&]{rtTask();}};
128  }
129 }
130 
132 {
133  shutdownRtThread = true;
134  rtThread.join();
135 }
136 
138 {
139  ARMARX_ON_SCOPE_EXIT { ARMARX_IMPORTANT << "exiting rt thread";};
140  try
141  {
142  {
143  const auto timing = -TimeUtil::GetTime(true);
145  //device init
146  {
147  const auto timing = -TimeUtil::GetTime(true);
148  //joints
149  {
150  const auto timing = -TimeUtil::GetTime(true);
151  ARMARX_INFO << "adding devices for joints:";
152  for (const VirtualRobot::RobotNodePtr& node : * (robot->getRobotNodeSet(getProperty<std::string>("RobotNodeSetName").getValue())))
153  {
154  if (node->isJoint())
155  {
156  JointSimulationDevicePtr jdev = std::make_shared<JointSimulationDevice>(node->getName(), anglesCtrl, velocitiesCtrl, torquesCtrl);
157  jointDevs.add(jdev->getDeviceName(), jdev);
158  addSensorDevice(jdev);
159  addControlDevice(jdev);
160  }
161  }
162  ARMARX_INFO << "adding devices for joints done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
163  }
164  //platform
165  {
166  const auto timing = -TimeUtil::GetTime(true);
167  ARMARX_INFO << "adding devices for the platform:";
168 
169  if (getRobotPlatformName().empty())
170  {
171  ARMARX_INFO << "No platform device will be created since platform name was given";
172  }
173  else
174  {
175  if (robot->hasRobotNode(getRobotPlatformName()))
176  {
177  platformDev = std::make_shared<PlatformSimulationDevice>(getRobotPlatformName());
178  addSensorDevice(platformDev);
179  addControlDevice(platformDev);
180  }
181  else
182  {
183  ARMARX_WARNING << "No robot node with the name '" + getRobotPlatformName() + "' so no platform device will be created";
184  }
185  }
186  ARMARX_INFO << "adding devices for the platform done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
187  }
188  //force torque
189  {
190  const auto timing = -TimeUtil::GetTime(true);
191  ARMARX_INFO << "adding devices for force torque sensors:";
192  for (const auto& ft : robot->getSensors<VirtualRobot::ForceTorqueSensor>())
193  {
194  ForceTorqueSimulationSensorDevicePtr ftdev = std::make_shared<ForceTorqueSimulationSensorDevice>(
195  getMappedFTName(ft->getName()),
196  getMappedFTReportingFrame(ft->getName(), ft->getRobotNode()->getName()),
197  getMappedFTReportingTransformation(ft->getName())
198  );
199  addSensorDevice(ftdev);
200  forceTorqueDevs.add(ftdev->getDeviceName(), ftdev);
201  }
202  ARMARX_INFO << "adding devices for force torque done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
203  }
204  //global pose device
205  {
206  // globalPoseDevice = std::make_shared<GlobalRobotPoseSimulationSensorDevice>();
207  // addSensorDevice(globalPoseDevice);
208 
209  }
210  ARMARX_INFO << "transitioning to " << RobotUnitState::InitializingUnits << std::flush;
212  ARMARX_INFO << "device init done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
213  ARMARX_INFO << "transitioned to " << getRobotUnitState() << std::flush;
214  }
215  //unit init
216  {
217  const auto timing = -TimeUtil::GetTime(true);
218  //resize my tripple buffers
219  {
220  const auto timing = -TimeUtil::GetTime(true);
221  torquesTB.reinit(std::vector<float>(jointDevs.size(), 0));
222  anglesTB.reinit(std::vector<float>(jointDevs.size(), 0));
223  velocitiesTB.reinit(std::vector<float>(jointDevs.size(), 0));
224  forceTorqueTB.reinit(std::vector<FT>(forceTorqueDevs.size(), FT {}));
225  forceTorqueTimes.clear();
226  forceTorqueTimes.resize(forceTorqueDevs.size(), 0);
228  ARMARX_INFO << "resize buffers done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
229  }
232  ARMARX_INFO << "transitioned to " << getRobotUnitState() << std::flush;
233  ARMARX_INFO << "unit init done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
234  }
235  //get initial sensor values
236  {
237  const auto timing = -TimeUtil::GetTime(true);
238  gotSensorData = false;
239  ARMARX_INFO << "fetching initial robot state" << std::flush;
240  rtUpdateSensors(true);
241  ARMARX_INFO << "fetching initial robot done" << std::flush;
242  if (platformDev)
243  {
244  const float absolutePositionX = robPoseTB.getReadBuffer()(0, 3);
245  const float absolutePositionY = robPoseTB.getReadBuffer()(1, 3);
246  const float absolutePositionRotation = VirtualRobot::MathTools::eigen4f2rpy(robPoseTB.getReadBuffer())(2);
247 
248  platformDev->initAbsolutePositionX = absolutePositionX;
249  platformDev->initAbsolutePositionY = absolutePositionY;
250  platformDev->initAbsolutePositionRotation = absolutePositionRotation;
251  }
252  ARMARX_INFO << "get init sensor values done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
253  }
254  //enter RT
255  {
256  if (synchronizedSimulation)
257  {
258  simulatorPrx->stop();
259  ARMARX_IMPORTANT << "using synchronized simulator execution" << std::flush;
260  }
261  ARMARX_INFO << "now transitioning to rt" << std::flush;
262  {
263  const auto timing = -TimeUtil::GetTime(true);
265  ARMARX_INFO << "init rt thread done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
266  }
267  ARMARX_INFO << "transitioned to " << getRobotUnitState() << std::flush;
268  }
269  ARMARX_INFO << "pre loop done (" << (timing + TimeUtil::GetTime(true)).toMicroSeconds() << " us)" ;
270  }
271  //meassure time
272  IceUtil::Time timeSinceLastIteration;
273  IceUtil::Time currentIterationStart;
274  IceUtil::Time lastIterationStart = TimeUtil::GetTime();
275  //loop
276  while (!shutdownRtThread)
277  {
279  //time
280  currentIterationStart = TimeUtil::GetTime();
281  timeSinceLastIteration = currentIterationStart - lastIterationStart;
282  lastIterationStart = currentIterationStart;
283  //call functions
284  rtSwitchControllerSetup(); // << switch controllers
286  rtRunNJointControllers(sensorValuesTimestamp, timeSinceLastIteration); // << run NJointControllers
287  rtHandleInvalidTargets();// << deactivate broken NJointControllers
288  rtRunJointControllers(sensorValuesTimestamp, timeSinceLastIteration); // << run JointControllers
289  //communicate with the simulator
290  {
293  rtSendCommands();
294  //run sim
295  if (synchronizedSimulation)
296  {
297  gotSensorData = false;
298  simulatorPrx->step();
299  }
300  rtUpdateSensors(synchronizedSimulation);
301  }
302  rtUpdateSensorAndControlBuffer(sensorValuesTimestamp, timeSinceLastIteration); // << swap out ControllerTargets / SensorValues
303  ++iterationCount;
305  //sleep remainder
306  //since the timeserver does not end the sleep on shutdown (and this would block shutdown),
307  //we do busy waiting and poll the time
308  const IceUtil::Time sleepUntil = currentIterationStart + controlIterationMs;
309  IceUtil::Time currentTime = TimeUtil::GetTime();
310  while (currentTime < sleepUntil)
311  {
312  if (shutdownRtThread)
313  {
314  return;
315  }
316  if (currentTime < currentIterationStart)
317  {
318  //this fixes sleeping for a long time
319  //in case the time server is reset
320  break;
321  }
322  std::this_thread::sleep_for(std::chrono::microseconds {100}); //polling is done with 10kHz
323  currentTime = TimeUtil::GetTime();
324  }
325  }
326  }
327  catch (Ice::Exception& e)
328  {
329  ARMARX_ERROR << "exception in rtTask!\nwhat:\n"
330  << e.what()
331  << "\n\tname: " << e.ice_id()
332  << "\n\tfile: " << e.ice_file()
333  << "\n\tline: " << e.ice_line()
334  << "\n\tstack: " << e.ice_stackTrace()
335  << std::flush;
336  throw;
337  }
338  catch (std::exception& e)
339  {
340  ARMARX_ERROR << "exception in rtTask!\nwhat:\n" << e.what() << std::flush;
341  throw;
342  }
343  catch (...)
344  {
345  ARMARX_ERROR << "exception in rtTask!" << std::flush;
346  throw;
347  }
348 }
349 
350 void RobotUnitSimulation::reportState(const SimulatedRobotState& state, const Ice::Current&)
351 {
352  IceUtil::Time timestamp = IceUtil::Time::microSeconds(state.timestampInMicroSeconds);
353 
355  {
356  simulationDataTimestampInMicroSeconds = state.timestampInMicroSeconds;
357  }
358  else
359  {
361  }
362 
363  fillTB(anglesTB, state.jointAngles, "JointAngles");
364  fillTB(velocitiesTB, state.jointVelocities, "JointVelocities");
365  fillTB(torquesTB, state.jointTorques, "JointTorques");
366 
367  for (ForceTorqueData const& ftData : state.forceTorqueValues)
368  {
369  updateForceTorque(ftData, timestamp);
370  }
371 
372  // Pose
373  if (skipReport())
374  {
375  ARMARX_DEBUG << deactivateSpam() << "Skipped all sensor values for robot pose";
376  }
377  else
378  {
379  auto g = robPoseTB.guard();
380  ARMARX_CHECK_NOT_NULL(state.pose) << "Robot Pose is not allowed to be NULL. Maybe no state was reported from Simulator!";
381  robPoseTB.getWriteBuffer() = PosePtr::dynamicCast(state.pose)->toEigen();
382  robPoseTB.write();
383  ARMARX_DEBUG << deactivateSpam() << "Got sensor values for robot pose";
384  }
385 
386  if (skipReport())
387  {
388  ARMARX_DEBUG << deactivateSpam() << "Skipped all sensor values for robot vel";
389  return;
390  }
391  else
392  {
393  auto& trans = state.linearVelocity;
394  auto& rotat = state.angularVelocity;
395 
396  auto g = robVelTB.guard();
397  robVelTB.getWriteBuffer().lin(0) = trans->x;
398  robVelTB.getWriteBuffer().lin(1) = trans->y;
399  robVelTB.getWriteBuffer().lin(2) = trans->z;
400  robVelTB.getWriteBuffer().lin = robPoseTB.getReadBuffer().block<3, 3>(0, 0).transpose() * robVelTB.getWriteBuffer().lin;
401  robVelTB.getWriteBuffer().ang(0) = rotat->x;
402  robVelTB.getWriteBuffer().ang(1) = rotat->y;
403  robVelTB.getWriteBuffer().ang(2) = rotat->z;
404  robVelTB.getWriteBuffer().ang = robPoseTB.getReadBuffer().block<3, 3>(0, 0).transpose() * robVelTB.getWriteBuffer().ang;
405  robVelTB.write();
406  ARMARX_DEBUG << deactivateSpam() << "Got sensor values for robot vel";
407  }
408 
409  gotSensorData = true;
410 }
411 
412 void RobotUnitSimulation::updateForceTorque(const ForceTorqueData& ftData, IceUtil::Time timestamp)
413 {
414  auto& sensorName = ftData.sensorName;
415  auto& nodeName = ftData.nodeName;
416 
417  const std::string sensname = ftMappings.count(sensorName) ? ftMappings.at(sensorName).sensorName : sensorName;
418  if (ftMappings.count(sensorName) && ftMappings.at(sensorName).originalReportFrame != nodeName)
419  {
420  ARMARX_ERROR << deactivateSpam(0.25) << "Sensor values for sensor '" << sensorName << "' ('" << sensname << "') are reported in frame '" << nodeName
421  << "' instead of '" << ftMappings.at(sensorName).originalReportFrame << "' as defined during setup! (this value is skipped!)";
422  return;
423  }
424  if (skipReport())
425  {
426  ARMARX_DEBUG << deactivateSpam(10, sensname) << "Skipped all sensor values for force torque of sensor " << sensname << " (node = " << nodeName << ")";
427  return;
428  }
429  auto g = forceTorqueTB.guard();
430  if (!forceTorqueDevs.has(sensname))
431  {
432  ARMARX_WARNING << deactivateSpam(10, sensname) << "no ftsensor with name " << sensname << "\nftsensors:\n" << forceTorqueDevs.keys();
433  return;
434  }
435  auto i = forceTorqueDevs.index(sensname);
436  ARMARX_CHECK_EXPRESSION(forceTorqueTB.getWriteBuffer().size() > i) << forceTorqueTB.getWriteBuffer().size() << " > " << i;
437  auto& force = ftData.force;
438  auto& torque = ftData.torque;
439  ForceTorqueSimulationSensorDevice& ftdev = *forceTorqueDevs.at(i);
440  ftdev.fx.update(force->x);
441  ftdev.fy.update(force->y);
442  ftdev.fz.update(force->z);
443  ftdev.tx.update(torque->x);
444  ftdev.ty.update(torque->y);
445  ftdev.tz.update(torque->z);
446 
447  Eigen::Vector3f filteredTorque;
448  Eigen::Vector3f filteredForce;
449  filteredForce(0) = ftdev.fx.getRawValue();
450  filteredForce(1) = ftdev.fy.getRawValue();
451  filteredForce(2) = ftdev.fz.getRawValue();
452  filteredTorque(0) = ftdev.tx.getRawValue();
453  filteredTorque(1) = ftdev.ty.getRawValue();
454  filteredTorque(2) = ftdev.tz.getRawValue();
455 
456  forceTorqueTB.getWriteBuffer().at(i).force = ftdev.reportingTransformation * filteredForce;
457  forceTorqueTB.getWriteBuffer().at(i).torque = ftdev.reportingTransformation * filteredTorque;
458  forceTorqueTB.write();
459  forceTorqueTimes.at(i) = timestamp.toMicroSeconds() * 1000; // Nanoseconds
460  ARMARX_DEBUG << deactivateSpam(10, sensname) << "Got new sensor values for force torque of sensor " << sensname << " (node = " << nodeName << ")";
461 }
462 
463 void RobotUnitSimulation::fillTB(TripleBufferWithGuardAndTime<std::vector<float> >& b, const NameValueMap& nv, const std::string name) const
464 {
465  if (skipReport())
466  {
467  ARMARX_DEBUG << deactivateSpam(10, name) << "Skipped all sensor values for " << name;
468  return;
469  }
470  auto g = b.guard();
471  std::stringstream ignored;
472  bool someWereIgnored = false;
473  for (const auto& a : nv)
474  {
475  if (jointDevs.has(a.first))
476  {
477  b.getWriteBuffer().at(jointDevs.index(a.first)) = a.second;
478  }
479  else
480  {
481  ignored << a.first << " -> " << a.second << "\n";
482  someWereIgnored = true;
483  }
484  }
485  b.write();
486  ARMARX_DEBUG << deactivateSpam(10, name) << "Got new sensor values for " << name;
487  if (someWereIgnored)
488  {
489  ARMARX_VERBOSE << deactivateSpam(10, name) << "Ignored sensor values for " << name << ":\n" << ignored.str();
490  }
491 }
492 
493 void RobotUnitSimulation::rtSendCommands()
494 {
495  try
496  {
497  auto prx = simulatorPrx->ice_batchOneway();
498  //send commands
499  if (!velocitiesCtrl.empty())
500  {
501  prx->actuateRobotJointsVel(robotName, velocitiesCtrl);
502  }
503  if (!anglesCtrl.empty())
504  {
505  prx->actuateRobotJointsPos(robotName, anglesCtrl);
506  }
507  if (!torquesCtrl.empty())
508  {
509  prx->actuateRobotJointsTorque(robotName, torquesCtrl);
510  }
511 
512  if (platformDev)
513  {
514  Eigen::Vector3f translationVel;
515  translationVel(0) = std::clamp(platformDev->target.velocityX, -maxLinearPlatformVelocity, maxLinearPlatformVelocity);
516  translationVel(1) = std::clamp(platformDev->target.velocityY, -maxLinearPlatformVelocity, maxLinearPlatformVelocity);
517  translationVel(2) = 0;
518  translationVel /= 1000;
519 
520  Eigen::Vector3f rotationVel(0.f, 0.f, std::clamp(platformDev->target.velocityRotation, -maxAngularPlatformVelocity, maxAngularPlatformVelocity));
521 
522  prx->setRobotLinearVelocityRobotRootFrame(robotName, platformDev->getDeviceName(), new Vector3(translationVel));
523  prx->setRobotAngularVelocityRobotRootFrame(robotName, platformDev->getDeviceName(), new Vector3(rotationVel));
524  ARMARX_DEBUG << deactivateSpam(10) << "setting platform vel ang: " << rotationVel.transpose();
525  ARMARX_DEBUG << deactivateSpam(10) << "setting platform vel lin: " << translationVel.transpose();
526  }
527  prx->ice_flushBatchRequests();
528  }
529  catch (Ice::ConnectionRefusedException&)
530  {
531  if (!shutdownRtThread)
532  {
533  //ignore this when shutting down. this probably happened when the simulator
534  //was shut down while the RobotUnitSimulation was still running
535  ARMARX_WARNING << "Ice::ConnectionRefusedException when sending commands to the simulator";
536  }
537  }
538  catch (Ice::NotRegisteredException&)
539  {
540  if (!shutdownRtThread)
541  {
542  //ignore this when shutting down. this probably happened when the simulator
543  //was shut down while the RobotUnitSimulation was still running
544  ARMARX_WARNING << "Ice::NotRegisteredException when sending commands to the simulator";
545  }
546  }
547 }
548 
549 bool RobotUnitSimulation::skipReport() const
550 {
551  static const std::set<RobotUnitState> reportAcceptingStates
552  {
555  };
556  return !reportAcceptingStates.count(getRobotUnitState());
557 }
558 
559 void RobotUnitSimulation::rtPollRobotState()
560 {
561  if (!isPolling.exchange(true))
562  {
563  std::thread
564  {
565  [&]
566  {
567  try
568  {
569  const auto name = getRobotName();
570  auto rootname = robot->getRootNode()->getName();
571  SimulatedRobotState state = simulatorPrx->getRobotState(robotName);
572 
573  reportState(state);
574  }
575  catch (Ice::Exception& e)
576  {
577  ARMARX_ERROR << "exception in polling!\nwhat:\n"
578  << e.what()
579  << "\n\tname: " << e.ice_id()
580  << "\n\tfile: " << e.ice_file()
581  << "\n\tline: " << e.ice_line()
582  << "\n\tstack: " << e.ice_stackTrace()
583  << std::flush;
584  throw;
585  }
586  catch (std::exception& e)
587  {
588  ARMARX_ERROR << "exception in polling!\nwhat:\n" << e.what() << std::flush;
589  throw;
590  }
591  catch (...)
592  {
593  ARMARX_ERROR << "exception in polling!" << std::flush;
594  throw;
595  }
596  isPolling = false;
597  }
598  } .detach();
599  }
600 }
601 
602 void RobotUnitSimulation::componentPropertiesUpdated(const std::set<std::string>& changedProperties)
603 {
604  RobotUnit::componentPropertiesUpdated(changedProperties);
605  if (changedProperties.count("SynchronizedSimulation"))
606  {
607  synchronizedSimulation = getProperty<bool>("SynchronizedSimulation").getValue();
608  }
609  if (areDevicesReady())
610  {
611  if (synchronizedSimulation)
612  {
613  simulatorPrx->stop();
614  ARMARX_IMPORTANT << "using synchronized simulator execution" << std::flush;
615  }
616  else
617  {
618  simulatorPrx->start();
619  ARMARX_IMPORTANT << "using synchronized simulator execution" << std::flush;
620  }
621  }
622 }
623 
624 void RobotUnitSimulation::rtUpdateSensors(bool wait)
625 {
626  //wait for all new data
627  if (wait)
628  {
629  std::mutex dummy;
630  std::unique_lock<std::mutex> dummlock {dummy};
631  std::size_t fails = 0;
632  while (!gotSensorData)
633  {
634  ARMARX_IMPORTANT << deactivateSpam() << "waiting for up to date sensor values (iteration " << iterationCount << ") ";
635  cvGotSensorData.wait_for(dummlock, std::chrono::milliseconds {10});
636  ++fails;
637  if (!(fails % 10))
638  {
639  rtPollRobotState();
640  }
641  }
642  }
643 
644  // This should be the timestamp from the time where the data was queried
645  // We have to use armarx::rtNow() now because of changes in the framework to assess the timestamp in
646  // a realtime-conform way (using MONOTONIC_RAW clock, which is the time difference since last boot).
647  // This probably breaks simulation speeds faster than realtime, but this feature probably was broken
648  // before anyways. See https://git.h2t.iar.kit.edu/sw/armarx/armarx-simulation/-/issues/26.
649  const IceUtil::Time now = armarx::rtNow();
650  //const IceUtil::Time now = IceUtil::Time::microSeconds(simulationDataTimestampInMicroSeconds);
651  const IceUtil::Time timeSinceLastIteration = now - sensorValuesTimestamp;
652  const float dt = static_cast<float>(timeSinceLastIteration.toSecondsDouble());
653  sensorValuesTimestamp = now;
654  torquesTB.read();
655  anglesTB.read();
656  velocitiesTB.read();
657  robPoseTB.read();
658  robVelTB.read();
659  forceTorqueTB.read();
660  //update joint sensors
661  for (std::size_t i = 0; i < jointDevs.size(); ++i)
662  {
663  JointSimulationDevice& jdev = *jointDevs.at(i);
664  const float deltav = velocitiesTB.getReadBuffer().at(i) - jdev.sensorValue.velocity;
665  jdev.sensorValue.acceleration = deltav / dt;
666  jdev.sensorValue.position = anglesTB.getReadBuffer().at(i);
667  jdev.sensorValue.torque = torquesTB.getReadBuffer().at(i);
668  jdev.sensorValue.velocity = velocitiesTB.getReadBuffer().at(i);
669  }
670 
671  //ft
672  for (std::size_t i = 0; i < forceTorqueDevs.size(); ++i)
673  {
674  ForceTorqueSimulationSensorDevice& ft = *forceTorqueDevs.at(i);
675  ft.sensorValue.force = forceTorqueTB.getReadBuffer().at(i).force;
676  ft.sensorValue.torque = forceTorqueTB.getReadBuffer().at(i).torque;
677  }
678  //platform
679  if (platformDev)
680  {
681  auto& s = platformDev->sensorValue;
682 
683  const float absolutePositionX = robPoseTB.getReadBuffer()(0, 3);
684  const float absolutePositionY = robPoseTB.getReadBuffer()(1, 3);
685  const float absolutePositionRotation = VirtualRobot::MathTools::eigen4f2rpy(robPoseTB.getReadBuffer())(2);
686 
687  Eigen::Vector2f relativePositionGlobalFrame;
688  relativePositionGlobalFrame << absolutePositionX - platformDev->initAbsolutePositionX,
689  absolutePositionY - platformDev->initAbsolutePositionY;
690  s.relativePositionRotation = absolutePositionRotation - platformDev->initAbsolutePositionRotation;
691  // Revert the rotation by rotating by the negative angle
692  Eigen::Vector2f relativePosition = Eigen::Rotation2Df(-platformDev->initAbsolutePositionRotation) * relativePositionGlobalFrame;
693  s.relativePositionX = relativePosition(0);
694  s.relativePositionY = relativePosition(1);
695 
696  const RobVel& v = robVelTB.getReadBuffer();
697  s.setVelocitiesAndDeriveAcceleration(v.lin(0) / 3.f, v.lin(1) / 3.f, v.ang(2) / 5.0f, dt);
698  }
699  //globalpose
700  // globalPoseDevice->sensor.pose = robPoseTB.getReadBuffer();
701 
702  rtSetRobotGlobalPose(robPoseTB.getReadBuffer(), false);
703  //this call should not do anything in this case, since sensors are updated above
704  rtReadSensorDeviceValues(sensorValuesTimestamp, timeSinceLastIteration);
705 }
armarx::TripleBufferWithGuardAndTime::getReadBuffer
const T & getReadBuffer() const
Definition: RobotUnitSimulation.h:83
armarx::RobotUnitModule::Units::initializeDefaultUnits
virtual void initializeDefaultUnits()
Calls all init hooks for all managed Units.
Definition: RobotUnitModuleUnits.cpp:201
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
armarx::KeyValueVector::keys
KeyContT const & keys() const
Definition: KeyValueVector.h:164
armarx::ForceTorqueSimulationSensorDevice::fx
filters::ButterworthFilter fx
Definition: ForceTorqueSimulationSensorDevice.h:56
armarx::RobotUnitSimulation::rtThread
std::thread rtThread
Definition: RobotUnitSimulation.h:195
armarx::RobotUnitModule::ControlThread::rtRunNJointControllers
void rtRunNJointControllers(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Runs NJoint controllers.
Definition: RobotUnitModuleControlThread.cpp:571
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
armarx::RTThreadTimingsSensorDevice::rtMarkRtBusSendReceiveStart
virtual void rtMarkRtBusSendReceiveStart()=0
OnScopeExit.h
armarx::KeyValueVector::at
ValT & at(IdxT i)
Definition: KeyValueVector.h:110
armarx::RobotUnitSimulation::simulatorPrxName
std::string simulatorPrxName
Definition: RobotUnitSimulation.h:198
armarx::TripleBufferWithGuardAndTime::write
void write()
Definition: RobotUnitSimulation.h:87
armarx::filters::ButterworthFilter::update
void update(Ice::Long, const VariantBasePtr &value, const Ice::Current &=Ice::emptyCurrent) override
Definition: ButterworthFilter.cpp:92
armarx::RobotUnitSimulation::reportState
void reportState(SimulatedRobotState const &state, const Ice::Current &=Ice::emptyCurrent) override
Definition: RobotUnitSimulation.cpp:350
ARMARX_CHECK_NOT_NULL
#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...
Definition: ExpressionException.h:206
armarx::KeyValueVector::size
IdxT size() const
Definition: KeyValueVector.h:146
armarx::ForceTorqueSimulationSensorDevice::ty
filters::ButterworthFilter ty
Definition: ForceTorqueSimulationSensorDevice.h:54
armarx::KeyValueVector::has
bool has(const KeyT &k) const
Definition: KeyValueVector.h:176
armarx::Split
std::vector< std::string > Split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
Definition: StringHelperTemplates.h:35
armarx::TripleBufferWithGuardAndTime::guard
std::unique_lock< std::recursive_mutex > guard()
Definition: RobotUnitSimulation.h:60
armarx::RTThreadTimingsSensorDevice::rtMarkRtLoopPreSleep
virtual void rtMarkRtLoopPreSleep()=0
armarx::RobotUnitSimulation::maxAngularPlatformVelocity
float maxAngularPlatformVelocity
Definition: RobotUnitSimulation.h:202
armarx::ForceTorqueSimulationSensorDevice::reportingTransformation
const Eigen::Matrix3f reportingTransformation
Definition: ForceTorqueSimulationSensorDevice.h:61
armarx::RobotUnitModule::Devices::rtGetRTThreadTimingsSensorDevice
RTThreadTimingsSensorDevice & rtGetRTThreadTimingsSensorDevice()
Returns the SensorDevice used to log timings in the ControlThread.
Definition: RobotUnitModuleDevices.h:401
armarx::KeyValueVector::index
IdxT index(const KeyT &k) const
Definition: KeyValueVector.h:104
ARMARX_ON_SCOPE_EXIT
#define ARMARX_ON_SCOPE_EXIT
Executes given code when the enclosing scope is left.
Definition: OnScopeExit.h:112
armarx::RobotUnitModule::ControlThread::rtReadSensorDeviceValues
void rtReadSensorDeviceValues(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Calls SensorDevice::rtReadSensorValues for all SensorDevices.
Definition: RobotUnitModuleControlThread.cpp:532
armarx::JointSimulationDevice
Definition: JointSimulationDevice.h:35
armarx::RobotUnitModule::ControlThread::rtSetRobotGlobalPose
void rtSetRobotGlobalPose(const Eigen::Matrix4f &gp, bool updateRobot=true)
Definition: RobotUnitModuleControlThread.cpp:1222
armarx::RobotUnitModule::ModuleBase::getRobotUnitState
RobotUnitState getRobotUnitState() const
Returns the RobotUnit's State.
Definition: RobotUnitModuleBase.ipp:29
armarx::SensorValueForceTorque::force
Eigen::Vector3f force
Definition: SensorValueForceTorque.h:35
clamp
double clamp(double x, double a, double b)
Definition: point.hpp:125
cxxopts::empty
bool empty(const std::string &s)
Definition: cxxopts.hpp:255
armarx::RTThreadTimingsSensorDevice::rtMarkRtLoopStart
virtual void rtMarkRtLoopStart()=0
armarx::RobotUnitModule::ModuleBase::finishUnitInitialization
virtual void finishUnitInitialization()
Transition RobotUnitState::InitializingUnits -> RobotUnitState::WaitingForRTThreadInitialization.
Definition: RobotUnitModuleBase.cpp:268
armarx::ForceTorqueSimulationSensorDevice::fz
filters::ButterworthFilter fz
Definition: ForceTorqueSimulationSensorDevice.h:58
armarx::RobotUnitState::InitializingUnits
@ InitializingUnits
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
armarx::RobotUnitModule::ControlThread::rtRunJointControllers
void rtRunJointControllers(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Runs Joint controllers and writes target values to ControlDevices.
Definition: RobotUnitModuleControlThread.cpp:559
armarx::ctrlutil::a
double a(double t, double a0, double j)
Definition: CtrlUtil.h:45
armarx::RobotUnitState::Running
@ Running
armarx::RobotUnitSimulation::robot
VirtualRobot::RobotPtr robot
Definition: RobotUnitSimulation.h:204
armarx::RobotUnitModule::ModuleBase::componentPropertiesUpdated
void componentPropertiesUpdated(const std::set< std::string > &changedProperties) override
Definition: RobotUnitModuleBase.cpp:205
armarx::KeyValueVector::add
void add(KeyT key, ValT value)
Definition: KeyValueVector.h:92
armarx::TimeUtil::HasTimeServer
static bool HasTimeServer()
check if we have been initialized with a Timeserver
Definition: TimeUtil.cpp:114
armarx::flush
const LogSender::manipulator flush
Definition: LogSender.h:251
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::TripleBufferWithGuardAndTime::reinit
void reinit(const T &i)
Definition: RobotUnitSimulation.h:74
armarx::Vector3
The Vector3 class.
Definition: Pose.h:112
armarx::RobotUnitModule::ModuleBase::finishControlThreadInitialization
virtual void finishControlThreadInitialization()
Transition RobotUnitState::InitializingControlThread -> RobotUnitState::Running.
Definition: RobotUnitModuleBase.cpp:289
armarx::RobotUnitModule::ControlThread::rtSwitchControllerSetup
bool rtSwitchControllerSetup(SwitchControllerMode mode=SwitchControllerMode::IceRequests)
Changes the set of active controllers.
Definition: RobotUnitModuleControlThread.cpp:291
armarx::RobotUnitSimulation::onConnectRobotUnit
void onConnectRobotUnit() override
called in onConnectComponent
Definition: RobotUnitSimulation.cpp:122
armarx::SensorValueForceTorque::torque
DETAIL_SensorValueBase_DEFAULT_METHOD_IMPLEMENTATION Eigen::Vector3f torque
Definition: SensorValueForceTorque.h:34
armarx::RobotUnitModule::Devices::addSensorDevice
void addSensorDevice(const SensorDevicePtr &sd)
Adds a SensorDevice to the robot.
Definition: RobotUnitModuleDevices.cpp:377
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
armarx::RobotUnitSimulation::robotName
std::string robotName
Definition: RobotUnitSimulation.h:199
ARMARX_CHECK_POSITIVE
#define ARMARX_CHECK_POSITIVE(number)
This macro evaluates whether number is positive (> 0) and if it turns out to be false it will throw a...
Definition: ExpressionException.h:145
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::RobotUnitState::InitializingControlThread
@ InitializingControlThread
armarx::TripleBufferWithGuardAndTime
Definition: RobotUnitSimulation.h:56
armarx::RobotUnitModule::ControlThread::rtHandleInvalidTargets
void rtHandleInvalidTargets()
Deactivates all NJointControllers generating invalid targets.
Definition: RobotUnitModuleControlThread.cpp:509
armarx::TimeUtil::GetTime
static IceUtil::Time GetTime(TimeMode timeMode=TimeMode::VirtualTime)
Get the current time.
Definition: TimeUtil.cpp:42
armarx::ForceTorqueSimulationSensorDevice::tx
filters::ButterworthFilter tx
Definition: ForceTorqueSimulationSensorDevice.h:53
armarx::TripleBufferWithGuardAndTime::getWriteBuffer
T & getWriteBuffer()
Definition: RobotUnitSimulation.h:79
armarx::RobotUnitModule::RobotData::getRobotPlatformName
const std::string & getRobotPlatformName() const
Returns the name of the robot's platform.
Definition: RobotUnitModuleRobotData.cpp:75
ExpressionException.h
armarx::control::njoint_controller::platform::platform_follower_controller::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformFollowerController.h:91
armarx::ManagedIceObject::usingTopic
void usingTopic(const std::string &name, bool orderedPublishing=false)
Registers a proxy for subscription after initialization.
Definition: ManagedIceObject.cpp:248
armarx::RobotUnitModule::Devices::addControlDevice
void addControlDevice(const ControlDevicePtr &cd)
Adds a ControlDevice to the robot.
Definition: RobotUnitModuleDevices.cpp:335
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
armarx::RobotUnitModule::ControlThread::rtResetAllTargets
void rtResetAllTargets()
Calls JointController::rtResetTarget for all active Joint controllers.
Definition: RobotUnitModuleControlThread.cpp:498
armarx::SensorDeviceTemplate::sensorValue
SensorValueType sensorValue
Definition: SensorDevice.h:123
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::ForceTorqueSimulationSensorDevice
Definition: ForceTorqueSimulationSensorDevice.h:33
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::RobotUnitSimulation::joinControlThread
void joinControlThread() override
Implementations have to join their ControlThread in this hook. (used by RobotUnit::finishRunning())
Definition: RobotUnitSimulation.cpp:131
armarx::RobotUnitModule::ModuleBase::areDevicesReady
bool areDevicesReady() const
Returns whether Devices are ready.
Definition: RobotUnitModuleBase.cpp:403
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:182
armarx::ForceTorqueSimulationSensorDevice::tz
filters::ButterworthFilter tz
Definition: ForceTorqueSimulationSensorDevice.h:55
armarx::RTThreadTimingsSensorDevice::rtMarkRtBusSendReceiveEnd
virtual void rtMarkRtBusSendReceiveEnd()=0
armarx::RobotUnitSimulation::rtTask
void rtTask()
Definition: RobotUnitSimulation.cpp:137
armarx::ForceTorqueSimulationSensorDevice::fy
filters::ButterworthFilter fy
Definition: ForceTorqueSimulationSensorDevice.h:57
armarx::RobotUnitModule::ControlThread::rtUpdateSensorAndControlBuffer
void rtUpdateSensorAndControlBuffer(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Updates the current SensorValues and ControlTargets for code running outside of the ControlThread.
Definition: RobotUnitModuleControlThread.cpp:846
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::RobotUnitSimulation::simulatorPrx
SimulatorInterfacePrx simulatorPrx
Definition: RobotUnitSimulation.h:196
armarx::TripleBufferWithGuardAndTime::read
void read()
Definition: RobotUnitSimulation.h:94
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::transpose
std::vector< std::vector< T > > transpose(const std::vector< std::vector< T >> &src, Thrower thrower)
Definition: SimoxCSpace.cpp:706
armarx::RobotUnitSimulation::simulationDataTimestampInMicroSeconds
std::atomic< long > simulationDataTimestampInMicroSeconds
Definition: RobotUnitSimulation.h:197
armarx::RobotUnitSimulation::maxLinearPlatformVelocity
float maxLinearPlatformVelocity
Definition: RobotUnitSimulation.h:201
armarx::filters::ButterworthFilter::getRawValue
double getRawValue() const
Definition: ButterworthFilter.cpp:143
armarx::RobotUnitModule::RobotData::cloneRobot
VirtualRobot::RobotPtr cloneRobot(bool updateCollisionModel=false) const
Returns a clone of the robot's model.
Definition: RobotUnitModuleRobotData.cpp:127
armarx::RobotUnitSimulation::onInitRobotUnit
void onInitRobotUnit() override
called in onInitComponent
Definition: RobotUnitSimulation.cpp:38
RobotUnitSimulation.h
armarx::RobotUnitModule::RobotData::getRobotName
std::string getRobotName() const
Returns the robot's name.
Definition: RobotUnitModuleRobotData.cpp:117
armarx::RobotUnitModule::ModuleBase::finishDeviceInitialization
virtual void finishDeviceInitialization()
Transition RobotUnitState::InitializingDevices -> RobotUnitState::InitializingUnits.
Definition: RobotUnitModuleBase.cpp:247
armarx::ManagedIceObject::usingProxy
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Definition: ManagedIceObject.cpp:151
armarx::ctrlutil::s
double s(double t, double s0, double v0, double a0, double j)
Definition: CtrlUtil.h:33
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::RobotUnitSimulation::shutdownRtThread
std::atomic_bool shutdownRtThread
Definition: RobotUnitSimulation.h:194
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:42
armarx::RobotUnitSimulation::componentPropertiesUpdated
void componentPropertiesUpdated(const std::set< std::string > &changedProperties) override
Definition: RobotUnitSimulation.cpp:602
armarx::rtNow
IceUtil::Time rtNow()
Definition: RtTiming.h:40