TCPControlUnit.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 ArmarX::
17 * @author Mirko Waechter ( mirko.waechter at kit dot edu)
18 * @date 2013
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22 
23 #include "TCPControlUnit.h"
25 
27 
30 #include <VirtualRobot/RobotConfig.h>
31 #include <VirtualRobot/XML/RobotIO.h>
32 #include <VirtualRobot/MathTools.h>
33 
34 #include <SimoxUtility/algorithm/string/string_tools.h>
35 
36 #include <Eigen/Core>
37 
38 #include <memory>
39 #include <cfloat>
40 
41 using namespace VirtualRobot;
42 using namespace Eigen;
43 
44 namespace armarx
45 {
46  TCPControlUnit::TCPControlUnit() :
47  maxJointVelocity(30.f / 180 * 3.141),
48  cycleTime(30),
49  requested(false),
50  calculationRunning(false)
51  {
52 
53  }
54 
56  {
57  topicName = getName() + "State";
58  usingProxy(getProperty<std::string>("KinematicUnitName").getValue());
59  usingProxy(getProperty<std::string>("RobotStateComponentName").getValue());
60  offeringTopic("DebugObserver");
61  offeringTopic(topicName);
62  usingTopic(getProperty<std::string>("RobotStateTopicName").getValue());
63 
64  cycleTime = getProperty<int>("CycleTime").getValue();
65  maxJointVelocity = getProperty<float>("MaxJointVelocity").getValue();
66  }
67 
68 
70  {
71  std::unique_lock lock(dataMutex);
72 
73  debugObs = getTopic<DebugObserverInterfacePrx>("DebugObserver");
74  kinematicUnitPrx = getProxy<KinematicUnitInterfacePrx>(getProperty<std::string>("KinematicUnitName").getValue());
75  robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>(getProperty<std::string>("RobotStateComponentName").getValue());
76 
77 
78  //remoteRobotPrx = robotStateComponentPrx->getSynchronizedRobot();
79  robotName = robotStateComponentPrx->getRobotName();
80  localRobot = RemoteRobot::createLocalClone(robotStateComponentPrx, robotStateComponentPrx->getRobotFilename(), robotStateComponentPrx->getArmarXPackages());
81  jointExistenceCheckRobot = RemoteRobot::createLocalClone(robotStateComponentPrx, robotStateComponentPrx->getRobotFilename(), robotStateComponentPrx->getArmarXPackages());
82 
83  localReportRobot = localRobot->clone(localRobot->getName());
84 
85  std::string nodesetsString = getProperty<std::string>("TCPsToReport").getValue();
86  nodesToReport.clear();
87  if (!nodesetsString.empty())
88  {
89  if (nodesetsString == "*")
90  {
91  auto nodesets = localReportRobot->getRobotNodeSets();
92 
93  for (RobotNodeSetPtr& set : nodesets)
94  {
95  if (set->getTCP())
96  {
97  nodesToReport.push_back(set->getTCP());
98  }
99  }
100  }
101  else
102  {
103  std::vector<std::string> nodesetNames = simox::alg::split(nodesetsString, ",");
104 
105  for (auto& name : nodesetNames)
106  {
107  auto node = localReportRobot->getRobotNode(name);
108 
109  if (node)
110  {
111  nodesToReport.push_back(node);
112  }
113  else
114  {
115  ARMARX_ERROR << "Could not find node with name: " << name;
116  }
117  }
118  }
119  }
120 
121  std::vector<RobotNodePtr> nodes = localRobot->getRobotNodes();
122 
123  for (unsigned int i = 0; i < nodes.size(); i++)
124  {
125  ARMARX_VERBOSE << nodes.at(i)->getName();
126  }
127 
128 
129 
130  listener = getTopic<TCPControlUnitListenerPrx>(topicName);
131 
132  requested = false;
133 
134  if (execTask)
135  {
136  execTask->stop();
137  }
138 
139  execTask = new PeriodicTask<TCPControlUnit>(this, &TCPControlUnit::periodicExec, cycleTime, false, "TCPVelocityCalculator");
140  execTask->start();
141  execTask->setDelayWarningTolerance(100);
142 
143  }
144 
146  {
147 
148  try
149  {
150  release();
151  }
152  catch (std::exception& e)
153  {
154  ARMARX_WARNING << "Releasing TCP Unit failed";
155  }
156 
157  if (execTask)
158  {
159  execTask->stop();
160  }
161  }
162 
164  {
165  }
166 
167 
168 
169  void TCPControlUnit::setCycleTime(Ice::Int milliseconds, const Ice::Current& c)
170  {
171  std::unique_lock lock(taskMutex);
172  cycleTime = milliseconds;
173 
174  if (execTask)
175  {
176  execTask->changeInterval(cycleTime);
177  }
178  }
179 
180  void TCPControlUnit::setTCPVelocity(const std::string& nodeSetName, const std::string& tcpName, const FramedDirectionBasePtr& translationVelocity, const FramedDirectionBasePtr& orientationVelocityRPY, const Ice::Current& c)
181  {
182  if (!isRequested())
183  {
184  ARMARX_WARNING << "Implicitly requesting TCPControlUnit! Please call request before setting TCPVelocities!";
185  request();
186  }
187 
188  std::unique_lock lock(dataMutex);
189  ARMARX_CHECK_EXPRESSION(jointExistenceCheckRobot->hasRobotNodeSet(nodeSetName)) << "The robot does not have the node set: " + nodeSetName;
190 
191 
192  if (translationVelocity)
193  {
194  ARMARX_DEBUG << "Setting new Velocity for " << nodeSetName << " in frame " << translationVelocity->frame << ":\n" << FramedDirectionPtr::dynamicCast(translationVelocity)->toEigen();
195  }
196 
197  if (orientationVelocityRPY)
198  {
199  ARMARX_DEBUG << "Orientation Velo in frame " << orientationVelocityRPY->frame << ": \n" << FramedDirectionPtr::dynamicCast(orientationVelocityRPY)->toEigen();
200  }
201 
202  TCPVelocityData data;
203  data.nodeSetName = nodeSetName;
204  data.translationVelocity = FramedDirectionPtr::dynamicCast(translationVelocity);
205  data.orientationVelocity = FramedDirectionPtr::dynamicCast(orientationVelocityRPY);
206 
207  if (tcpName.empty())
208  {
209  data.tcpName = jointExistenceCheckRobot->getRobotNodeSet(nodeSetName)->getTCP()->getName();
210  }
211  else
212  {
213  ARMARX_CHECK_EXPRESSION(jointExistenceCheckRobot->hasRobotNode(tcpName)) << "The robot does not have the node: " + tcpName;
214 
215  data.tcpName = tcpName;
216  }
217 
218  tcpVelocitiesMap[data.tcpName] = data;
219  }
220 
221 
222  void TCPControlUnit::init(const Ice::Current& c)
223  {
224  }
225 
226  void TCPControlUnit::start(const Ice::Current& c)
227  {
228  }
229 
230  void TCPControlUnit::stop(const Ice::Current& c)
231  {
232  }
233 
234  UnitExecutionState TCPControlUnit::getExecutionState(const Ice::Current& c)
235  {
236  switch (getState())
237  {
238  case eManagedIceObjectStarted:
239  return eUnitStarted;
240 
241  case eManagedIceObjectInitialized:
242  case eManagedIceObjectStarting:
243  return eUnitInitialized;
244 
245  case eManagedIceObjectExiting:
246  case eManagedIceObjectExited:
247  return eUnitStopped;
248 
249  default:
250  return eUnitConstructed;
251  }
252  }
253 
254  void TCPControlUnit::request(const Ice::Current& c)
255  {
256  if (execTask)
257  {
258  // while (calculationRunning)
259  // {
260  // IceUtil::ThreadControl::yield();
261  // }
262 
263  execTask->stop();
264  }
265 
266  ARMARX_IMPORTANT << "Requesting TCPControlUnit";
267  std::unique_lock lock(dataMutex);
268  requested = true;
269 
270  execTask = new PeriodicTask<TCPControlUnit>(this, &TCPControlUnit::periodicExec, cycleTime, false, "TCPVelocityCalculator");
271  execTask->start();
272  execTask->setDelayWarningTolerance(100);
273  ARMARX_IMPORTANT << "Requested TCPControlUnit";
274  }
275 
276  void TCPControlUnit::release(const Ice::Current& c)
277  {
278  ARMARX_IMPORTANT << "Releasing TCPControlUnit";
279  std::unique_lock lock(dataMutex);
280 
281  // while (calculationRunning)
282  // {
283  // IceUtil::ThreadControl::yield();
284  // }
285 
286  tcpVelocitiesMap.clear();
287  localTcpVelocitiesMap.clear();
288  requested = false;
289  //kinematicUnitPrx->stop();
290  ARMARX_IMPORTANT << "Released TCPControlUnit";
291 
292  }
293 
294  bool TCPControlUnit::isRequested(const Ice::Current& c)
295  {
296  // no lock needed to read a single bool value.
297  return requested;
298  }
299 
300 
301  void TCPControlUnit::periodicExec()
302  {
303  std::unique_lock lock(dataMutex, std::defer_lock);
304 
305  if (lock.try_lock())
306  {
307 
308  {
309  localTcpVelocitiesMap.clear();
310  TCPVelocityDataMap::iterator it = tcpVelocitiesMap.begin();
311 
312  for (; it != tcpVelocitiesMap.end(); it++)
313  {
314  localTcpVelocitiesMap[it->first] = it->second;
315  }
316 
317  localDIKMap.clear();
318  DIKMap::iterator itDIK = dIKMap.begin();
319 
320  for (; itDIK != dIKMap.end(); itDIK++)
321  {
322  localDIKMap[itDIK->first] = itDIK->second;
323  }
324 
325  //ARMARX_DEBUG << "RN TCP R pose1:" << localRobot->getRobotNode("TCP R")->getGlobalPose();
326 
327  RemoteRobot::synchronizeLocalClone(localRobot, robotStateComponentPrx);
328  //ARMARX_DEBUG << "RN TCP R pose2:" << localRobot->getRobotNode("TCP R")->getGlobalPose();
329  }
330 
331  if (requested)
332  {
334  }
335  }
336  }
337 
338 
339 
341  {
342  TCPVelocityDataMap::iterator it = localTcpVelocitiesMap.begin();
343 
344  for (; it != localTcpVelocitiesMap.end(); it++)
345  {
346  const TCPVelocityData& data = it->second;
347  RobotNodeSetPtr nodeSet = localRobot->getRobotNodeSet(data.nodeSetName);
348  // std::string refFrame = nodeSet->getTCP()->getName();
349  DIKMap::iterator itDIK = localDIKMap.find(data.nodeSetName);
350 
351  if (itDIK == localDIKMap.end())
352  {
353  VirtualRobot::DifferentialIKPtr dIk(new EDifferentialIK(nodeSet, localRobot->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
354  float lambda = getProperty<float>("LambdaDampedSVD").getValue();
355  dIk->setDampedSvdLambda(lambda);
356  localDIKMap[data.nodeSetName] = dIk;
357  }
358 
359  auto dIk = std::dynamic_pointer_cast<EDifferentialIK>(localDIKMap[data.nodeSetName]);
360  dIk->clearGoals();
361  }
362 
363  using namespace Eigen;
364 
365  it = localTcpVelocitiesMap.begin();
366 
367  for (; it != localTcpVelocitiesMap.end(); it++)
368  {
369 
370  TCPVelocityData& data = it->second;
371  // RobotNodeSetPtr nodeSet = localRobot->getRobotNodeSet(data.nodeSetName);
372  std::string refFrame = localRobot->getRootNode()->getName();
374 
375  if (data.translationVelocity && data.orientationVelocity)
376  {
377  mode = IKSolver::All;
378  // ARMARX_DEBUG << deactivateSpam(4) << "FullMode";
379  }
380  else if (data.translationVelocity && !data.orientationVelocity)
381  {
382  mode = IKSolver::Position;
383  }
384  else if (!data.translationVelocity && data.orientationVelocity)
385  {
386  mode = IKSolver::Orientation;
387  }
388  else
389  {
390  // ARMARX_VERBOSE << deactivateSpam(2) << "No mode feasible for " << data.nodeSetName << " - skipping";
391  continue;
392  }
393 
394  RobotNodePtr tcpNode = localRobot->getRobotNode(data.tcpName);
395  Eigen::Matrix4f m;
396  m.setIdentity();
397 
398  if (data.orientationVelocity)
399  {
400  Eigen::Matrix3f rotInOriginalFrame, rotInRefFrame;
401  rotInOriginalFrame = Eigen::AngleAxisf(data.orientationVelocity->z * cycleTime * 0.001, Eigen::Vector3f::UnitZ())
402  * Eigen::AngleAxisf(data.orientationVelocity->y * cycleTime * 0.001, Eigen::Vector3f::UnitY())
403  * Eigen::AngleAxisf(data.orientationVelocity->x * cycleTime * 0.001, Eigen::Vector3f::UnitX());
404 
405  if (data.orientationVelocity->frame != refFrame)
406  {
407  Eigen::Matrix4f trafoOriginalFrameToGlobal = Eigen::Matrix4f::Identity();
408 
409  if (data.orientationVelocity->frame != GlobalFrame)
410  {
411  trafoOriginalFrameToGlobal = localRobot->getRobotNode(data.orientationVelocity->frame)->getGlobalPose();
412  }
413 
414  Eigen::Matrix4f trafoRefFrameToGlobal = Eigen::Matrix4f::Identity();
415 
416  if (refFrame != GlobalFrame)
417  {
418  trafoRefFrameToGlobal = localRobot->getRobotNode(refFrame)->getGlobalPose();
419  }
420 
421  Eigen::Matrix4f trafoOriginalToRef = trafoRefFrameToGlobal.inverse() * trafoOriginalFrameToGlobal;
422  rotInRefFrame = trafoOriginalToRef.block<3, 3>(0, 0) * rotInOriginalFrame * trafoOriginalToRef.block<3, 3>(0, 0).inverse();
423  }
424  else
425  {
426  rotInRefFrame = rotInOriginalFrame;
427  }
428 
429  m.block(0, 0, 3, 3) = rotInRefFrame * (tcpNode->getGlobalPose().block(0, 0, 3, 3));
430  }
431 
432  // ARMARX_VERBOSE << deactivateSpam(1) << "Delta Mat: \n" << m;
433 
434 
435  // m = m * tcpNode->getGlobalPose();
436 
437  if (data.translationVelocity)
438  {
439  data.translationVelocity = FramedDirection::ChangeFrame(localRobot, *data.translationVelocity, refFrame);
440  ARMARX_INFO << deactivateSpam(1) << "Translation in " << refFrame << ": " << data.translationVelocity->toEigen();
441  m.block(0, 3, 3, 1) = tcpNode->getGlobalPose().block(0, 3, 3, 1) + data.translationVelocity->toEigen() * cycleTime * 0.001;
442  }
443 
444 
445  DifferentialIKPtr dIK = localDIKMap[data.nodeSetName];
446 
447  if (!dIK)
448  {
449  ARMARX_WARNING << deactivateSpam(1) << "DiffIK is NULL for robot node set: " << data.nodeSetName;
450  continue;
451  }
452 
453  // ARMARX_VERBOSE << deactivateSpam(1) << "Old Pos: \n" << tcpNode->getGlobalPose();
454  // ARMARX_VERBOSE << deactivateSpam(1) << "New Goal: \n" << m;
455  // if(tcpNode != nodeSet->getTCP())
456  // {
457  // mode = IKSolver::Z;
458  // Eigen::VectorXf weight(1);
459  // weight << 0.2;
460  // boost::shared_dynamic_cast<EDifferentialIK>(dIK)->setGoal(m, tcpNode,mode, 0.001, 0.001/180.0f*3.14159, weight);
461  // }
462  // else
463  dIK->setGoal(m, tcpNode, mode, 0.001, 0.001 / 180.0f * 3.14159);
464 
465  // ARMARX_VERBOSE << deactivateSpam(1) << "Delta to Goal: " << dIK->getDeltaToGoal(tcpNode);
466  }
467 
468 
469  NameValueMap targetVelocities;
470  NameControlModeMap controlModes;
471  DIKMap::iterator itDIK = localDIKMap.begin();
472 
473  for (; itDIK != localDIKMap.end(); itDIK++)
474  {
475  RobotNodeSetPtr robotNodeSet = localRobot->getRobotNodeSet(itDIK->first);
476 
477  auto dIK = std::dynamic_pointer_cast<EDifferentialIK>(itDIK->second);
478  // ARMARX_VERBOSE << deactivateSpam(1) << "Old Pos: \n" << robotNodeSet->getTCP()->getGlobalPose();
479  // dIK->setVerbose(true);
480  Eigen::VectorXf jointDelta;
481  dIK->computeSteps(jointDelta, 0.8f, 0.001, 1, &EDifferentialIK::computeStep); // 1.0, 0.00001, 50
482  // ARMARX_VERBOSE << deactivateSpam(1) << "New Goal: \n" << robotNodeSet->getTCP()->getGlobalPose();
483 
484  jointDelta /= (cycleTime * 0.001);
485 
486  jointDelta = applyMaxJointVelocity(jointDelta, maxJointVelocity);
487 
488  lastTCPPose = robotNodeSet->getTCP()->getGlobalPose();
489 
490  // build name value map
491 
492  const std::vector< VirtualRobot::RobotNodePtr > nodes = robotNodeSet->getAllRobotNodes();
493  std::vector< VirtualRobot::RobotNodePtr >::const_iterator iter = nodes.begin();
494  int i = 0;
495 
496  while (iter != nodes.end() && i < jointDelta.rows())
497  {
498  if (targetVelocities.find((*iter)->getName()) != targetVelocities.end())
499  {
500  ARMARX_WARNING << deactivateSpam(2) << (*iter)->getName() << " is set from two joint delta calculations - overwriting first value";
501  }
502 
503  targetVelocities.insert(std::make_pair((*iter)->getName(), jointDelta(i)));
504 
505  controlModes.insert(std::make_pair((*iter)->getName(), eVelocityControl));
506  i++;
507  iter++;
508  };
509  }
510 
511 
512  kinematicUnitPrx->switchControlMode(controlModes);
513  kinematicUnitPrx->setJointVelocities(targetVelocities);
514  }
515 
516 
517 
518  void TCPControlUnit::ContinuousAngles(const Eigen::AngleAxisf& oldAngle, Eigen::AngleAxisf& newAngle, double& offset)
519  {
520  // if(oldAngle.axis().isApprox(newAngle.axis()*-1))
521  const Eigen::Vector3f& v1 = oldAngle.axis();
522  const Eigen::Vector3f& v2 = newAngle.axis();
523  const Eigen::Vector3f& v2i = newAngle.axis() * -1;
524  double angle = acos(v1.dot(v2) / (v1.norm() * v2.norm()));
525  double angleInv = acos(v1.dot(v2i) / (v1.norm() * v2i.norm()));
526  // std::cout << "angle1: " << angle << std::endl;
527  // std::cout << "angleInv: " << angleInv << std::endl;
528 
529  // Eigen::AngleAxisd result;
530  if (angle > angleInv)
531  {
532  // ARMARX_IMPORTANT_S << "inversion needed" << std::endl;
533  newAngle = Eigen::AngleAxisf(2.0 * M_PI - newAngle.angle(), newAngle.axis() * -1);
534  }
535 
536  // else newAngle = newAngle;
537 
538  if (fabs(newAngle.angle() + offset - oldAngle.angle()) > fabs(newAngle.angle() + offset - (oldAngle.angle() + M_PI * 2)))
539  {
540  offset -= M_PI * 2;
541  }
542  else if (fabs(newAngle.angle() + offset - oldAngle.angle()) > fabs((newAngle.angle() + M_PI * 2 + offset) - oldAngle.angle()))
543  {
544  offset += M_PI * 2;
545  }
546 
547  newAngle.angle() += offset;
548  }
549 
550 
551  Eigen::VectorXf TCPControlUnit::CalcJointLimitAvoidanceDeltas(VirtualRobot::RobotNodeSetPtr robotNodeSet, const Eigen::MatrixXf& jacobian, const Eigen::MatrixXf& jacobianInverse, Eigen::VectorXf desiredJointValues)
552  {
553  std::vector< VirtualRobot::RobotNodePtr > nodes = robotNodeSet->getAllRobotNodes();
554  Eigen::VectorXf actualJointValues(nodes.size());
555 
556  if (desiredJointValues.rows() == 0)
557  {
558 
559  desiredJointValues.resize(nodes.size());
560 
561  for (unsigned int i = 0; i < nodes.size(); i++)
562  {
563  VirtualRobot::RobotNodePtr node = nodes.at(i);
564  desiredJointValues(i) = (node->getJointLimitHigh() - node->getJointLimitLow()) * 0.5f + node->getJointLimitLow();
565  }
566 
567 
568  }
569 
570  // ARMARX_IMPORTANT << deactivateSpam(true, 0.5) << "desiredJointValues: " << desiredJointValues;
571  Eigen::VectorXf jointCompensationDeltas(desiredJointValues.rows());
572 
573  for (unsigned int i = 0; i < desiredJointValues.rows(); i++)
574  {
575  VirtualRobot::RobotNodePtr node = nodes.at(i);
576  actualJointValues(i) = node->getJointValue();
577  jointCompensationDeltas(i) = (node->getJointValue() - desiredJointValues(i)) / (node->getJointLimitHigh() - node->getJointLimitLow());
578  jointCompensationDeltas(i) = -pow(jointCompensationDeltas(i), 3) * pow(nodes.size() - i, 2);
579  }
580 
581  // ARMARX_IMPORTANT << deactivateSpam(true, 0.5) << "actualJointValues: " << actualJointValues;
582 
583  return CalcNullspaceJointDeltas(jointCompensationDeltas, jacobian, jacobianInverse);
584  }
585 
586  Eigen::VectorXf TCPControlUnit::CalcNullspaceJointDeltas(const Eigen::VectorXf& desiredJointDeltas, const Eigen::MatrixXf& jacobian, const Eigen::MatrixXf& jacobianInverse)
587  {
588  Eigen::MatrixXf I(jacobianInverse.rows(), jacobian.cols());
589  I.setIdentity();
590 
591  Eigen::MatrixXf nullspaceProjection = I - jacobianInverse * jacobian;
592 
593  Eigen::VectorXf delta = nullspaceProjection * desiredJointDeltas;
594  return delta;
595  }
596 
597  Eigen::VectorXf TCPControlUnit::applyMaxJointVelocity(const Eigen::VectorXf& jointVelocity, float maxJointVelocity)
598  {
599  double currentMaxJointVel = std::numeric_limits<double>::min();
600 
601  for (unsigned int i = 0; i < jointVelocity.rows(); i++)
602  {
603  currentMaxJointVel = std::max(static_cast<double>(std::abs(jointVelocity(i))), currentMaxJointVel);
604  }
605 
606  if (currentMaxJointVel > maxJointVelocity)
607  {
608  ARMARX_IMPORTANT << deactivateSpam(1) << "max joint velocity too high: " << currentMaxJointVel << " allowed: " << maxJointVelocity;
609  return jointVelocity * (maxJointVelocity / currentMaxJointVel);
610  }
611  else
612  {
613  return jointVelocity;
614  }
615 
616  }
617 
618 
620  {
621 
624  }
625 
626  EDifferentialIK::EDifferentialIK(RobotNodeSetPtr rns, RobotNodePtr coordSystem, JacobiProvider::InverseJacobiMethod invJacMethod) :
627  DifferentialIK(rns, coordSystem, invJacMethod)
628  {
629  }
630 
632  {
633  if (nRows == 0)
634  {
635  this->setNRows();
636  }
637 
638  size_t nDoF = nodes.size();
639 
640  using namespace Eigen;
641  MatrixXf Jacobian(nRows, nDoF);
642 
643  size_t index = 0;
644 
645  for (size_t i = 0; i < tcp_set.size(); i++)
646  {
647  SceneObjectPtr tcp = tcp_set[i];
648 
649  if (this->targets.find(tcp) != this->targets.end())
650  {
651  IKSolver::CartesianSelection mode = this->modes[tcp];
652  MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
653  Jacobian.block(index, 0, partJacobian.rows(), nDoF) = partJacobian;
654  }
655  else
656  {
657  VR_ERROR << "Internal error?!" << std::endl; // Error
658  }
659 
660 
661  }
662 
663  return Jacobian;
664  }
665 
667  {
668  targets.clear();
669  modes.clear();
670  tolerancePosition.clear();
671  toleranceRotation.clear();
672  parents.clear();
673  tcpWeights.clear();
674  }
675 
676  void EDifferentialIK::setRefFrame(RobotNodePtr coordSystem)
677  {
678  this->coordSystem = coordSystem;
679  }
680 
681  void EDifferentialIK::setGoal(const Matrix4f& goal, RobotNodePtr tcp, IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, VectorXf tcpWeight)
682  {
683  if (mode <= IKSolver::Z)
684  {
685  ARMARX_CHECK_EXPRESSION(tcpWeight.rows() == 1) << "The tcpWeight vector must be of size 1";
686  }
687  else if (mode <= IKSolver::Orientation)
688  {
689  ARMARX_CHECK_EXPRESSION(tcpWeight.rows() == 3) << "The tcpWeight vector must be of size 3";
690  }
691  else if (mode == IKSolver::All)
692  {
693  ARMARX_CHECK_EXPRESSION(tcpWeight.rows() == 6) << "The tcpWeight vector must be of size 6";
694  }
695 
696  tcpWeights[tcp] = tcpWeight;
697  DifferentialIK::setGoal(goal, tcp, mode, tolerancePosition, toleranceRotation);
698  }
699 
701  {
702  this->dofWeights = dofWeights;
703  }
704 
705  bool EDifferentialIK::computeSteps(float stepSize, float mininumChange, int maxNStep)
706  {
707  VectorXf jointDelta;
708  return computeSteps(jointDelta, stepSize, mininumChange, maxNStep, &DifferentialIK::computeStep);
709  }
710 
711  // void EDifferentialIK::setTCPWeights(Eigen::VectorXf tcpWeights)
712  // {
713  // this->tcpWeights = tcpWeights;
714  // }
715 
716  bool EDifferentialIK::computeSteps(VectorXf& resultJointDelta, float stepSize, float mininumChange, int maxNStep, ComputeFunction computeFunction)
717  {
718  VR_ASSERT(rns);
719  VR_ASSERT(nodes.size() == rns->getSize());
720  //std::vector<RobotNodePtr> rn = this->nodes;
721  RobotPtr robot = rns->getRobot();
722  VR_ASSERT(robot);
723  std::vector<float> jv(nodes.size(), 0.0f);
724  std::vector<float> jvBest = rns->getJointValues();
725  int step = 0;
726  checkTolerances();
727 
728  std::vector<std::pair<float, VectorXf> > jointDeltaIterations;
729  float lastDist = FLT_MAX;
730  VectorXf oldJointValues;
731  rns->getJointValues(oldJointValues);
732  VectorXf tempDOFWeights = dofWeights;
733  // VectorXf dThetaSum(nodes.size());
734  resultJointDelta.resize(nodes.size());
735  resultJointDelta.setZero();
736 
737  do
738  {
739  VectorXf dTheta = (this->*computeFunction)(stepSize);
740 
741  if (adjustDOFWeightsToJointLimits(dTheta))
742  {
743  dTheta = computeStep(stepSize);
744  }
745 
746 
747 
748  for (unsigned int i = 0; i < nodes.size(); i++)
749  {
750  ARMARX_DEBUG << VAROUT(nodes[i]->getJointValue()) << VAROUT(dTheta[i]);
751  jv[i] = (nodes[i]->getJointValue() + dTheta[i]);
752 
753  if (std::isnan(jv[i]) || std::isinf(jv[i]))
754  {
755  ARMARX_WARNING_S << "Aborting, invalid joint value (nan)" << std::endl;
756  dofWeights = tempDOFWeights;
757  return false;
758  }
759 
760  //nodes[i]->setJointValue(nodes[i]->getJointValue() + dTheta[i]);
761  }
762 
763  robot->setJointValues(rns, jv);
764 
765  VectorXf newJointValues;
766  rns->getJointValues(newJointValues);
767  resultJointDelta = newJointValues - oldJointValues;
768 
769 
770  // ARMARX_DEBUG << "joint angle deltas:\n" << dThetaSum;
771 
772  // check tolerances
773  if (checkTolerances())
774  {
775  if (verbose)
776  {
777  ARMARX_INFO << deactivateSpam(1) << "Tolerances ok, loop:" << step << std::endl;
778  }
779 
780  break;
781  }
782 
783  float d = dTheta.norm();
784  float posDist = getMeanErrorPosition();
785  float oriErr = getErrorRotation(rns->getTCP());
786 
787  if (dTheta.norm() < mininumChange)
788  {
789  // if (verbose)
790  ARMARX_INFO << deactivateSpam(1) << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << " Resulting error: pos " << posDist << " orientation: " << oriErr << std::endl;
791  break;
792  }
793 
794  if (checkImprovement && posDist > lastDist)
795  {
796  // if (verbose)
797  ARMARX_INFO << deactivateSpam(1) << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << std::endl;
798  robot->setJointValues(rns, jvBest);
799  break;
800  }
801 
802  jvBest = jv;
803  lastDist = posDist;
804  step++;
805 
806  jointDeltaIterations.push_back(std::make_pair(getWeightedError(), resultJointDelta));
807  }
808  while (step < maxNStep);
809 
810 
811  float bestJVError = std::numeric_limits<float>::max();
812 
813  for (unsigned int i = 0; i < jointDeltaIterations.size(); i++)
814  {
815  if (jointDeltaIterations.at(i).first < bestJVError)
816  {
817  bestJVError = jointDeltaIterations.at(i).first;
818  resultJointDelta = jointDeltaIterations.at(i).second;
819 
820 
821  }
822  }
823 
824  robot->setJointValues(rns, oldJointValues + resultJointDelta);
825 
826  // ARMARX_DEBUG << "best try: " << bestIndex << " with error: " << bestJVError;
827  // rns->setJointValues(oldJointValues);
828  // Matrix4f oldPose = rns->getTCP()->getGlobalPose();
829  // rns->setJointValues(oldJointValues+dThetaSum);
830  // Matrix4f newPose = rns->getTCP()->getGlobalPose();
831  // ARMARX_IMPORTANT << "tcp delta:\n" << newPose.block(0,3,3,1) - oldPose.block(0,3,3,1);
832  dofWeights = tempDOFWeights;
833 
834  if (step >= maxNStep && verbose)
835  {
836  ARMARX_INFO << deactivateSpam(1) << "IK failed, loop:" << step << std::endl;
837  ARMARX_INFO << deactivateSpam(1) << "pos error:" << getMeanErrorPosition() << std::endl;
838  ARMARX_INFO << deactivateSpam(1) << "rot error:" << getErrorRotation(rns->getTCP()) << std::endl;
839  return false;
840  }
841 
842  return true;
843  }
844 
845  VectorXf EDifferentialIK::computeStep(float stepSize)
846  {
847 
848  if (nRows == 0)
849  {
850  this->setNRows();
851  }
852 
853  size_t nDoF = nodes.size();
854 
855  MatrixXf Jacobian(nRows, nDoF);
856  VectorXf error(nRows);
857  size_t index = 0;
858 
859  for (size_t i = 0; i < tcp_set.size(); i++)
860  {
861  SceneObjectPtr tcp = tcp_set[i];
862 
863  if (this->targets.find(tcp) != this->targets.end())
864  {
865  Eigen::VectorXf delta = getDeltaToGoal(tcp);
866  //ARMARX_DEBUG << VAROUT(delta);
867  IKSolver::CartesianSelection mode = this->modes[tcp];
868  MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
869  //ARMARX_DEBUG << VAROUT(partJacobian);
870 
871  Jacobian.block(index, 0, partJacobian.rows(), nDoF) = partJacobian;
872  Vector3f position = delta.head(3);
873  position *= stepSize;
874 
875  if (mode & IKSolver::X)
876  {
877  error(index) = position(0);
878  index++;
879  }
880 
881  if (mode & IKSolver::Y)
882  {
883  error(index) = position(1);
884  index++;
885  }
886 
887  if (mode & IKSolver::Z)
888  {
889  error(index) = position(2);
890  index++;
891  }
892 
893  if (mode & IKSolver::Orientation)
894  {
895  error.segment(index, 3) = delta.tail(3) * stepSize;
896  index += 3;
897  }
898 
899  }
900  else
901  {
902  VR_ERROR << "Internal error?!" << std::endl; // Error
903  }
904 
905 
906  }
907 
908  // applyDOFWeightsToJacobian(Jacobian);
909  ARMARX_DEBUG << VAROUT(Jacobian);
910  MatrixXf pseudo = computePseudoInverseJacobianMatrix(Jacobian);
911  ARMARX_DEBUG << VAROUT(pseudo);
912  ARMARX_DEBUG << VAROUT(error);
913  return pseudo * error;
914  }
915 
916 
918  {
919  if (nRows == 0)
920  {
921  this->setNRows();
922  }
923 
924  size_t nDoF = nodes.size();
925 
926  std::map<float, MatrixXf> partJacobians;
927 
928  VectorXf thetaSum(nDoF);
929  thetaSum.setZero();
930  size_t index = 0;
931 
932  for (size_t i = 0; i < tcp_set.size(); i++)
933  {
934  SceneObjectPtr tcp = tcp_set[i];
935 
936  if (this->targets.find(tcp) != this->targets.end())
937  {
938  Eigen::VectorXf delta = getDeltaToGoal(tcp);
939  IKSolver::CartesianSelection mode = this->modes[tcp];
940  MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
941 
942  // apply tcp weights
943  // applyTCPWeights(tcp, partJacobian);
944  int tcpDOF = 0;
945 
946  if (mode <= IKSolver::Z)
947  {
948  tcpDOF = 1;
949  }
950  else if (mode <= IKSolver::Orientation)
951  {
952  tcpDOF = 3;
953  }
954  else if (mode == IKSolver::All)
955  {
956  tcpDOF = 6;
957  }
958 
959  index = 0;
960  VectorXf partError(tcpDOF);
961  Vector3f position = delta.head(3);
962  // ARMARX_DEBUG << tcp->getName() << "'s error: " << position << " weighted error: " << position*stepSize;
963  position *= stepSize;
964 
965  if (mode & IKSolver::X)
966  {
967  partError(index) = position(0);
968  index++;
969  }
970 
971  if (mode & IKSolver::Y)
972  {
973  partError(index) = position(1);
974  index++;
975  }
976 
977  if (mode & IKSolver::Z)
978  {
979  partError(index) = position(2);
980  index++;
981  }
982 
983  if (mode & IKSolver::Orientation)
984  {
985  partError.segment(index, 3) = delta.tail(3) * stepSize;
986  index += 3;
987  }
988 
989 
990  ARMARX_DEBUG << deactivateSpam(0.05) << "step size adjusted error to goal:\n" << partError;
991 
992  applyDOFWeightsToJacobian(partJacobian);
993  // ARMARX_DEBUG << "Jac:\n" << partJacobian;
994 
995 
996  MatrixXf pseudo = computePseudoInverseJacobianMatrix(partJacobian);
997 
998  Eigen::VectorXf tcpWeightVec;
999  std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it = tcpWeights.find(tcp);
1000 
1001  if (it != tcpWeights.end())
1002  {
1003  tcpWeightVec = it->second;
1004  }
1005  else
1006  {
1007  IKSolver::CartesianSelection mode = modes[tcp_set.at(i)];
1008  int size = 1;
1009 
1010  if (mode <= IKSolver::Z)
1011  {
1012  size = 1;
1013  }
1014  else if (mode <= IKSolver::Orientation)
1015  {
1016  size = 3;
1017  }
1018  else if (mode == IKSolver::All)
1019  {
1020  size = 6;
1021  }
1022 
1023  Eigen::VectorXf tmptcpWeightVec(size);
1024  tmptcpWeightVec.setOnes();
1025  tcpWeightVec = tmptcpWeightVec;
1026 
1027  }
1028 
1029 
1030  if (pseudo.cols() == tcpWeightVec.rows())
1031  {
1032 
1033  Eigen::MatrixXf weightMat(tcpWeightVec.rows(), tcpWeightVec.rows());
1034  weightMat.setIdentity();
1035  weightMat.diagonal() = tcpWeightVec;
1036  // ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "tcpWeightVec:\n" << tcpWeightVec;
1037  // ARMARX_DEBUG << /*deactivateSpam(1) << */"InvJac Before:\n" << invJacobian;
1038  pseudo = pseudo * weightMat;
1039  // ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "InvJac after:\n" << pseudo;
1040  }
1041  else
1042  {
1043  ARMARX_WARNING << deactivateSpam(3) << "Wrong dimension of tcp weights: " << tcpWeightVec.rows() << ", but should be: " << pseudo.cols();
1044  }
1045 
1046 
1047  thetaSum += pseudo * partError;
1048 
1049  }
1050  else
1051  {
1052  VR_ERROR << "Internal error?!" << std::endl; // Error
1053  }
1054 
1055 
1056  }
1057 
1058  return thetaSum;
1059  }
1060 
1061  bool EDifferentialIK::solveIK(float stepSize, float minChange, int maxSteps, bool useAlternativeOnFail)
1062  {
1063  Eigen::VectorXf jointValuesBefore;
1064  rns->getJointValues(jointValuesBefore);
1065  Eigen::VectorXf resultJointDelta;
1066  Eigen::VectorXf jointDeltaAlternative;
1067  bool result = computeSteps(resultJointDelta, stepSize, minChange, maxSteps);
1068  float error = getWeightedError();
1069 
1070  if (useAlternativeOnFail && error > 5)
1071  {
1072  result = computeSteps(jointDeltaAlternative, stepSize, minChange, maxSteps, &EDifferentialIK::computeStepIndependently);
1073  }
1074 
1075  if (getWeightedError() < error)
1076  {
1077  resultJointDelta = jointDeltaAlternative;
1078  }
1079 
1080  return result;
1081  }
1082 
1084  {
1085  if (dofWeights.rows() == Jacobian.cols())
1086  {
1087  Eigen::MatrixXf weightMat(dofWeights.rows(), dofWeights.rows());
1088  weightMat.setIdentity();
1089  weightMat.diagonal() = dofWeights;
1090  // ARMARX_DEBUG << deactivateSpam(1) << "Jac before:\n" << Jacobian;
1091  // ARMARX_DEBUG << deactivateSpam(1) << "Weights:\n" << weightMat;
1092  Jacobian = Jacobian * weightMat;
1093  // ARMARX_DEBUG << deactivateSpam(1) << "Jac after:\n" << Jacobian;
1094 
1095  }
1096  }
1097 
1098  void EDifferentialIK::applyTCPWeights(RobotNodePtr tcp, MatrixXf& partJacobian)
1099  {
1100 
1101  std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it = tcpWeights.find(tcp);
1102 
1103  if (it != tcpWeights.end())
1104  {
1105  Eigen::VectorXf& tcpWeightVec = it->second;
1106 
1107  if (partJacobian.rows() == tcpWeightVec.rows())
1108  {
1109 
1110  Eigen::MatrixXf weightMat(tcpWeightVec.rows(), tcpWeightVec.rows());
1111  weightMat.setIdentity();
1112  weightMat.diagonal() = tcpWeightVec;
1113  ARMARX_DEBUG << deactivateSpam(1) << "Jac Before: " << partJacobian;
1114  partJacobian = weightMat * partJacobian;
1115  ARMARX_DEBUG << deactivateSpam(1) << "Jac after: " << partJacobian;
1116  }
1117  else
1118  {
1119  ARMARX_WARNING << deactivateSpam(3) << "Wrong dimension of tcp weights: " << tcpWeightVec.rows() << ", but should be: " << partJacobian.rows();
1120  }
1121  }
1122  }
1123 
1124  void EDifferentialIK::applyTCPWeights(MatrixXf& invJacobian)
1125  {
1126  if (tcpWeightVec.rows() == 0)
1127  for (size_t i = 0; i < tcp_set.size(); i++)
1128  {
1129  std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it = tcpWeights.find(tcp_set.at(i));
1130 
1131  if (it != tcpWeights.end())
1132  {
1133  Eigen::VectorXf& tmptcpWeightVec = it->second;
1134  Eigen::VectorXf oldVec = tcpWeightVec;
1135  tcpWeightVec.resize(tcpWeightVec.rows() + tmptcpWeightVec.rows());
1136 
1137  if (oldVec.rows() > 0)
1138  {
1139  tcpWeightVec.head(oldVec.rows()) = oldVec;
1140  }
1141 
1142  tcpWeightVec.tail(tmptcpWeightVec.rows()) = tmptcpWeightVec;
1143  }
1144  else
1145  {
1146  IKSolver::CartesianSelection mode = modes[tcp_set.at(i)];
1147  int size = 1;
1148 
1149  if (mode <= IKSolver::Z)
1150  {
1151  size = 1;
1152  }
1153  else if (mode <= IKSolver::Orientation)
1154  {
1155  size = 3;
1156  }
1157  else if (mode == IKSolver::All)
1158  {
1159  size = 6;
1160  }
1161 
1162  Eigen::VectorXf oldVec = tcpWeightVec;
1163  tcpWeightVec.resize(tcpWeightVec.rows() + size);
1164 
1165  if (oldVec.rows() > 0)
1166  {
1167  tcpWeightVec.head(oldVec.rows()) = oldVec;
1168  }
1169 
1170  Eigen::VectorXf tmptcpWeightVec(size);
1171  tmptcpWeightVec.setOnes();
1172  tcpWeightVec.tail(size) = tmptcpWeightVec;
1173 
1174  }
1175  }
1176 
1177  if (invJacobian.cols() == tcpWeightVec.rows())
1178  {
1179 
1180  Eigen::MatrixXf weightMat(tcpWeightVec.rows(), tcpWeightVec.rows());
1181  weightMat.setIdentity();
1182  weightMat.diagonal() = tcpWeightVec;
1183  // ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "tcpWeightVec:\n" << tcpWeightVec;
1184  // ARMARX_DEBUG << /*deactivateSpam(1) << */"InvJac Before:\n" << invJacobian;
1185  invJacobian = invJacobian * weightMat;
1186  ARMARX_DEBUG << /*deactivateSpam(1) <<*/ "InvJac after:\n" << invJacobian;
1187  }
1188  else
1189  {
1190  ARMARX_WARNING << deactivateSpam(3) << "Wrong dimension of tcp weights: " << tcpWeightVec.rows() << ", but should be: " << invJacobian.cols();
1191  }
1192 
1193  }
1194 
1196  {
1197  float result = 0.0f;
1198  float positionOrientationRatio = 3.f / 180.f * M_PI;
1199 
1200  for (size_t i = 0; i < tcp_set.size(); i++)
1201  {
1202  SceneObjectPtr tcp = tcp_set[i];
1203  result += getWeightedErrorPosition(tcp) + getErrorRotation(tcp) * positionOrientationRatio;
1204  }
1205 
1206  return result;
1207  }
1208 
1210  {
1211  if (modes[tcp] == IKSolver::Orientation)
1212  {
1213  return 0.0f; // ignoring position
1214  }
1215 
1216  if (!tcp)
1217  {
1218  tcp = getDefaultTCP();
1219  }
1220 
1221  Vector3f position = targets[tcp].block(0, 3, 3, 1) - tcp->getGlobalPose().block(0, 3, 3, 1);
1222  //cout << "Error Position <" << tcp->getName() << ">: " << position.norm() << std::endl;
1223  //cout << boost::format("Error Position < %1% >: %2%") % tcp->getName() % position.norm() << std::endl;
1224  float result = 0.0f;
1225  Eigen::VectorXf tcpWeight(3);
1226 
1227  if (tcpWeights.find(tcp) != tcpWeights.end())
1228  {
1229  tcpWeight = tcpWeights.find(tcp)->second;
1230  }
1231  else
1232  {
1233  tcpWeight.setOnes();
1234  }
1235 
1236  int weightIndex = 0;
1237 
1238  if (modes[tcp] & IKSolver::X)
1239  {
1240  // ARMARX_DEBUG << "error x: " << position(0)*tcpWeight(weightIndex);
1241  result += position(0) * position(0) * tcpWeight(weightIndex++);
1242  }
1243 
1244  if (modes[tcp] & IKSolver::Y)
1245  {
1246  // ARMARX_DEBUG << "error y: " << position(1)*tcpWeight(weightIndex);
1247  result += position(1) * position(1) * tcpWeight(weightIndex++);
1248  }
1249 
1250  if (modes[tcp] & IKSolver::Z)
1251  {
1252  // ARMARX_DEBUG << "error z: " << position(2)*tcpWeight(weightIndex);
1253  result += position(2) * position(2) * tcpWeight(weightIndex++);
1254  }
1255 
1256  return sqrtf(result);
1257  }
1258 
1259  bool EDifferentialIK::adjustDOFWeightsToJointLimits(const VectorXf& plannedJointDeltas)
1260  {
1261  if (dofWeights.rows() != plannedJointDeltas.rows())
1262  {
1263  dofWeights.resize(plannedJointDeltas.rows());
1264  dofWeights.setOnes();
1265 
1266  }
1267 
1268  bool result = false;
1269 
1270  for (unsigned int i = 0; i < nodes.size(); i++)
1271  {
1272  float angle = nodes[i]->getJointValue() + plannedJointDeltas[i] * 0.1;
1273 
1274  if (angle > nodes[i]->getJointLimitHi() || angle < nodes[i]->getJointLimitLo())
1275  {
1276  ARMARX_VERBOSE << deactivateSpam(3) << nodes[i]->getName() << " joint deactivated because of joint limit";
1277  dofWeights(i) = 0;
1278  result = true;
1279  }
1280  }
1281 
1282  return result;
1283 
1284  }
1285 
1286 
1287 
1288 }
1289 
1290 
1291 
1292 void armarx::TCPControlUnit::reportControlModeChanged(const NameControlModeMap&, Ice::Long timestamp, bool, const Ice::Current&)
1293 {
1294 }
1295 
1296 void armarx::TCPControlUnit::reportJointAngles(const NameValueMap& jointAngles, Ice::Long timestamp, bool, const Ice::Current&)
1297 {
1298  std::unique_lock lock(reportMutex);
1299  FramedPoseBaseMap tcpPoses;
1300  std::string rootFrame = localReportRobot->getRootNode()->getName();
1301  auto it = jointAngles.find("timestamp");
1302  if (it == jointAngles.end())
1303  {
1304  localReportRobot->setJointValues(jointAngles);
1305  }
1306  else
1307  {
1308  NameValueMap tempMap = jointAngles;
1309  tempMap.erase("timestamp");
1310  localReportRobot->setJointValues(tempMap);
1311  }
1312  for (unsigned int i = 0; i < nodesToReport.size(); i++)
1313  {
1314  RobotNodePtr& node = nodesToReport.at(i);
1315  const std::string& tcpName = node->getName();
1316  const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
1317  tcpPoses[tcpName] = new FramedPose(currentPose, rootFrame, robotName);
1318  }
1319 
1320  listener->reportTCPPose(tcpPoses);
1321 }
1322 
1323 void armarx::TCPControlUnit::reportJointVelocities(const NameValueMap& jointVel, Ice::Long timestamp, bool, const Ice::Current&)
1324 {
1325  if ((TimeUtil::GetTime() - lastTopicReportTime).toMilliSeconds() < cycleTime)
1326  {
1327  return;
1328  }
1329 
1330  lastTopicReportTime = TimeUtil::GetTime();
1331  std::unique_lock lock(reportMutex);
1332 
1333  if (!localVelReportRobot)
1334  {
1335  localVelReportRobot = localReportRobot->clone(robotName);
1336  }
1337 
1338  // ARMARX_DEBUG << jointVel; FramedPoseBaseMap tcpPoses;
1339  FramedDirectionMap tcpTranslationVelocities;
1340  FramedDirectionMap tcpOrientationVelocities;
1341  std::string rootFrame = localReportRobot->getRootNode()->getName();
1342  NameValueMap tempJointAngles = localReportRobot->getConfig()->getRobotNodeJointValueMap();
1343  FramedPoseBaseMap tcpPoses;
1344 
1345  for (unsigned int i = 0; i < nodesToReport.size(); i++)
1346  {
1347  RobotNodePtr node = nodesToReport.at(i);
1348  const std::string& tcpName = node->getName();
1349  const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
1350  tcpPoses[tcpName] = new FramedPose(currentPose, rootFrame, robotName);
1351 
1352  }
1353 
1354  double tDelta = 0.001;
1355 
1356  for (NameValueMap::iterator it = tempJointAngles.begin(); it != tempJointAngles.end(); it++)
1357  {
1358  NameValueMap::const_iterator itSrc = jointVel.find(it->first);
1359  if (itSrc != jointVel.end())
1360  {
1361  if (itSrc->first == "timestamp")
1362  {
1363  continue;
1364  }
1365  it->second += itSrc->second * tDelta;
1366  }
1367  }
1368 
1369  localVelReportRobot->setJointValues(tempJointAngles);
1370 
1371  for (unsigned int i = 0; i < nodesToReport.size(); i++)
1372  {
1373  RobotNodePtr node = localVelReportRobot->getRobotNode(nodesToReport.at(i)->getName());
1374  const std::string& tcpName = node->getName();
1375  const Eigen::Matrix4f& currentPose = node->getPoseInRootFrame();
1376 
1377 
1378  FramedPosePtr lastPose = FramedPosePtr::dynamicCast(tcpPoses[tcpName]);
1379 
1380  tcpTranslationVelocities[tcpName] = new FramedDirection((currentPose.block(0, 3, 3, 1) - lastPose->toEigen().block(0, 3, 3, 1)) / tDelta, rootFrame, localReportRobot->getName());
1381 
1382  const Eigen::Matrix4f mat = currentPose * lastPose->toEigen().inverse();
1383  // const Eigen::Matrix3f rot = currentPose.block(0,0,3,3) * lastPose->toEigen().block(0,0,3,3).inverse();
1384  Eigen::Vector3f rpy;
1385  VirtualRobot::MathTools::eigen4f2rpy(mat, rpy);
1386  // Eigen::AngleAxisf orient(rot.block<3,3>(0,0));
1387 
1388  tcpOrientationVelocities[tcpName] = new FramedDirection(rpy / tDelta, rootFrame, robotName);
1389 
1390 
1391  }
1392 
1393  listener->reportTCPVelocities(tcpTranslationVelocities, tcpOrientationVelocities);
1394 }
1395 
1396 void armarx::TCPControlUnit::reportJointTorques(const NameValueMap&, Ice::Long timestamp, bool, const Ice::Current&)
1397 {
1398 }
1399 
1400 void armarx::TCPControlUnit::reportJointAccelerations(const armarx::NameValueMap& jointAccelerations, Ice::Long timestamp, bool aValueChanged, const Ice::Current& c)
1401 {
1402 
1403 }
1404 
1405 void armarx::TCPControlUnit::reportJointCurrents(const NameValueMap&, Ice::Long timestamp, bool, const Ice::Current&)
1406 {
1407 }
1408 
1409 void armarx::TCPControlUnit::reportJointMotorTemperatures(const NameValueMap&, Ice::Long timestamp, bool, const Ice::Current&)
1410 {
1411 }
1412 
1413 void armarx::TCPControlUnit::reportJointStatuses(const NameStatusMap&, Ice::Long timestamp, bool, const Ice::Current&)
1414 {
1415 }
LinkedPose.h
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
armarx::TCPControlUnitPropertyDefinitions
Definition: TCPControlUnit.h:42
Eigen
Definition: Elements.h:36
armarx::TCPControlUnit::createPropertyDefinitions
PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: TCPControlUnit.cpp:619
armarx::TCPControlUnit::onInitComponent
void onInitComponent() override
Pure virtual hook for the subclass.
Definition: TCPControlUnit.cpp:55
armarx::EDifferentialIK::computeStep
Eigen::VectorXf computeStep(float stepSize) override
Definition: TCPControlUnit.cpp:845
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
GfxTL::Orientation
ScalarT Orientation(const VectorXD< 2, ScalarT > &p1, const VectorXD< 2, ScalarT > &p2, const VectorXD< 2, ScalarT > &c)
Definition: Orientation.h:9
armarx::TCPControlUnit::onConnectComponent
void onConnectComponent() override
Pure virtual hook for the subclass.
Definition: TCPControlUnit.cpp:69
index
uint8_t index
Definition: EtherCATFrame.h:59
armarx::RemoteRobot::synchronizeLocalClone
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
Definition: RemoteRobot.cpp:448
armarx::EDifferentialIK::clearGoals
void clearGoals()
Definition: TCPControlUnit.cpp:666
armarx::VariantType::FramedPose
const VariantTypeId FramedPose
Definition: FramedPose.h:37
VirtualRobot
Definition: FramedPose.h:43
armarx::EDifferentialIK::computeSteps
bool computeSteps(float stepSize=1.f, float mininumChange=0.01f, int maxNStep=50) override
Definition: TCPControlUnit.cpp:705
armarx::EDifferentialIK::setDOFWeights
void setDOFWeights(Eigen::VectorXf dofWeights)
Definition: TCPControlUnit.cpp:700
armarx::TCPControlUnit::getExecutionState
UnitExecutionState getExecutionState(const Ice::Current &c=Ice::emptyCurrent) override
Definition: TCPControlUnit.cpp:234
armarx::TCPControlUnit::init
void init(const Ice::Current &c=Ice::emptyCurrent) override
Does not do anything at the moment.
Definition: TCPControlUnit.cpp:222
armarx::TCPControlUnit::start
void start(const Ice::Current &c=Ice::emptyCurrent) override
Does not do anything at the moment.
Definition: TCPControlUnit.cpp:226
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:62
armarx::TCPControlUnit::CalcNullspaceJointDeltas
static Eigen::VectorXf CalcNullspaceJointDeltas(const Eigen::VectorXf &desiredJointDeltas, const Eigen::MatrixXf &jacobian, const Eigen::MatrixXf &jacobianInverse)
Definition: TCPControlUnit.cpp:586
armarx::EDifferentialIK::applyTCPWeights
void applyTCPWeights(VirtualRobot::RobotNodePtr tcp, Eigen::MatrixXf &partJacobian)
armarx::ManagedIceObject::getState
int getState() const
Retrieve current state of the ManagedIceObject.
Definition: ManagedIceObject.cpp:725
armarx::TCPControlUnit::isRequested
bool isRequested(const Ice::Current &c=Ice::emptyCurrent) override
Definition: TCPControlUnit.cpp:294
TCPControlUnit.h
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::navigation::platform_controller::platform_global_trajectory::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformGlobalTrajectoryController.h:93
armarx::TCPControlUnit::request
void request(const Ice::Current &c=Ice::emptyCurrent) override
Triggers the calculation loop for using cartesian velocity.
Definition: TCPControlUnit.cpp:254
armarx::TCPControlUnit::reportJointCurrents
void reportJointCurrents(const NameValueMap &, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1405
armarx::TCPControlUnit::reportJointVelocities
void reportJointVelocities(const NameValueMap &jointVel, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1323
armarx::TCPControlUnit::setCycleTime
void setCycleTime(Ice::Int milliseconds, const Ice::Current &c=Ice::emptyCurrent) override
Sets the cycle time with which the joint velocities are recalculated.
Definition: TCPControlUnit.cpp:169
armarx::TCPControlUnit::reportJointStatuses
void reportJointStatuses(const NameStatusMap &, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1413
IceInternal::Handle< FramedPose >
armarx::EDifferentialIK::setRefFrame
void setRefFrame(VirtualRobot::RobotNodePtr coordSystem)
Definition: TCPControlUnit.cpp:676
armarx::FramedDirection::ChangeFrame
static FramedDirectionPtr ChangeFrame(const VirtualRobot::RobotPtr &robot, const FramedDirection &framedVec, const std::string &newFrame)
Definition: FramedPose.cpp:86
armarx::TCPControlUnit::stop
void stop(const Ice::Current &c=Ice::emptyCurrent) override
Does not do anything at the moment.
Definition: TCPControlUnit.cpp:230
armarx::FramedPoseBaseMap
::std::map< ::std::string, ::armarx::FramedPoseBasePtr > FramedPoseBaseMap
Definition: RobotStateObserver.h:55
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
armarx::abs
std::vector< T > abs(const std::vector< T > &v)
Definition: VectorHelpers.h:253
M_PI
#define M_PI
Definition: MathTools.h:17
armarx::EDifferentialIK::applyDOFWeightsToJacobian
void applyDOFWeightsToJacobian(Eigen::MatrixXf &Jacobian)
Definition: TCPControlUnit.cpp:1083
armarx::EDifferentialIK::setGoal
void setGoal(const Eigen::Matrix4f &goal, VirtualRobot::RobotNodePtr tcp, VirtualRobot::IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, Eigen::VectorXf tcpWeight)
Definition: TCPControlUnit.cpp:681
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::EDifferentialIK::adjustDOFWeightsToJointLimits
bool adjustDOFWeightsToJointLimits(const Eigen::VectorXf &plannedJointDeltas)
Definition: TCPControlUnit.cpp:1259
armarx::EDifferentialIK
Definition: TCPControlUnit.h:238
armarx::NJointTaskSpaceDMPControllerMode::CartesianSelection
CartesianSelection
Definition: ControllerInterface.ice:34
armarx::EDifferentialIK::dofWeights
Eigen::VectorXf dofWeights
Definition: TCPControlUnit.h:276
armarx::EDifferentialIK::tcpWeights
std::map< VirtualRobot::SceneObjectPtr, Eigen::VectorXf > tcpWeights
Definition: TCPControlUnit.h:277
armarx::VariantType::Long
const VariantTypeId Long
Definition: Variant.h:917
armarx::TCPControlUnit::CalcJointLimitAvoidanceDeltas
static Eigen::VectorXf CalcJointLimitAvoidanceDeltas(VirtualRobot::RobotNodeSetPtr robotNodeSet, const Eigen::MatrixXf &jacobian, const Eigen::MatrixXf &jacobianInverse, Eigen::VectorXf desiredJointValues=Eigen::VectorXf())
Definition: TCPControlUnit.cpp:551
max
T max(T t1, T t2)
Definition: gdiam.h:48
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
armarx::EDifferentialIK::solveIK
bool solveIK(float stepSize=1, float minChange=0.01f, int maxSteps=50, bool useAlternativeOnFail=false)
Definition: TCPControlUnit.cpp:1061
armarx::TCPControlUnit::reportJointTorques
void reportJointTorques(const NameValueMap &, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1396
ARMARX_WARNING_S
#define ARMARX_WARNING_S
Definition: Logging.h:206
armarx::EDifferentialIK::computeStepIndependently
Eigen::VectorXf computeStepIndependently(float stepSize)
Definition: TCPControlUnit.cpp:917
armarx::TCPControlUnit::calcAndSetVelocities
void calcAndSetVelocities()
Definition: TCPControlUnit.cpp:340
armarx::EDifferentialIK::ComputeFunction
Eigen::VectorXf(EDifferentialIK::* ComputeFunction)(float)
Definition: TCPControlUnit.h:241
armarx::TCPControlUnit::onExitComponent
void onExitComponent() override
Hook for subclass.
Definition: TCPControlUnit.cpp:163
armarx::EDifferentialIK::getWeightedErrorPosition
float getWeightedErrorPosition(VirtualRobot::SceneObjectPtr tcp)
Definition: TCPControlUnit.cpp:1209
armarx::TimeUtil::GetTime
static IceUtil::Time GetTime(TimeMode timeMode=TimeMode::VirtualTime)
Get the current time.
Definition: TimeUtil.cpp:42
ExpressionException.h
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::TCPControlUnit::reportJointAngles
void reportJointAngles(const NameValueMap &jointAngles, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1296
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:600
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
TimeUtil.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::VariantType::FramedDirection
const VariantTypeId FramedDirection
Definition: FramedPose.h:38
armarx::RemoteRobot::createLocalClone
VirtualRobot::RobotPtr createLocalClone()
Clones the structure of this remote robot to a local instance.
Definition: RemoteRobot.cpp:328
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:182
armarx::ManagedIceObject::offeringTopic
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
Definition: ManagedIceObject.cpp:290
set
set(LIBS ArmarXCoreInterfaces ${CMAKE_THREAD_LIBS_INIT} ${dl_LIBRARIES} ${rt_LIBRARIES} ${QT_LIBRARIES} ${Boost_LIBRARIES} BoostAssertionHandler ArmarXCPPUtility SimoxUtility) set(LIB_FILES ArmarXManager.cpp ArmarXMultipleObjectsScheduler.cpp ArmarXObjectScheduler.cpp ManagedIceObject.cpp ManagedIceObjectPlugin.cpp Component.cpp ComponentPlugin.cpp IceGridAdmin.cpp ArmarXObjectObserver.cpp IceManager.cpp PackagePath.cpp RemoteReferenceCount.cpp logging/LoggingUtil.cpp logging/Logging.cpp logging/LogSender.cpp logging/ArmarXLogBuf.cpp system/ArmarXDataPath.cpp system/DynamicLibrary.cpp system/ProcessWatcher.cpp system/FactoryCollectionBase.cpp system/cmake/CMakePackageFinder.cpp system/cmake/CMakePackageFinderCache.cpp system/cmake/ArmarXPackageToolInterface.cpp system/RemoteObjectNode.cpp services/sharedmemory/HardwareId.cpp services/tasks/RunningTask.cpp services/tasks/ThreadList.cpp services/tasks/ThreadPool.cpp services/profiler/Profiler.cpp services/profiler/FileLoggingStrategy.cpp services/profiler/IceLoggingStrategy.cpp application/Application.cpp application/ApplicationOptions.cpp application/ApplicationProcessFacet.cpp application/ApplicationNetworkStats.cpp application/properties/PropertyUser.cpp application/properties/Property.cpp application/properties/PropertyDefinition.cpp application/properties/PropertyDefinitionContainer.cpp application/properties/PropertyDefinitionHelpFormatter.cpp application/properties/PropertyDefinitionConfigFormatter.cpp application/properties/PropertyDefinitionBriefHelpFormatter.cpp application/properties/PropertyDefinitionXmlFormatter.cpp application/properties/PropertyDefinitionDoxygenFormatter.cpp application/properties/PropertyDefinitionDoxygenComponentPagesFormatter.cpp application/properties/PropertyDefinitionContainerBriefHelpFormatter.cpp application/properties/IceProperties.cpp exceptions/Exception.cpp exceptions/local/UnexpectedEnumValueException.cpp util/FileSystemPathBuilder.cpp util/StringHelpers.cpp util/IceReportSkipper.cpp util/Throttler.cpp util/distributed/AMDCallbackCollection.cpp util/distributed/RemoteHandle/ClientSideRemoteHandleControlBlock.cpp util/distributed/RemoteHandle/RemoteHandle.cpp util/distributed/RemoteHandle/RemoteHandleControlBlock.cpp time/ice_conversions.cpp time/json_conversions.cpp time/CallbackWaitLock.cpp time/Clock.cpp time/ClockType.cpp time/ClockTypeNames.cpp time/CycleUtil.cpp time/DateTime.cpp time/Duration.cpp time/Frequency.cpp time/LocalTimeServer.cpp time/Metronome.cpp time/ScopedStopWatch.cpp time/StopWatch.cpp time/Timer.cpp time/TimeKeeper.cpp time/TimeUtil.cpp csv/CsvWriter.cpp csv/CsvReader.cpp eigen/conversions.cpp eigen/ice_conversions.cpp) set(LIB_HEADERS ArmarXManager.h ArmarXDummyManager.h ArmarXMultipleObjectsScheduler.h ArmarXObjectObserver.h ArmarXObjectScheduler.h ArmarXFwd.h Component.h ComponentPlugin.h ComponentFactories.h CoreObjectFactories.h IceGridAdmin.h IceManager.h IceManagerImpl.h json_conversions.h ManagedIceObject.h ManagedIceObjectPlugin.h ManagedIceObjectImpl.h ManagedIceObjectDependency.h ManagedIceObjectRegistryInterface.h PackagePath.h RemoteReferenceCount.h system/ImportExport.h system/ImportExportComponent.h system/AbstractFactoryMethod.h system/FactoryCollectionBase.h system/Synchronization.h system/ArmarXDataPath.h system/DynamicLibrary.h system/ProcessWatcher.h system/ConditionSynchronization.h system/cmake/CMakePackageFinder.h system/cmake/CMakePackageFinderCache.h system/cmake/FindPackageX.cmake system/cmake/ArmarXPackageToolInterface.h system/RemoteObjectNode.h logging/LoggingUtil.h logging/LogSender.h logging/Logging.h logging/ArmarXLogBuf.h logging/SpamFilterData.h services/tasks/RunningTask.h services/tasks/PeriodicTask.h services/tasks/ThreadList.h services/tasks/TaskUtil.h services/tasks/ThreadPool.h services/sharedmemory/SharedMemoryProvider.h services/sharedmemory/SharedMemoryConsumer.h services/sharedmemory/IceSharedMemoryProvider.h services/sharedmemory/IceSharedMemoryConsumer.h services/sharedmemory/HardwareIdentifierProvider.h services/sharedmemory/HardwareId.h services/sharedmemory/exceptions/SharedMemoryExceptions.h services/profiler/Profiler.h services/profiler/LoggingStrategy.h services/profiler/FileLoggingStrategy.h services/profiler/IceLoggingStrategy.h application/Application.h application/ApplicationOptions.h application/ApplicationProcessFacet.h application/ApplicationNetworkStats.h application/properties/forward_declarations.h application/properties/Properties.h application/properties/Property.h application/properties/PluginEigen.h application/properties/PluginEnumNames.h application/properties/PluginCfgStruct.h application/properties/PluginAll.h application/properties/PropertyUser.h application/properties/PropertyDefinition.h application/properties/PropertyDefinition.hpp application/properties/PropertyDefinitionInterface.h application/properties/PropertyDefinitionContainer.h application/properties/PropertyDefinitionFormatter.h application/properties/PropertyDefinitionContainerFormatter.h application/properties/PropertyDefinitionConfigFormatter.h application/properties/PropertyDefinitionHelpFormatter.h application/properties/PropertyDefinitionBriefHelpFormatter.h application/properties/PropertyDefinitionXmlFormatter.h application/properties/PropertyDefinitionDoxygenFormatter.h application/properties/PropertyDefinitionDoxygenComponentPagesFormatter.h application/properties/PropertyDefinitionContainerBriefHelpFormatter.h application/properties/ProxyPropertyDefinition.h application/properties/IceProperties.h exceptions/Exception.h exceptions/LocalException.h exceptions/local/DynamicLibraryException.h exceptions/local/ExpressionException.h exceptions/local/FileIOException.h exceptions/local/InvalidPropertyValueException.h exceptions/local/MissingRequiredPropertyException.h exceptions/local/PropertyInheritanceCycleException.h exceptions/local/ProxyNotInitializedException.h exceptions/local/UnexpectedEnumValueException.h exceptions/local/UnmappedValueException.h exceptions/local/ValueRangeExceededException.h exceptions/user/NotImplementedYetException.h rapidxml/rapidxml.hpp rapidxml/rapidxml_print.hpp rapidxml/rapidxml_iterators.hpp rapidxml/rapidxml_utils.hpp rapidxml/wrapper/RapidXmlReader.h rapidxml/wrapper/RapidXmlWriter.h rapidxml/wrapper/DefaultRapidXmlReader.h rapidxml/wrapper/MultiNodeRapidXMLReader.h util/IceBlobToObject.h util/ObjectToIceBlob.h util/FileSystemPathBuilder.h util/FiniteStateMachine.h util/StringHelpers.h util/StringHelperTemplates.h util/algorithm.h util/OnScopeExit.h util/Predicates.h util/Preprocessor.h util/PropagateConst.h util/Registrar.h util/TemplateMetaProgramming.h util/TripleBuffer.h util/IceReportSkipper.h util/Throttler.h util/distributed/AMDCallbackCollection.h util/distributed/RemoteHandle/ClientSideRemoteHandleControlBlock.h util/distributed/RemoteHandle/RemoteHandle.h util/distributed/RemoteHandle/RemoteHandleControlBlock.h util/SimpleStatemachine.h time.h time_minimal.h time/forward_declarations.h time/ice_conversions.h time/json_conversions.h time/CallbackWaitLock.h time/Clock.h time/ClockType.h time/ClockTypeNames.h time/CycleUtil.h time/DateTime.h time/Duration.h time/Frequency.h time/LocalTimeServer.h time/Metronome.h time/ScopedStopWatch.h time/StopWatch.h time/Timer.h time/TimeUtil.h time/TimeKeeper.h csv/CsvWriter.h csv/CsvReader.h eigen/conversions.h eigen/ice_conversions.h ice_conversions.h ice_conversions/ice_conversions_boost_templates.h ice_conversions/ice_conversions_templates.h ice_conversions/ice_conversions_templates.tpp $
Definition: CMakeLists.txt:12
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::TCPControlUnit::release
void release(const Ice::Current &c=Ice::emptyCurrent) override
Releases and stops the recalculation and updating of joint velocities.
Definition: TCPControlUnit.cpp:276
armarx::EDifferentialIK::getWeightedError
float getWeightedError()
Definition: TCPControlUnit.cpp:1195
armarx::TCPControlUnit::reportJointMotorTemperatures
void reportJointMotorTemperatures(const NameValueMap &, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1409
scene3D::SceneObjectPtr
boost::intrusive_ptr< SceneObject > SceneObjectPtr
Definition: PointerDefinitions.h:40
armarx::VariantType::Int
const VariantTypeId Int
Definition: Variant.h:916
angle
double angle(const Point &a, const Point &b, const Point &c)
Definition: point.hpp:100
armarx::TCPControlUnit::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: TCPControlUnit.cpp:145
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::EDifferentialIK::tcpWeightVec
Eigen::VectorXf tcpWeightVec
Definition: TCPControlUnit.h:278
armarx::ManagedIceObject::getName
std::string getName() const
Retrieve name of object.
Definition: ManagedIceObject.cpp:107
armarx::EDifferentialIK::calcFullJacobian
Eigen::MatrixXf calcFullJacobian()
Definition: TCPControlUnit.cpp:631
armarx::PeriodicTask
Definition: ArmarXManager.h:70
armarx::navigation::core::Position
Eigen::Vector3f Position
Definition: basic_types.h:36
min
T min(T t1, T t2)
Definition: gdiam.h:42
armarx::EDifferentialIK::EDifferentialIK
EDifferentialIK(VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr coordSystem=VirtualRobot::RobotNodePtr(), VirtualRobot::JacobiProvider::InverseJacobiMethod invJacMethod=eSVD)
Definition: TCPControlUnit.cpp:626
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:34
armarx::TCPControlUnit::reportJointAccelerations
void reportJointAccelerations(const NameValueMap &jointAccelerations, Ice::Long timestamp, bool aValueChanged, const Ice::Current &c) override
Definition: TCPControlUnit.cpp:1400
ArmarXDataPath.h
armarx::TCPControlUnit::reportControlModeChanged
void reportControlModeChanged(const NameControlModeMap &, Ice::Long timestamp, bool, const Ice::Current &) override
Definition: TCPControlUnit.cpp:1292
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
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::TCPControlUnit::setTCPVelocity
void setTCPVelocity(const std::string &nodeSetName, const std::string &tcpName, const ::armarx::FramedDirectionBasePtr &translationVelocity, const ::armarx::FramedDirectionBasePtr &orientationVelocityRPY, const Ice::Current &c=Ice::emptyCurrent) override
Sets the cartesian velocity of a node in a nodeset for translation and/or orientation.
Definition: TCPControlUnit.cpp:180
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::split
std::vector< std::string > split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
Definition: StringHelpers.cpp:36