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 
40 
43 
44 #include <RobotAPI/interface/units/GraspCandidateProviderInterface.h>
46 
47 namespace armarx
48 {
49 
50  Eigen::VectorXf
52  {
54  Eigen::VectorXf vector(map.size());
56  map.begin(), map.end(), vector.data(), [](const auto& item) { return item.second; });
57  return vector;
58  }
59 
60  void
61  GraspTrajectory::writeToFile(const std::string& filename)
62  {
64  RapidXmlWriter writer;
65  RapidXmlWriterNode root = writer.createRootNode("GraspTrajectory");
66  for (const KeypointPtr& keypoint : keypoints)
67  {
68  SimpleJsonLoggerEntry e;
69  e.Add("dt", keypoint->dt);
70  e.AddAsArr("Pose", keypoint->tcpTarget);
71  JsonObjectPtr const obj = std::make_shared<JsonObject>();
72  for (const auto& [name, value] : keypoint->handJointsTarget)
73  {
74  obj->add(name, JsonValue::Create(value));
75  }
76  e.obj->add("HandValues", obj);
77  root.append_string_node("Keypoint", e.obj->toJsonString(0, "", true));
78  }
79  writer.saveToFile(filename, true);
80  }
81 
84  {
86  RapidXmlReaderNode const root = reader->getRoot();
87 
88  GraspTrajectoryPtr traj;
89  for (const RapidXmlReaderNode& kpNode : root.nodes("Keypoint"))
90  {
91  StructuralJsonParser p(kpNode.value());
92  p.parse();
93  JPathNavigator nav(p.parsedJson);
94  float dt = nav.selectSingleNode("dt").asFloat();
95 
96  Eigen::Matrix4f pose;
97  std::vector<JPathNavigator> rows = nav.select("Pose/*");
98  for (int i = 0; i < 4; i++)
99  {
100  std::vector<JPathNavigator> cells = rows.at(i).select("*");
101  for (int j = 0; j < 4; j++)
102  {
103  pose(i, j) = cells.at(j).asFloat();
104  }
105  }
106 
107  armarx::NameValueMap handValues;
108  std::vector<JPathNavigator> cells = nav.select("HandValues/*");
109  for (const auto& cell : cells)
110  {
111  handValues[cell.getKey()] = cell.asFloat();
112  }
113 
114  // does not work at the moment
115  const auto shapeNode = nav.selectSingleNode("shape");
116  // ARMARX_IMPORTANT << VAROUT(shapeNode.isValid());
117 
118  std::optional<std::string> shape;
119  if (shapeNode.isString())
120  {
121  shape = nav.selectSingleNode("shape").asString();
122  // ARMARX_IMPORTANT << "shape: " << shape.value();
123  }
124 
125 
126  if (!traj)
127  {
128  traj = std::make_shared<GraspTrajectory>(pose, handValues, shape);
129  }
130  else
131  {
132  traj->addKeypoint(pose, handValues, dt, shape);
133  }
134  }
135  return traj;
136  }
137 
139  GraspTrajectory::ReadFromFile(const std::string& filename)
140  {
141  ARMARX_TRACE;
142  const auto ext = std::filesystem::path(filename).extension();
143  if (ext == ".xml")
144  {
146  }
147  if (ext == ".json")
148  {
149  return ReadFromJSON(filename);
150  }
151 
152  ARMARX_WARNING << "Unknown extension `" << ext << "`!";
153  return nullptr;
154  }
155 
156  // NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(GraspTrajectory::Keypoint,tcpTarget,handJointsTarget,shape,dt );
157 
158 
159  inline void
160  from_json(const nlohmann::json& j, GraspTrajectoryKeypoint& kp)
161  {
162  const std::optional<std::string> shape =
163  j.contains("shape") ? std::optional<std::string>(j.at("shape").get<std::string>())
164  : std::nullopt;
165 
166  const std::map<std::string, float> targetHandValues =
167  j.contains("HandValues") ? j.at("HandValues").get<std::map<std::string, float>>()
168  : std::map<std::string, float>{};
169 
170  kp = GraspTrajectoryKeypoint(j.at("Pose"), targetHandValues, shape);
171  }
172 
175  {
176  ARMARX_CHECK(std::filesystem::exists(filename));
177  std::ifstream ifs(filename);
178 
179  const nlohmann::json j = nlohmann::json::parse(ifs);
180 
181  std::vector<GraspTrajectoryKeypoint> traj;
182  traj = j;
183 
184  return std::make_shared<GraspTrajectory>(traj);
185  }
186 
188  GraspTrajectory::ReadFromString(const std::string& xml)
189  {
190  ARMARX_TRACE;
192  }
193 
195  const armarx::NameValueMap& handJointsStart,
196  const std::optional<std::string>& shape)
197  {
198  ARMARX_TRACE;
199  KeypointPtr keypoint(new Keypoint(tcpStart, handJointsStart, shape));
200  keypointMap[0] = keypoints.size();
201  keypoints.push_back(keypoint);
202  }
203 
204  GraspTrajectory::GraspTrajectory(const std::vector<Keypoint>& keypointz)
205  {
206  if (keypointz.empty())
207  {
208  return;
209  }
210 
211  // insert first keypoint
212  keypointMap[0] = keypoints.size();
213  keypoints.push_back(std::make_shared<Keypoint>(keypointz.front()));
214 
215  // insert remaining keypoints
216  for (std::size_t i = 1; i < keypointz.size(); i++)
217  {
218  const auto& kp = keypointz.at(i);
219  addKeypoint(kp.tcpTarget, kp.handJointsTarget, kp.dt, kp.shape);
220  }
221  }
222 
223  void
225  const armarx::NameValueMap& handJointsTarget,
226  float dt,
227  const std::optional<std::string>& shape)
228  {
229  ARMARX_TRACE;
230  KeypointPtr prev = lastKeypoint();
231  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape));
232  keypoint->updateVelocities(prev, dt);
233  float t = getDuration() + dt;
234  keypointMap[t] = keypoints.size();
235  keypoints.push_back(keypoint);
236  }
237 
238  size_t
240  {
241  ARMARX_TRACE;
242  return keypoints.size();
243  }
244 
245  const std::vector<GraspTrajectory::KeypointPtr>&
247  {
248  return keypoints;
249  }
250 
251  void
253  const Eigen::Matrix4f& tcpTarget,
254  const armarx::NameValueMap& handJointsTarget,
255  float dt,
256  const std::optional<std::string>& shape)
257  {
258  ARMARX_TRACE;
259  if (index <= 0 || index > keypoints.size())
260  {
261  throw LocalException("Index out of range" + std::to_string(index));
262  }
263  KeypointPtr prev = keypoints.at(index - 1);
264  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape));
265  keypoint->updateVelocities(prev, dt);
266  if (index < keypoints.size())
267  {
268  KeypointPtr next = keypoints.at(index);
269  next->updateVelocities(keypoint, next->dt);
270  }
271  keypoints.insert(keypoints.begin() + index, keypoint);
272  updateKeypointMap();
273  }
274 
275  void
277  {
278  ARMARX_TRACE;
279  if (index <= 0 || index >= keypoints.size())
280  {
281  throw LocalException("Index out of range" + std::to_string(index));
282  }
283  keypoints.erase(keypoints.begin() + index);
284  if (index < keypoints.size())
285  {
286  ARMARX_TRACE;
287  KeypointPtr prev = keypoints.at(index - 1);
288  KeypointPtr next = keypoints.at(index);
289  next->updateVelocities(prev, next->dt);
290  }
291  updateKeypointMap();
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  keypoints.at(index) = keypoint;
310  updateKeypointMap();
311  }
312 
313  void
315  {
316  ARMARX_TRACE;
317  if (index <= 0 || index >= keypoints.size())
318  {
319  throw LocalException("Index out of range" + std::to_string(index));
320  }
321  KeypointPtr prev = keypoints.at(index - 1);
322  KeypointPtr& keypoint = keypoints.at(index);
323  keypoint->updateVelocities(prev, dt);
324  updateKeypointMap();
325  }
326 
329  {
330  ARMARX_TRACE;
331  return keypoints.at(keypoints.size() - 1);
332  }
333 
336  {
337  ARMARX_TRACE;
338  return keypoints.at(i);
339  }
340 
343  {
344  ARMARX_TRACE;
345  return getKeypoint(0)->getTargetPose();
346  }
347 
348  void
349  GraspTrajectory::getIndex(float t, int& i1, int& i2, float& f) const
350  {
351  ARMARX_TRACE;
352  if (t <= 0)
353  {
354  i1 = 0;
355  i2 = 0;
356  f = 0;
357  return;
358  }
359  std::map<float, size_t>::const_iterator it, prev;
360  it = keypointMap.upper_bound(t);
361  if (it == keypointMap.end())
362  {
363  i1 = keypoints.size() - 1;
364  i2 = keypoints.size() - 1;
365  f = 0;
366  return;
367  }
368  prev = std::prev(it);
369  i1 = prev->second;
370  i2 = it->second;
371  f = ::math::Helpers::ILerp(prev->first, it->first, t);
372  }
373 
374  Eigen::Vector3f
376  {
377  ARMARX_TRACE;
378  int i1, i2;
379  float f;
380  getIndex(t, i1, i2, f);
381  return ::math::Helpers::Lerp(
382  getKeypoint(i1)->getTargetPosition(), getKeypoint(i2)->getTargetPosition(), f);
383  }
384 
387  {
388  ARMARX_TRACE;
389  int i1, i2;
390  float f;
391  getIndex(t, i1, i2, f);
392  Eigen::Vector3f oriVel = GetOrientationDerivative(t);
393  if (oriVel.squaredNorm() == 0)
394  {
395  return getKeypoint(i1)->getTargetOrientation();
396  }
397  Eigen::AngleAxisf aa(oriVel.norm(), oriVel.normalized());
398  aa.angle() = aa.angle() * f * getKeypoint(i2)->dt;
399  return aa.toRotationMatrix() * getKeypoint(i1)->getTargetOrientation();
400  }
401 
404  {
405  ARMARX_TRACE;
406  return ::math::Helpers::CreatePose(GetPosition(t), GetOrientation(t));
407  }
408 
409  std::vector<Eigen::Matrix4f>
411  {
412  ARMARX_TRACE;
413  std::vector<Eigen::Matrix4f> res;
414  for (const KeypointPtr& keypoint : keypoints)
415  {
416  res.emplace_back(keypoint->getTargetPose());
417  }
418  return res;
419  }
420 
421  std::vector<Eigen::Vector3f>
423  {
424  ARMARX_TRACE;
425  std::vector<Eigen::Vector3f> res;
426  for (const KeypointPtr& keypoint : keypoints)
427  {
428  res.emplace_back(keypoint->getTargetPosition());
429  }
430  return res;
431  }
432 
433  std::vector<Eigen::Matrix3f>
435  {
436  ARMARX_TRACE;
437  std::vector<Eigen::Matrix3f> res;
438  for (const KeypointPtr& keypoint : keypoints)
439  {
440  res.emplace_back(keypoint->getTargetOrientation());
441  }
442  return res;
443  }
444 
447  {
448  ARMARX_TRACE;
449  int i1, i2;
450  float f;
451  getIndex(t, i1, i2, f);
452  auto handTargetsMap = getKeypoint(i1)->handJointsTarget;
453  const auto handTargets1 = mapValuesToVector(handTargetsMap);
454  const auto handTargets2 = mapValuesToVector(getKeypoint(i2)->handJointsTarget);
455  const Eigen::VectorXf lerpTargets = handTargets1 * (1 - f) + handTargets2 * f;
456  auto* lerpTargetsIt = lerpTargets.data();
457  for (auto& [name, value] : handTargetsMap)
458  {
459  value = *(lerpTargetsIt++);
460  }
461  return handTargetsMap;
462  }
463 
464  std::optional<std::string>
466  {
467  ARMARX_TRACE;
468  int i1, i2;
469  float f;
470  getIndex(t, i1, i2, f);
471 
472  // i1 is the one before or at the timestamp t
473  return getKeypoint(i1)->shape;
474  }
475 
476  Eigen::Vector3f
478  {
479  ARMARX_TRACE;
480  int i1, i2;
481  float f;
482  getIndex(t, i1, i2, f);
483  return getKeypoint(i2)->feedForwardPosVelocity;
484  }
485 
486  Eigen::Vector3f
488  {
489  ARMARX_TRACE;
490  int i1, i2;
491  float f;
492  getIndex(t, i1, i2, f);
493  return getKeypoint(i2)->feedForwardOriVelocity;
494  }
495 
498  {
499  ARMARX_TRACE;
501  ffVel.block<3, 1>(0, 0) = GetPositionDerivative(t);
502  ffVel.block<3, 1>(3, 0) = GetOrientationDerivative(t);
503  return ffVel;
504  }
505 
506  Eigen::Vector3f
508  {
509  ARMARX_TRACE;
510  int i1, i2;
511  float f;
512  getIndex(t, i1, i2, f);
513  return getKeypoint(i2)->feedForwardHandJointsVelocity;
514  }
515 
516  float
518  {
519  ARMARX_TRACE;
520  return keypointMap.rbegin()->first;
521  }
522 
523  GraspTrajectory::Length
525  {
526  ARMARX_TRACE;
527  Length l;
528  for (size_t i = 1; i < keypoints.size(); i++)
529  {
530  KeypointPtr k0 = keypoints.at(i - 1);
531  KeypointPtr k1 = keypoints.at(i);
532 
533  Eigen::Vector3f pos0 = ::math::Helpers::GetPosition(k0->tcpTarget);
534  Eigen::Matrix3f ori0 = ::math::Helpers::GetOrientation(k0->tcpTarget);
535 
536  Eigen::Vector3f pos1 = ::math::Helpers::GetPosition(k1->tcpTarget);
537  Eigen::Matrix3f ori1 = ::math::Helpers::GetOrientation(k1->tcpTarget);
538 
539  l.pos += (pos1 - pos0).norm();
540  l.ori += fabs(::math::Helpers::GetAngleAxisFromTo(ori0, ori1).angle());
541  }
542  return l;
543  }
544 
546  GraspTrajectory::getTranslatedAndRotated(const Eigen::Vector3f& translation,
547  const Eigen::Matrix3f& rotation) const
548  {
549  ARMARX_TRACE;
550  GraspTrajectoryPtr traj(
551  new GraspTrajectory(::math::Helpers::TranslateAndRotatePose(
552  getKeypoint(0)->getTargetPose(), translation, rotation),
553  getKeypoint(0)->handJointsTarget));
554  for (size_t i = 1; i < keypoints.size(); i++)
555  {
556  const KeypointPtr& kp = keypoints.at(i);
557  traj->addKeypoint(
558  ::math::Helpers::TranslateAndRotatePose(kp->getTargetPose(), translation, rotation),
559  kp->handJointsTarget,
560  kp->dt);
561  }
562  return traj;
563  }
564 
567  {
568  ARMARX_TRACE;
569  GraspTrajectoryPtr traj(
570  new GraspTrajectory(transform * getStartPose(), getKeypoint(0)->handJointsTarget));
571  for (size_t i = 1; i < keypoints.size(); i++)
572  {
573  const KeypointPtr& kp = keypoints.at(i);
574  traj->addKeypoint(transform * kp->getTargetPose(), kp->handJointsTarget, kp->dt);
575  }
576  return traj;
577  }
578 
581  {
582  ARMARX_TRACE;
584  }
585 
588  const Eigen::Vector3f& handForward) const
589  {
590  ARMARX_TRACE;
591  Eigen::Matrix4f startPose = getStartPose();
592  Eigen::Vector3f targetHandForward =
593  ::math::Helpers::TransformDirection(target, handForward);
594  Eigen::Vector3f trajHandForward =
595  ::math::Helpers::TransformDirection(startPose, handForward);
596  Eigen::Vector3f up(0, 0, 1);
597 
598  float angle = ::math::Helpers::Angle(targetHandForward, trajHandForward, up);
599  Eigen::AngleAxisf aa(angle, up);
600 
601  Eigen::Matrix4f transform = ::math::Helpers::CreateTranslationRotationTranslationPose(
602  -::math::Helpers::GetPosition(startPose),
603  aa.toRotationMatrix(),
604  ::math::Helpers::GetPosition(target));
605  return getTransformed(transform);
606  }
607 
610  {
611  ARMARX_TRACE;
613  flip_yz(0, 0) *= -1.0;
614  Eigen::Matrix4f start_pose = getStartPose();
615  start_pose.block<3, 3>(0, 0) = flip_yz * start_pose.block<3, 3>(0, 0) * flip_yz;
616  GraspTrajectoryPtr output_trajectory(
617  new GraspTrajectory(start_pose, getKeypoint(0)->handJointsTarget));
618  for (size_t i = 1; i < getKeypointCount(); i++)
619  {
621  Eigen::Matrix4f target_pose = kp->getTargetPose();
622  target_pose.block<3, 3>(0, 0) = flip_yz * target_pose.block<3, 3>(0, 0) * flip_yz;
623  output_trajectory->addKeypoint(target_pose, kp->handJointsTarget, kp->dt);
624  }
625  return output_trajectory;
626  }
627 
629  GraspTrajectory::calculateReachability(VirtualRobot::RobotNodeSetPtr rns,
630  VirtualRobot::RobotNodePtr tcp,
632  {
633  ARMARX_TRACE;
635  getAllKeypointPoses(), Eigen::VectorXf::Zero(rns->getSize()), rns, tcp, params);
636  }
637 
638  void
639  GraspTrajectory::updateKeypointMap()
640  {
641  ARMARX_TRACE;
642  keypointMap.clear();
643  float t = 0;
644  for (size_t i = 0; i < keypoints.size(); i++)
645  {
646  t += getKeypoint(i)->dt;
647  keypointMap[t] = i;
648  }
649  }
650 
651  void
653  float deltat)
654  {
655  ARMARX_TRACE;
656  Eigen::Vector3f pos0 = ::math::Helpers::GetPosition(prev->tcpTarget);
657  Eigen::Matrix3f ori0 = ::math::Helpers::GetOrientation(prev->tcpTarget);
658  auto hnd0 = mapValuesToVector(prev->handJointsTarget);
659 
660  Eigen::Vector3f pos1 = ::math::Helpers::GetPosition(tcpTarget);
661  Eigen::Matrix3f ori1 = ::math::Helpers::GetOrientation(tcpTarget);
662  auto hnd1 = mapValuesToVector(handJointsTarget);
663 
664  Eigen::Vector3f dpos = pos1 - pos0;
665  Eigen::Vector3f dori = ::math::Helpers::GetRotationVector(ori0, ori1);
666  Eigen::VectorXf dhnd = hnd1 - hnd0;
667 
668  this->dt = deltat;
669  feedForwardPosVelocity = dpos / deltat;
670  feedForwardOriVelocity = dori / deltat;
671  feedForwardHandJointsVelocity = dhnd / deltat;
672  }
673 
674  Eigen::Vector3f
676  {
677  ARMARX_TRACE;
678  return ::math::Helpers::GetPosition(tcpTarget);
679  }
680 
683  {
684  ARMARX_TRACE;
685  return ::math::Helpers::GetOrientation(tcpTarget);
686  }
687 
690  {
691  ARMARX_TRACE;
692  return tcpTarget;
693  }
694 
696  const Eigen::Matrix4f& tcpTarget,
697  const armarx::NameValueMap& handJointsTarget,
698  float dt,
699  const Eigen::Vector3f& feedForwardPosVelocity,
700  const Eigen::Vector3f& feedForwardOriVelocity,
701  const Eigen::VectorXf& feedForwardHandJointsVelocity,
702  const std::optional<std::string>& shape) :
703  tcpTarget(tcpTarget),
704  handJointsTarget(handJointsTarget),
705  shape(shape),
706  dt(dt),
707  feedForwardPosVelocity(feedForwardPosVelocity),
708  feedForwardOriVelocity(feedForwardOriVelocity),
709  feedForwardHandJointsVelocity(feedForwardHandJointsVelocity)
710  {
711  }
712 
714  const armarx::NameValueMap& handJointsTarget,
715  const std::optional<std::string>& shape) :
716  tcpTarget(tcpTarget),
717  handJointsTarget(handJointsTarget),
718  shape(shape),
719  dt(0),
720  feedForwardPosVelocity(0, 0, 0),
721  feedForwardOriVelocity(0, 0, 0)
722  {
723  }
724 } // 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::GraspTrajectory::ReadFromJSON
static GraspTrajectoryPtr ReadFromJSON(const std::string &filename)
Definition: GraspTrajectory.cpp:174
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
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:609
armarx::navigation::platform_controller::platform_global_trajectory::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformGlobalTrajectoryController.h:93
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:465
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::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:51
filename
std::string filename
Definition: VisualizationRobot.cpp:84
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:246
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
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
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< float, 6, 1 >
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::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