GraspTrajectory.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
5  * Karlsruhe Institute of Technology (KIT), all rights reserved.
6  *
7  * ArmarX is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License version 2 as
9  * published by the Free Software Foundation.
10  *
11  * ArmarX is distributed in the hope that it will be useful, but
12  * WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with this program. If not, see <http://www.gnu.org/licenses/>.
18  *
19  * @author Simon Ottenhaus (simon dot ottenhaus at kit dot edu)
20  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21  * GNU General Public License
22  */
23 
24 #include "GraspTrajectory.h"
25 
26 #include <filesystem>
27 #include <fstream>
28 #include <memory>
29 #include <optional>
30 
31 #include <SimoxUtility/json/eigen_conversion.h>
32 #include <SimoxUtility/json/json.hpp>
33 #include <VirtualRobot/math/Helpers.h>
34 
42 
45 
46 #include <RobotAPI/interface/units/GraspCandidateProviderInterface.h>
48 
49 
50 namespace armarx
51 {
52 
53  Eigen::VectorXf
55  {
57  Eigen::VectorXf vector(map.size());
59  map.begin(), map.end(), vector.data(), [](const auto& item) { return item.second; });
60  return vector;
61  }
62 
63  void
64  GraspTrajectory::writeToFile(const std::string& filename)
65  {
67  RapidXmlWriter writer;
68  RapidXmlWriterNode root = writer.createRootNode("GraspTrajectory");
69  for (const KeypointPtr& keypoint : keypoints)
70  {
71  SimpleJsonLoggerEntry e;
72  e.Add("dt", keypoint->dt);
73  e.AddAsArr("Pose", keypoint->tcpTarget);
74  JsonObjectPtr const obj = std::make_shared<JsonObject>();
75  for (const auto& [name, value] : keypoint->handJointsTarget)
76  {
77  obj->add(name, JsonValue::Create(value));
78  }
79  e.obj->add("HandValues", obj);
80  root.append_string_node("Keypoint", e.obj->toJsonString(0, "", true));
81  }
82  writer.saveToFile(filename, true);
83  }
84 
87  {
89  RapidXmlReaderNode const root = reader->getRoot();
90 
91  GraspTrajectoryPtr traj;
92  for (const RapidXmlReaderNode& kpNode : root.nodes("Keypoint"))
93  {
94  StructuralJsonParser p(kpNode.value());
95  p.parse();
96  JPathNavigator nav(p.parsedJson);
97  float dt = nav.selectSingleNode("dt").asFloat();
98 
99  Eigen::Matrix4f pose;
100  std::vector<JPathNavigator> rows = nav.select("Pose/*");
101  for (int i = 0; i < 4; i++)
102  {
103  std::vector<JPathNavigator> cells = rows.at(i).select("*");
104  for (int j = 0; j < 4; j++)
105  {
106  pose(i, j) = cells.at(j).asFloat();
107  }
108  }
109 
110  armarx::NameValueMap handValues;
111  std::vector<JPathNavigator> cells = nav.select("HandValues/*");
112  for (const auto& cell : cells)
113  {
114  handValues[cell.getKey()] = cell.asFloat();
115  }
116 
117  // does not work at the moment
118  const auto shapeNode = nav.selectSingleNode("shape");
119  // ARMARX_IMPORTANT << VAROUT(shapeNode.isValid());
120 
121  std::optional<std::string> shape;
122  if (shapeNode.isString())
123  {
124  shape = nav.selectSingleNode("shape").asString();
125  // ARMARX_IMPORTANT << "shape: " << shape.value();
126  }
127 
128 
129  if (!traj)
130  {
131  traj = std::make_shared<GraspTrajectory>(pose, handValues, shape);
132  }
133  else
134  {
135  traj->addKeypoint(pose, handValues, dt, shape);
136  }
137  }
138  return traj;
139  }
140 
142  GraspTrajectory::ReadFromFile(const std::string& filename)
143  {
144  ARMARX_TRACE;
145  const auto ext = std::filesystem::path(filename).extension();
146  if (ext == ".xml")
147  {
149  }
150  if (ext == ".json")
151  {
152  return ReadFromJSON(filename);
153  }
154 
155  ARMARX_WARNING << "Unknown extension `" << ext << "`!";
156  return nullptr;
157  }
158 
159  // NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(GraspTrajectory::Keypoint,tcpTarget,handJointsTarget,shape,dt );
160 
161 
162  inline void
163  from_json(const nlohmann::json& j, GraspTrajectoryKeypoint& kp)
164  {
165  ARMARX_TRACE;
166  std::optional<std::string> shape;
167 
168  if (j.contains("shape"))
169  {
170  if (not j.at("shape").is_null())
171  {
172  shape = j.at("shape");
173  }
174  }
175 
176  ARMARX_TRACE;
177  std::optional<std::map<std::string, float>> targetHandValues;
178 
179  if (j.contains("fingerValues"))
180  {
181  if (not j.at("fingerValues").is_null())
182  {
183  targetHandValues = j.at("fingerValues");
184  }
185  }
186 
187  // VERY hacky!
188  const Eigen::Matrix<float, 4, 4, Eigen::RowMajor> aronTf = j.at("pose");
189  const Eigen::Matrix4f tf = aronTf.transpose();
190 
191  ARMARX_IMPORTANT << tf;
192 
193  ARMARX_TRACE;
195  tf, targetHandValues.value_or(std::map<std::string, float>{}), shape);
196  }
197 
200  {
201  ARMARX_CHECK(std::filesystem::exists(filename));
202  std::ifstream ifs(filename);
203 
204  const nlohmann::json j = nlohmann::json::parse(ifs);
205 
206  std::vector<GraspTrajectoryKeypoint> traj;
207  traj = j.at("keypoints");
208 
209  const armarx::Duration duration =
210  armarx::Duration::MicroSeconds(j.at("duration").at("microSeconds").get<std::int64_t>());
211 
212  // at the moment, we assume that all keypoints are sampled equidistant
213 
215  const float dtSeconds = duration.toSecondsDouble() / (traj.size() - 1);
216 
217  for (auto& kp : traj)
218  {
219  kp.dt = dtSeconds;
220  }
221 
222  const std::string frame = j.at("frame").at("frame");
223 
224  auto graspTrajectory = std::make_shared<GraspTrajectory>(traj);
225  graspTrajectory->setFrame(frame);
226 
227  return graspTrajectory;
228  }
229 
231  GraspTrajectory::ReadFromString(const std::string& xml)
232  {
233  ARMARX_TRACE;
235  }
236 
238  const armarx::NameValueMap& handJointsStart,
239  const std::optional<std::string>& shape)
240  {
241  ARMARX_TRACE;
242  KeypointPtr keypoint(new Keypoint(tcpStart, handJointsStart, shape));
243  keypointMap[0] = keypoints.size();
244  keypoints.push_back(keypoint);
245  }
246 
247  GraspTrajectory::GraspTrajectory(const std::vector<Keypoint>& keypointz)
248  {
249  if (keypointz.empty())
250  {
251  return;
252  }
253 
254  // insert first keypoint
255  keypointMap[0] = keypoints.size();
256  keypoints.push_back(std::make_shared<Keypoint>(keypointz.front()));
257 
258  // insert remaining keypoints
259  for (std::size_t i = 1; i < keypointz.size(); i++)
260  {
261  const auto& kp = keypointz.at(i);
262  addKeypoint(kp.tcpTarget, kp.handJointsTarget, kp.dt, kp.shape);
263  }
264  }
265 
266  void
268  const armarx::NameValueMap& handJointsTarget,
269  float dt,
270  const std::optional<std::string>& shape)
271  {
272  ARMARX_TRACE;
273  KeypointPtr prev = lastKeypoint();
274  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape));
275  keypoint->updateVelocities(prev, dt);
276  float t = getDuration() + dt;
277  keypointMap[t] = keypoints.size();
278  keypoints.push_back(keypoint);
279  }
280 
281  size_t
283  {
284  ARMARX_TRACE;
285  return keypoints.size();
286  }
287 
288  const std::vector<GraspTrajectory::KeypointPtr>&
290  {
291  return keypoints;
292  }
293 
294  void
296  const Eigen::Matrix4f& tcpTarget,
297  const armarx::NameValueMap& handJointsTarget,
298  float dt,
299  const std::optional<std::string>& shape)
300  {
301  ARMARX_TRACE;
302  if (index <= 0 || index > keypoints.size())
303  {
304  throw LocalException("Index out of range" + std::to_string(index));
305  }
306  KeypointPtr prev = keypoints.at(index - 1);
307  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape));
308  keypoint->updateVelocities(prev, dt);
309  if (index < keypoints.size())
310  {
311  KeypointPtr next = keypoints.at(index);
312  next->updateVelocities(keypoint, next->dt);
313  }
314  keypoints.insert(keypoints.begin() + index, keypoint);
315  updateKeypointMap();
316  }
317 
318  void
320  {
321  ARMARX_TRACE;
322  if (index <= 0 || index >= keypoints.size())
323  {
324  throw LocalException("Index out of range" + std::to_string(index));
325  }
326  keypoints.erase(keypoints.begin() + index);
327  if (index < keypoints.size())
328  {
329  ARMARX_TRACE;
330  KeypointPtr prev = keypoints.at(index - 1);
331  KeypointPtr next = keypoints.at(index);
332  next->updateVelocities(prev, next->dt);
333  }
334  updateKeypointMap();
335  }
336 
337  void
339  const Eigen::Matrix4f& tcpTarget,
340  const armarx::NameValueMap& handJointsTarget,
341  float dt,
342  const std::optional<std::string>& shape)
343  {
344  ARMARX_TRACE;
345  if (index <= 0 || index >= keypoints.size())
346  {
347  throw LocalException("Index out of range" + std::to_string(index));
348  }
349  KeypointPtr prev = keypoints.at(index - 1);
350  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape));
351  keypoint->updateVelocities(prev, dt);
352  keypoints.at(index) = keypoint;
353  updateKeypointMap();
354  }
355 
356  void
358  {
359  ARMARX_TRACE;
360  if (index <= 0 || index >= keypoints.size())
361  {
362  throw LocalException("Index out of range" + std::to_string(index));
363  }
364  KeypointPtr prev = keypoints.at(index - 1);
365  KeypointPtr& keypoint = keypoints.at(index);
366  keypoint->updateVelocities(prev, dt);
367  updateKeypointMap();
368  }
369 
372  {
373  ARMARX_TRACE;
374  return keypoints.at(keypoints.size() - 1);
375  }
376 
379  {
380  ARMARX_TRACE;
381  return keypoints.at(i);
382  }
383 
386  {
387  ARMARX_TRACE;
388  return getKeypoint(0)->getTargetPose();
389  }
390 
391  void
392  GraspTrajectory::getIndex(float t, int& i1, int& i2, float& f) const
393  {
394  ARMARX_TRACE;
395  if (t <= 0)
396  {
397  i1 = 0;
398  i2 = 0;
399  f = 0;
400  return;
401  }
402  std::map<float, size_t>::const_iterator it, prev;
403  it = keypointMap.upper_bound(t);
404  if (it == keypointMap.end())
405  {
406  i1 = keypoints.size() - 1;
407  i2 = keypoints.size() - 1;
408  f = 0;
409  return;
410  }
411  prev = std::prev(it);
412  i1 = prev->second;
413  i2 = it->second;
414  f = ::math::Helpers::ILerp(prev->first, it->first, t);
415  }
416 
417  Eigen::Vector3f
419  {
420  ARMARX_TRACE;
421  int i1, i2;
422  float f;
423  getIndex(t, i1, i2, f);
424  return ::math::Helpers::Lerp(
425  getKeypoint(i1)->getTargetPosition(), getKeypoint(i2)->getTargetPosition(), f);
426  }
427 
430  {
431  ARMARX_TRACE;
432  int i1, i2;
433  float f;
434  getIndex(t, i1, i2, f);
435  Eigen::Vector3f oriVel = GetOrientationDerivative(t);
436  if (oriVel.squaredNorm() == 0)
437  {
438  return getKeypoint(i1)->getTargetOrientation();
439  }
440  Eigen::AngleAxisf aa(oriVel.norm(), oriVel.normalized());
441  aa.angle() = aa.angle() * f * getKeypoint(i2)->dt;
442  return aa.toRotationMatrix() * getKeypoint(i1)->getTargetOrientation();
443  }
444 
447  {
448  ARMARX_TRACE;
449  return ::math::Helpers::CreatePose(GetPosition(t), GetOrientation(t));
450  }
451 
452  std::vector<Eigen::Matrix4f>
454  {
455  ARMARX_TRACE;
456  std::vector<Eigen::Matrix4f> res;
457  for (const KeypointPtr& keypoint : keypoints)
458  {
459  res.emplace_back(keypoint->getTargetPose());
460  }
461  return res;
462  }
463 
464  std::vector<Eigen::Vector3f>
466  {
467  ARMARX_TRACE;
468  std::vector<Eigen::Vector3f> res;
469  for (const KeypointPtr& keypoint : keypoints)
470  {
471  res.emplace_back(keypoint->getTargetPosition());
472  }
473  return res;
474  }
475 
476  std::vector<Eigen::Matrix3f>
478  {
479  ARMARX_TRACE;
480  std::vector<Eigen::Matrix3f> res;
481  for (const KeypointPtr& keypoint : keypoints)
482  {
483  res.emplace_back(keypoint->getTargetOrientation());
484  }
485  return res;
486  }
487 
490  {
491  ARMARX_TRACE;
492  int i1, i2;
493  float f;
494  getIndex(t, i1, i2, f);
495  auto handTargetsMap = getKeypoint(i1)->handJointsTarget;
496  const auto handTargets1 = mapValuesToVector(handTargetsMap);
497  const auto handTargets2 = mapValuesToVector(getKeypoint(i2)->handJointsTarget);
498  const Eigen::VectorXf lerpTargets = handTargets1 * (1 - f) + handTargets2 * f;
499  auto* lerpTargetsIt = lerpTargets.data();
500  for (auto& [name, value] : handTargetsMap)
501  {
502  value = *(lerpTargetsIt++);
503  }
504  return handTargetsMap;
505  }
506 
507  std::optional<std::string>
509  {
510  ARMARX_TRACE;
511  int i1, i2;
512  float f;
513  getIndex(t, i1, i2, f);
514 
515  // i1 is the one before or at the timestamp t
516  return getKeypoint(i1)->shape;
517  }
518 
519  Eigen::Vector3f
521  {
522  ARMARX_TRACE;
523  int i1, i2;
524  float f;
525  getIndex(t, i1, i2, f);
526  return getKeypoint(i2)->feedForwardPosVelocity;
527  }
528 
529  Eigen::Vector3f
531  {
532  ARMARX_TRACE;
533  int i1, i2;
534  float f;
535  getIndex(t, i1, i2, f);
536  return getKeypoint(i2)->feedForwardOriVelocity;
537  }
538 
541  {
542  ARMARX_TRACE;
544  ffVel.block<3, 1>(0, 0) = GetPositionDerivative(t);
545  ffVel.block<3, 1>(3, 0) = GetOrientationDerivative(t);
546  return ffVel;
547  }
548 
549  Eigen::Vector3f
551  {
552  ARMARX_TRACE;
553  int i1, i2;
554  float f;
555  getIndex(t, i1, i2, f);
556  return getKeypoint(i2)->feedForwardHandJointsVelocity;
557  }
558 
559  float
561  {
562  ARMARX_TRACE;
563  return keypointMap.rbegin()->first;
564  }
565 
566  GraspTrajectory::Length
568  {
569  ARMARX_TRACE;
570  Length l;
571  for (size_t i = 1; i < keypoints.size(); i++)
572  {
573  KeypointPtr k0 = keypoints.at(i - 1);
574  KeypointPtr k1 = keypoints.at(i);
575 
576  Eigen::Vector3f pos0 = ::math::Helpers::GetPosition(k0->tcpTarget);
577  Eigen::Matrix3f ori0 = ::math::Helpers::GetOrientation(k0->tcpTarget);
578 
579  Eigen::Vector3f pos1 = ::math::Helpers::GetPosition(k1->tcpTarget);
580  Eigen::Matrix3f ori1 = ::math::Helpers::GetOrientation(k1->tcpTarget);
581 
582  l.pos += (pos1 - pos0).norm();
583  l.ori += fabs(::math::Helpers::GetAngleAxisFromTo(ori0, ori1).angle());
584  }
585  return l;
586  }
587 
589  GraspTrajectory::getTranslatedAndRotated(const Eigen::Vector3f& translation,
590  const Eigen::Matrix3f& rotation) const
591  {
592  ARMARX_TRACE;
593  GraspTrajectoryPtr traj(
594  new GraspTrajectory(::math::Helpers::TranslateAndRotatePose(
595  getKeypoint(0)->getTargetPose(), translation, rotation),
596  getKeypoint(0)->handJointsTarget));
597  for (size_t i = 1; i < keypoints.size(); i++)
598  {
599  const KeypointPtr& kp = keypoints.at(i);
600  traj->addKeypoint(
601  ::math::Helpers::TranslateAndRotatePose(kp->getTargetPose(), translation, rotation),
602  kp->handJointsTarget,
603  kp->dt,
604  kp->shape);
605  }
606  return traj;
607  }
608 
611  {
612  ARMARX_TRACE;
614  transform * getStartPose(), getKeypoint(0)->handJointsTarget, getKeypoint(0)->shape));
615  for (size_t i = 1; i < keypoints.size(); i++)
616  {
617  const KeypointPtr& kp = keypoints.at(i);
618  traj->addKeypoint(
619  transform * kp->getTargetPose(), kp->handJointsTarget, kp->dt, kp->shape);
620  }
621  return traj;
622  }
623 
626  {
627  ARMARX_TRACE;
629  }
630 
633  const Eigen::Vector3f& handForward) const
634  {
635  ARMARX_TRACE;
636  Eigen::Matrix4f startPose = getStartPose();
637  Eigen::Vector3f targetHandForward =
638  ::math::Helpers::TransformDirection(target, handForward);
639  Eigen::Vector3f trajHandForward =
640  ::math::Helpers::TransformDirection(startPose, handForward);
641  Eigen::Vector3f up(0, 0, 1);
642 
643  float angle = ::math::Helpers::Angle(targetHandForward, trajHandForward, up);
644  Eigen::AngleAxisf aa(angle, up);
645 
646  Eigen::Matrix4f transform = ::math::Helpers::CreateTranslationRotationTranslationPose(
647  -::math::Helpers::GetPosition(startPose),
648  aa.toRotationMatrix(),
649  ::math::Helpers::GetPosition(target));
650  return getTransformed(transform);
651  }
652 
655  {
656  ARMARX_TRACE;
658  flip_yz(0, 0) *= -1.0;
659  Eigen::Matrix4f start_pose = getStartPose();
660  start_pose.block<3, 3>(0, 0) = flip_yz * start_pose.block<3, 3>(0, 0) * flip_yz;
661  GraspTrajectoryPtr output_trajectory(
662  new GraspTrajectory(start_pose, getKeypoint(0)->handJointsTarget));
663  for (size_t i = 1; i < getKeypointCount(); i++)
664  {
666  Eigen::Matrix4f target_pose = kp->getTargetPose();
667  target_pose.block<3, 3>(0, 0) = flip_yz * target_pose.block<3, 3>(0, 0) * flip_yz;
668  output_trajectory->addKeypoint(target_pose, kp->handJointsTarget, kp->dt, kp->shape);
669  }
670  return output_trajectory;
671  }
672 
674  GraspTrajectory::calculateReachability(VirtualRobot::RobotNodeSetPtr rns,
675  VirtualRobot::RobotNodePtr tcp,
677  {
678  ARMARX_TRACE;
680  getAllKeypointPoses(), Eigen::VectorXf::Zero(rns->getSize()), rns, tcp, params);
681  }
682 
683  void
684  GraspTrajectory::updateKeypointMap()
685  {
686  ARMARX_TRACE;
687  keypointMap.clear();
688  float t = 0;
689  for (size_t i = 0; i < keypoints.size(); i++)
690  {
691  t += getKeypoint(i)->dt;
692  keypointMap[t] = i;
693  }
694  }
695 
696  void
698  float deltat)
699  {
700  ARMARX_TRACE;
701  Eigen::Vector3f pos0 = ::math::Helpers::GetPosition(prev->tcpTarget);
702  Eigen::Matrix3f ori0 = ::math::Helpers::GetOrientation(prev->tcpTarget);
703  auto hnd0 = mapValuesToVector(prev->handJointsTarget);
704 
705  Eigen::Vector3f pos1 = ::math::Helpers::GetPosition(tcpTarget);
706  Eigen::Matrix3f ori1 = ::math::Helpers::GetOrientation(tcpTarget);
707  auto hnd1 = mapValuesToVector(handJointsTarget);
708 
709  Eigen::Vector3f dpos = pos1 - pos0;
710  Eigen::Vector3f dori = ::math::Helpers::GetRotationVector(ori0, ori1);
711  Eigen::VectorXf dhnd = hnd1 - hnd0;
712 
713  this->dt = deltat;
714  feedForwardPosVelocity = dpos / deltat;
715  feedForwardOriVelocity = dori / deltat;
716  feedForwardHandJointsVelocity = dhnd / deltat;
717  }
718 
719  Eigen::Vector3f
721  {
722  ARMARX_TRACE;
723  return ::math::Helpers::GetPosition(tcpTarget);
724  }
725 
728  {
729  ARMARX_TRACE;
730  return ::math::Helpers::GetOrientation(tcpTarget);
731  }
732 
735  {
736  ARMARX_TRACE;
737  return tcpTarget;
738  }
739 
741  const Eigen::Matrix4f& tcpTarget,
742  const armarx::NameValueMap& handJointsTarget,
743  float dt,
744  const Eigen::Vector3f& feedForwardPosVelocity,
745  const Eigen::Vector3f& feedForwardOriVelocity,
746  const Eigen::VectorXf& feedForwardHandJointsVelocity,
747  const std::optional<std::string>& shape) :
748  tcpTarget(tcpTarget),
749  handJointsTarget(handJointsTarget),
750  shape(shape),
751  dt(dt),
752  feedForwardPosVelocity(feedForwardPosVelocity),
753  feedForwardOriVelocity(feedForwardOriVelocity),
754  feedForwardHandJointsVelocity(feedForwardHandJointsVelocity)
755  {
756  }
757 
759  const armarx::NameValueMap& handJointsTarget,
760  const std::optional<std::string>& shape) :
761  tcpTarget(tcpTarget),
762  handJointsTarget(handJointsTarget),
763  shape(shape),
764  dt(0),
765  feedForwardPosVelocity(0, 0, 0),
766  feedForwardOriVelocity(0, 0, 0)
767  {
768  }
769 
770  void
771  GraspTrajectory::setFrame(const std::string& frame)
772  {
773  frame_ = frame;
774  }
775 
776  const std::optional<std::string>&
778  {
779  return frame_;
780  }
781 } // namespace armarx
armarx::RapidXmlReaderPtr
std::shared_ptr< RapidXmlReader > RapidXmlReaderPtr
Definition: RapidXmlReader.h:66
armarx::RapidXmlReader::FromFile
static RapidXmlReaderPtr FromFile(const std::string &path)
Definition: RapidXmlReader.h:497
armarx::GraspTrajectory::GetPosition
Eigen::Vector3f GetPosition(float t)
Definition: GraspTrajectory.cpp:203
armarx::GraspTrajectory::getAllKeypointPositions
std::vector< Eigen::Vector3f > getAllKeypointPositions()
Definition: GraspTrajectory.cpp:241
armarx::GraspTrajectory::Keypoint::tcpTarget
Eigen::Matrix4f tcpTarget
Definition: GraspTrajectory.h:62
armarx::GraspTrajectory::getAllKeypointOrientations
std::vector< Eigen::Matrix3f > getAllKeypointOrientations()
Definition: GraspTrajectory.cpp:251
armarx::GraspTrajectory::calculateReachability
SimpleDiffIK::Reachability calculateReachability(VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr tcp=VirtualRobot::RobotNodePtr(), SimpleDiffIK::Parameters params=SimpleDiffIK::Parameters())
Definition: GraspTrajectory.cpp:373
GraspTrajectory.h
armarx::core::time::Duration::toSecondsDouble
double toSecondsDouble() const
Returns the amount of seconds.
Definition: Duration.cpp:104
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
armarx::GraspTrajectory::getFrame
const std::optional< std::string > & getFrame() const
Definition: GraspTrajectory.cpp:777
armarx::GraspTrajectory::ReadFromJSON
static GraspTrajectoryPtr ReadFromJSON(const std::string &filename)
Definition: GraspTrajectory.cpp:199
armarx::SimpleDiffIK::Parameters
Definition: SimpleDiffIK.h:40
armarx::GraspTrajectory::ReadFromFile
static GraspTrajectoryPtr ReadFromFile(const grasping::GraspCandidatePtr &cnd)
Definition: GraspTrajectory.cpp:393
armarx::GraspTrajectory::insertKeypoint
void insertKeypoint(size_t index, const Eigen::Matrix4f &tcpTarget, const Eigen::VectorXf &handJointsTarget, float dt)
Definition: GraspTrajectory.cpp:103
index
uint8_t index
Definition: EtherCATFrame.h:59
armarx::RapidXmlReader::FromXmlString
static RapidXmlReaderPtr FromXmlString(const std::string &xml)
Definition: RapidXmlReader.h:491
armarx::GraspTrajectory::getTranslatedAndRotated
GraspTrajectoryPtr getTranslatedAndRotated(const Eigen::Vector3f &translation, const Eigen::Matrix3f &rotation)
Definition: GraspTrajectory.cpp:332
armarx::GraspTrajectory::getStartPose
Eigen::Matrix4f getStartPose()
Definition: GraspTrajectory.cpp:174
armarx::SimpleDiffIK::Reachability
Definition: SimpleDiffIK.h:81
SimpleJsonLogger.h
armarx::GraspTrajectory::KeypointPtr
std::shared_ptr< Keypoint > KeypointPtr
Definition: GraspTrajectory.h:56
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:688
StructuralJsonParser.h
Duration.h
armarx::JsonValue::Create
static JsonValuePtr Create(const std::string &value)
Definition: JsonValue.cpp:65
RapidXmlWriter.h
armarx::GraspTrajectory::Keypoint::handJointsTarget
Eigen::VectorXf handJointsTarget
Definition: GraspTrajectory.h:63
armarx::GraspTrajectory::getTransformedToOtherHand
GraspTrajectoryPtr getTransformedToOtherHand() const
Definition: GraspTrajectory.cpp:654
ARMARX_CHECK_NOT_EMPTY
#define ARMARX_CHECK_NOT_EMPTY(c)
Definition: ExpressionException.h:224
armarx::GraspTrajectory::GetTcpDerivative
Eigen::Vector6f GetTcpDerivative(float t)
Definition: GraspTrajectory.cpp:286
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
armarx::GraspTrajectory::Keypoint::getTargetOrientation
Eigen::Matrix3f getTargetOrientation() const
Definition: GraspTrajectory.cpp:50
armarx::GraspTrajectory::ReadFromReader
static GraspTrajectoryPtr ReadFromReader(const RapidXmlReaderPtr &reader)
Definition: GraspTrajectory.cpp:401
armarx::GraspTrajectory::GetShape
std::optional< std::string > GetShape(float t) const
Definition: GraspTrajectory.cpp:508
ARMARX_TRACE
#define ARMARX_TRACE
Definition: trace.h:69
armarx::GraspTrajectory::Keypoint
GraspTrajectoryKeypoint Keypoint
Definition: GraspTrajectory.h:80
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
armarx::GraspTrajectory::getAllKeypointPoses
std::vector< Eigen::Matrix4f > getAllKeypointPoses()
Definition: GraspTrajectory.cpp:231
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
armarx::GraspTrajectoryPtr
std::shared_ptr< class GraspTrajectory > GraspTrajectoryPtr
Definition: GraspTrajectory.h:51
armarx::GraspTrajectory::GraspTrajectory
GraspTrajectory()=default
armarx::GraspTrajectory::setFrame
void setFrame(const std::string &frame)
Definition: GraspTrajectory.cpp:771
armarx::GraspTrajectory::GetPositionDerivative
Eigen::Vector3f GetPositionDerivative(float t)
Definition: GraspTrajectory.cpp:270
armarx::GraspTrajectory::removeKeypoint
void removeKeypoint(size_t index)
Definition: GraspTrajectory.cpp:122
JPathNavigator.h
armarx::GraspTrajectory::GetHandValues
Eigen::VectorXf GetHandValues(float t)
Definition: GraspTrajectory.cpp:261
armarx::GraspTrajectory::calculateLength
Length calculateLength() const
Definition: GraspTrajectory.cpp:307
armarx::GraspTrajectory::setKeypointDt
void setKeypointDt(size_t index, float dt)
Definition: GraspTrajectory.cpp:152
armarx::GraspTrajectory::Keypoint::getTargetPosition
Eigen::Vector3f getTargetPosition() const
Definition: GraspTrajectory.cpp:45
armarx::GraspTrajectory::getTransformed
GraspTrajectoryPtr getTransformed(const Eigen::Matrix4f &transform)
Definition: GraspTrajectory.cpp:343
armarx::KeypointPtr
std::shared_ptr< Keypoint > KeypointPtr
Definition: KeypointManager.h:104
armarx::mapValuesToVector
Eigen::VectorXf mapValuesToVector(const armarx::NameValueMap &map)
Definition: GraspTrajectory.cpp:54
filename
std::string filename
Definition: VisualizationRobot.cpp:83
armarx::GraspTrajectory::getIndex
void getIndex(float t, int &i1, int &i2, float &f)
Definition: GraspTrajectory.cpp:179
armarx::GraspTrajectoryKeypoint::GraspTrajectoryKeypoint
GraspTrajectoryKeypoint()=default
armarx::GraspTrajectory::getAllKeypoints
const std::vector< KeypointPtr > & getAllKeypoints() const
Definition: GraspTrajectory.cpp:289
armarx::GraspTrajectory::GetHandJointsDerivative
Eigen::VectorXf GetHandJointsDerivative(float t)
Definition: GraspTrajectory.cpp:294
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
armarx::GraspTrajectory::GetOrientationDerivative
Eigen::Vector3f GetOrientationDerivative(float t)
Definition: GraspTrajectory.cpp:278
armarx::GraspTrajectory::ReadFromString
static GraspTrajectoryPtr ReadFromString(const std::string &xml)
Definition: GraspTrajectory.cpp:447
armarx::GraspTrajectory::getTransformedToGraspPose
GraspTrajectoryPtr getTransformedToGraspPose(const Eigen::Matrix4f &target, const Eigen::Vector3f &handForward=Eigen::Vector3f::UnitZ())
Definition: GraspTrajectory.cpp:359
ExpressionException.h
armarx::control::njoint_controller::platform::platform_follower_controller::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformFollowerController.h:91
armarx::from_json
void from_json(const nlohmann::json &j, Vector2f &value)
armarx::GraspTrajectoryKeypoint
Definition: GraspTrajectory.h:44
CMakePackageFinder.h
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:600
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::GraspTrajectory::lastKeypoint
KeypointPtr & lastKeypoint()
Definition: GraspTrajectory.cpp:164
armarx::SimpleDiffIK::CalculateReachability
static Reachability CalculateReachability(const std::vector< Eigen::Matrix4f > targets, const Eigen::VectorXf &initialJV, VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr tcp=VirtualRobot::RobotNodePtr(), Parameters params=Parameters())
Use this to check a trajectory of waypoints.
Definition: SimpleDiffIK.cpp:127
armarx::GraspTrajectory::getKeypoint
KeypointPtr & getKeypoint(int i)
Definition: GraspTrajectory.cpp:169
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:315
armarx::core::time::Duration
Represents a duration.
Definition: Duration.h:17
RapidXmlReader.h
armarx::GraspTrajectory::GetOrientation
Eigen::Matrix3f GetOrientation(float t)
Definition: GraspTrajectory.cpp:211
angle
double angle(const Point &a, const Point &b, const Point &c)
Definition: point.hpp:100
armarx::GraspTrajectory::Keypoint::feedForwardHandJointsVelocity
Eigen::VectorXf feedForwardHandJointsVelocity
Definition: GraspTrajectory.h:67
armarx::GraspTrajectory::Keypoint::feedForwardOriVelocity
Eigen::Vector3f feedForwardOriVelocity
Definition: GraspTrajectory.h:66
Eigen::Matrix
Definition: EigenForwardDeclarations.h:27
armarx::GraspTrajectory::replaceKeypoint
void replaceKeypoint(size_t index, const Eigen::Matrix4f &tcpTarget, const Eigen::VectorXf &handJointsTarget, float dt)
Definition: GraspTrajectory.cpp:138
armarx::GraspTrajectory::writeToFile
void writeToFile(const std::string &filename)
Definition: GraspTrajectory.cpp:378
Logging.h
armarx::GraspTrajectory::Keypoint::getTargetPose
Eigen::Matrix4f getTargetPose() const
Definition: GraspTrajectory.cpp:55
armarx::GraspTrajectory::GetPose
Eigen::Matrix4f GetPose(float t)
Definition: GraspTrajectory.cpp:226
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::GraspTrajectory::getClone
GraspTrajectoryPtr getClone()
Definition: GraspTrajectory.cpp:354
armarx::core::time::Duration::MicroSeconds
static Duration MicroSeconds(std::int64_t microSeconds)
Constructs a duration in microseconds.
Definition: Duration.cpp:27
armarx::GraspTrajectory::Keypoint::feedForwardPosVelocity
Eigen::Vector3f feedForwardPosVelocity
Definition: GraspTrajectory.h:65
armarx::GraspTrajectory::getDuration
float getDuration() const
Definition: GraspTrajectory.cpp:302
armarx::GraspTrajectory::Keypoint::updateVelocities
void updateVelocities(const KeypointPtr &prev, float dt)
Definition: GraspTrajectory.cpp:60
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::GraspTrajectory::getKeypointCount
size_t getKeypointCount() const
Definition: GraspTrajectory.cpp:98
Exception.h
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:42
armarx::GraspTrajectory::addKeypoint
void addKeypoint(const Eigen::Matrix4f &tcpTarget, const Eigen::VectorXf &handJointsTarget, float dt)
Definition: GraspTrajectory.cpp:87
armarx::JsonObjectPtr
std::shared_ptr< JsonObject > JsonObjectPtr
Definition: JsonObject.h:34
norm
double norm(const Point &a)
Definition: point.hpp:94