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 
27 
28 using namespace armarx;
29 
30 
31 GraspTrajectory::Keypoint::Keypoint(const Eigen::Matrix4f& tcpTarget, const Eigen::VectorXf& handJointsTarget)
32  : tcpTarget(tcpTarget), handJointsTarget(handJointsTarget), dt(0),
33  feedForwardPosVelocity(0, 0, 0), feedForwardOriVelocity(0, 0, 0),
34  feedForwardHandJointsVelocity(Eigen::VectorXf::Zero(handJointsTarget.rows()))
35 { }
36 
37 GraspTrajectory::Keypoint::Keypoint(const Eigen::Matrix4f& tcpTarget, const Eigen::VectorXf& handJointsTarget,
38  float dt, const Eigen::Vector3f& feedForwardPosVelocity, const Eigen::Vector3f& feedForwardOriVelocity,
39  const Eigen::VectorXf& feedForwardHandJointsVelocity)
40  : tcpTarget(tcpTarget), handJointsTarget(handJointsTarget), dt(dt),
41  feedForwardPosVelocity(feedForwardPosVelocity), feedForwardOriVelocity(feedForwardOriVelocity),
42  feedForwardHandJointsVelocity(feedForwardHandJointsVelocity)
43 { }
44 
46 {
47  return ::math::Helpers::GetPosition(tcpTarget);
48 }
49 
51 {
52  return ::math::Helpers::GetOrientation(tcpTarget);
53 }
54 
56 {
57  return tcpTarget;
58 }
59 
61 {
62  Eigen::Vector3f pos0 = ::math::Helpers::GetPosition(prev->tcpTarget);
63  Eigen::Matrix3f ori0 = ::math::Helpers::GetOrientation(prev->tcpTarget);
64  Eigen::VectorXf hnd0 = prev->handJointsTarget;
65 
66  Eigen::Vector3f pos1 = ::math::Helpers::GetPosition(tcpTarget);
67  Eigen::Matrix3f ori1 = ::math::Helpers::GetOrientation(tcpTarget);
68  Eigen::VectorXf hnd1 = handJointsTarget;
69 
70  Eigen::Vector3f dpos = pos1 - pos0;
71  Eigen::Vector3f dori = ::math::Helpers::GetRotationVector(ori0, ori1);
72  Eigen::VectorXf dhnd = hnd1 - hnd0;
73 
74  this->dt = dt;
75  feedForwardPosVelocity = dpos / dt;
76  feedForwardOriVelocity = dori / dt;
77  feedForwardHandJointsVelocity = dhnd / dt;
78 }
79 
80 GraspTrajectory::GraspTrajectory(const Eigen::Matrix4f& tcpStart, const Eigen::VectorXf& handJointsStart)
81 {
82  KeypointPtr keypoint(new Keypoint(tcpStart, handJointsStart));
83  keypointMap[0] = keypoints.size();
84  keypoints.push_back(keypoint);
85 }
86 
87 void GraspTrajectory::addKeypoint(const Eigen::Matrix4f& tcpTarget, const Eigen::VectorXf& handJointsTarget, float dt)
88 {
89  ARMARX_CHECK_EQUAL(GetHandJointCount(), handJointsTarget.rows());
90  KeypointPtr prev = lastKeypoint();
91  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget));
92  keypoint->updateVelocities(prev, dt);
93  float t = getDuration() + dt;
94  keypointMap[t] = keypoints.size();
95  keypoints.push_back(keypoint);
96 }
97 
99 {
100  return keypoints.size();
101 }
102 
103 void GraspTrajectory::insertKeypoint(size_t index, const Eigen::Matrix4f& tcpTarget, const Eigen::VectorXf& handJointsTarget, float dt)
104 {
105  ARMARX_CHECK_EQUAL(GetHandJointCount(), handJointsTarget.rows());
106  if (index <= 0 || index > keypoints.size())
107  {
108  throw LocalException("Index out of range" + std::to_string(index));
109  }
110  KeypointPtr prev = keypoints.at(index - 1);
111  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget));
112  keypoint->updateVelocities(prev, dt);
113  if (index < keypoints.size())
114  {
115  KeypointPtr next = keypoints.at(index);
116  next->updateVelocities(keypoint, next->dt);
117  }
118  keypoints.insert(keypoints.begin() + index, keypoint);
119  updateKeypointMap();
120 }
121 
123 {
124  if (index <= 0 || index >= keypoints.size())
125  {
126  throw LocalException("Index out of range" + std::to_string(index));
127  }
128  keypoints.erase(keypoints.begin() + index);
129  if (index < keypoints.size())
130  {
131  KeypointPtr prev = keypoints.at(index - 1);
132  KeypointPtr next = keypoints.at(index);
133  next->updateVelocities(prev, next->dt);
134  }
135  updateKeypointMap();
136 }
137 
138 void GraspTrajectory::replaceKeypoint(size_t index, const Eigen::Matrix4f& tcpTarget, const Eigen::VectorXf& handJointsTarget, float dt)
139 {
140  ARMARX_CHECK_EQUAL(GetHandJointCount(), handJointsTarget.rows());
141  if (index <= 0 || index >= keypoints.size())
142  {
143  throw LocalException("Index out of range" + std::to_string(index));
144  }
145  KeypointPtr prev = keypoints.at(index - 1);
146  KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget));
147  keypoint->updateVelocities(prev, dt);
148  keypoints.at(index) = keypoint;
149  updateKeypointMap();
150 }
151 
153 {
154  if (index <= 0 || index >= keypoints.size())
155  {
156  throw LocalException("Index out of range" + std::to_string(index));
157  }
158  KeypointPtr prev = keypoints.at(index - 1);
159  KeypointPtr& keypoint = keypoints.at(index);
160  keypoint->updateVelocities(prev, dt);
161  updateKeypointMap();
162 }
163 
165 {
166  return keypoints.at(keypoints.size() - 1);
167 }
168 
170 {
171  return keypoints.at(i);
172 }
173 
175 {
176  return getKeypoint(0)->getTargetPose();
177 }
178 
179 void GraspTrajectory::getIndex(float t, int& i1, int& i2, float& f)
180 {
181  if (t <= 0)
182  {
183  i1 = 0;
184  i2 = 0;
185  f = 0;
186  return;
187  }
188  std::map<float, size_t>::const_iterator it, prev;
189  it = keypointMap.upper_bound(t);
190  if (it == keypointMap.end())
191  {
192  i1 = keypoints.size() - 1;
193  i2 = keypoints.size() - 1;
194  f = 0;
195  return;
196  }
197  prev = std::prev(it);
198  i1 = prev->second;
199  i2 = it->second;
200  f = ::math::Helpers::ILerp(prev->first, it->first, t);
201 }
202 
203 Eigen::Vector3f GraspTrajectory::GetPosition(float t)
204 {
205  int i1, i2;
206  float f;
207  getIndex(t, i1, i2, f);
208  return ::math::Helpers::Lerp(getKeypoint(i1)->getTargetPosition(), getKeypoint(i2)->getTargetPosition(), f);
209 }
210 
212 {
213  int i1, i2;
214  float f;
215  getIndex(t, i1, i2, f);
216  Eigen::Vector3f oriVel = GetOrientationDerivative(t);
217  if (oriVel.squaredNorm() == 0)
218  {
219  return getKeypoint(i1)->getTargetOrientation();
220  }
221  Eigen::AngleAxisf aa(oriVel.norm(), oriVel.normalized());
222  aa.angle() = aa.angle() * f * getKeypoint(i2)->dt;
223  return aa.toRotationMatrix() * getKeypoint(i1)->getTargetOrientation();
224 }
225 
227 {
228  return ::math::Helpers::CreatePose(GetPosition(t), GetOrientation(t));
229 }
230 
231 std::vector<Eigen::Matrix4f> GraspTrajectory::getAllKeypointPoses()
232 {
233  std::vector<Eigen::Matrix4f> res;
234  for (const KeypointPtr& keypoint : keypoints)
235  {
236  res.emplace_back(keypoint->getTargetPose());
237  }
238  return res;
239 }
240 
241 std::vector<Eigen::Vector3f> GraspTrajectory::getAllKeypointPositions()
242 {
243  std::vector<Eigen::Vector3f> res;
244  for (const KeypointPtr& keypoint : keypoints)
245  {
246  res.emplace_back(keypoint->getTargetPosition());
247  }
248  return res;
249 }
250 
251 std::vector<Eigen::Matrix3f> GraspTrajectory::getAllKeypointOrientations()
252 {
253  std::vector<Eigen::Matrix3f> res;
254  for (const KeypointPtr& keypoint : keypoints)
255  {
256  res.emplace_back(keypoint->getTargetOrientation());
257  }
258  return res;
259 }
260 
261 Eigen::VectorXf GraspTrajectory::GetHandValues(float t)
262 {
263  int i1, i2;
264  float f;
265  getIndex(t, i1, i2, f);
266 
267  return getKeypoint(i1)->handJointsTarget * (1 - f) + getKeypoint(i2)->handJointsTarget * f;
268 }
269 
271 {
272  int i1, i2;
273  float f;
274  getIndex(t, i1, i2, f);
275  return getKeypoint(i2)->feedForwardPosVelocity;
276 }
277 
279 {
280  int i1, i2;
281  float f;
282  getIndex(t, i1, i2, f);
283  return getKeypoint(i2)->feedForwardOriVelocity;
284 }
285 
287 {
288  Eigen::Vector6f ffVel;
289  ffVel.block<3, 1>(0, 0) = GetPositionDerivative(t);
290  ffVel.block<3, 1>(3, 0) = GetOrientationDerivative(t);
291  return ffVel;
292 }
293 
295 {
296  int i1, i2;
297  float f;
298  getIndex(t, i1, i2, f);
299  return getKeypoint(i2)->feedForwardHandJointsVelocity;
300 }
301 
303 {
304  return keypointMap.rbegin()->first;
305 }
306 
308 {
309  Length l;
310  for (size_t i = 1; i < keypoints.size(); i++)
311  {
312  KeypointPtr k0 = keypoints.at(i - 1);
313  KeypointPtr k1 = keypoints.at(i);
314 
315  Eigen::Vector3f pos0 = ::math::Helpers::GetPosition(k0->tcpTarget);
316  Eigen::Matrix3f ori0 = ::math::Helpers::GetOrientation(k0->tcpTarget);
317 
318  Eigen::Vector3f pos1 = ::math::Helpers::GetPosition(k1->tcpTarget);
319  Eigen::Matrix3f ori1 = ::math::Helpers::GetOrientation(k1->tcpTarget);
320 
321  l.pos += (pos1 - pos0).norm();
322  l.ori += fabs(::math::Helpers::GetAngleAxisFromTo(ori0, ori1).angle());
323  }
324  return l;
325 }
326 
328 {
329  return keypoints.at(0)->handJointsTarget.rows();
330 }
331 
332 GraspTrajectoryPtr GraspTrajectory::getTranslatedAndRotated(const Eigen::Vector3f& translation, const Eigen::Matrix3f& rotation)
333 {
334  GraspTrajectoryPtr traj(new GraspTrajectory(::math::Helpers::TranslateAndRotatePose(getKeypoint(0)->getTargetPose(), translation, rotation), getKeypoint(0)->handJointsTarget));
335  for (size_t i = 1; i < keypoints.size(); i++)
336  {
337  KeypointPtr& kp = keypoints.at(i);
338  traj->addKeypoint(::math::Helpers::TranslateAndRotatePose(kp->getTargetPose(), translation, rotation), kp->handJointsTarget, kp->dt);
339  }
340  return traj;
341 }
342 
344 {
345  GraspTrajectoryPtr traj(new GraspTrajectory(transform * getStartPose(), getKeypoint(0)->handJointsTarget));
346  for (size_t i = 1; i < keypoints.size(); i++)
347  {
348  KeypointPtr& kp = keypoints.at(i);
349  traj->addKeypoint(transform * kp->getTargetPose(), kp->handJointsTarget, kp->dt);
350  }
351  return traj;
352 }
353 
355 {
357 }
358 
360 {
361  Eigen::Matrix4f startPose = getStartPose();
362  Eigen::Vector3f targetHandForward = ::math::Helpers::TransformDirection(target, handForward);
363  Eigen::Vector3f trajHandForward = ::math::Helpers::TransformDirection(startPose, handForward);
364  Eigen::Vector3f up(0, 0, 1);
365 
366  float angle = ::math::Helpers::Angle(targetHandForward, trajHandForward, up);
367  Eigen::AngleAxisf aa(angle, up);
368 
369  Eigen::Matrix4f transform = ::math::Helpers::CreateTranslationRotationTranslationPose(-::math::Helpers::GetPosition(startPose), aa.toRotationMatrix(), ::math::Helpers::GetPosition(target));
370  return getTransformed(transform);
371 }
372 
373 SimpleDiffIK::Reachability GraspTrajectory::calculateReachability(VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr tcp, SimpleDiffIK::Parameters params)
374 {
375  return SimpleDiffIK::CalculateReachability(getAllKeypointPoses(), Eigen::VectorXf::Zero(rns->getSize()), rns, tcp, params);
376 }
377 
378 void GraspTrajectory::writeToFile(const std::string& filename)
379 {
380  RapidXmlWriter writer;
381  RapidXmlWriterNode root = writer.createRootNode("GraspTrajectory");
382  for (const KeypointPtr& keypoint : keypoints)
383  {
385  e.Add("dt", keypoint->dt);
386  e.AddAsArr("Pose", keypoint->tcpTarget);
387  e.AddAsArr("HandValues", keypoint->handJointsTarget);
388  root.append_string_node("Keypoint", e.obj->toJsonString(0, "", true));
389  }
390  writer.saveToFile(filename, true);
391 }
392 
393 GraspTrajectoryPtr GraspTrajectory::ReadFromFile(const grasping::GraspCandidatePtr& cnd)
394 {
395  std::string packageName = "armar6_skills";// cnd->executionHints->graspTrajectoryPackage;
396  armarx::CMakePackageFinder finder(packageName);
397  std::string dataDir = finder.getDataDir() + "/" + packageName;
398  return GraspTrajectory::ReadFromFile(dataDir + "/motions/grasps/" + cnd->executionHints->graspTrajectoryName + ".xml");
399 }
400 
402 {
403  RapidXmlReaderNode root = reader->getRoot("GraspTrajectory");
404  GraspTrajectoryPtr traj;
405  for (const RapidXmlReaderNode& kpNode : root.nodes("Keypoint"))
406  {
407  StructuralJsonParser p(kpNode.value());
408  p.parse();
409  JPathNavigator nav(p.parsedJson);
410  float dt = nav.selectSingleNode("dt").asFloat();
411 
412  Eigen::Matrix4f pose;
413  std::vector<JPathNavigator> rows = nav.select("Pose/*");
414  for (int i = 0; i < 4; i++)
415  {
416  std::vector<JPathNavigator> cells = rows.at(i).select("*");
417  for (int j = 0; j < 4; j++)
418  {
419  pose(i, j) = cells.at(j).asFloat();
420  }
421  }
422 
423  Eigen::Vector3f handValues;
424  std::vector<JPathNavigator> cells = nav.select("HandValues/*");
425  for (int j = 0; j < 3; j++)
426  {
427  handValues(j) = cells.at(j).asFloat();
428  }
429 
430  if (!traj)
431  {
432  traj = GraspTrajectoryPtr(new GraspTrajectory(pose, handValues));
433  }
434  else
435  {
436  traj->addKeypoint(pose, handValues, dt);
437  }
438  }
439  return traj;
440 }
441 
443 {
445 }
446 
448 {
450 }
451 
452 void GraspTrajectory::updateKeypointMap()
453 {
454  keypointMap.clear();
455  float t = 0;
456  for (size_t i = 0; i < keypoints.size(); i++)
457  {
458  t += getKeypoint(i)->dt;
459  keypointMap[t] = i;
460  }
461 }
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
Eigen
Definition: Elements.h:36
armarx::GraspTrajectory::getAllKeypointOrientations
std::vector< Eigen::Matrix3f > getAllKeypointOrientations()
Definition: GraspTrajectory.cpp:251
armarx::RapidXmlWriter
Definition: RapidXmlWriter.h:99
armarx::GraspTrajectory::calculateReachability
SimpleDiffIK::Reachability calculateReachability(VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr tcp=VirtualRobot::RobotNodePtr(), SimpleDiffIK::Parameters params=SimpleDiffIK::Parameters())
Definition: GraspTrajectory.cpp:373
armarx::SimpleJsonLoggerEntry::AddAsArr
void AddAsArr(const std::string &key, const Eigen::Vector3f &vec)
Definition: SimpleJsonLoggerEntry.cpp:34
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
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
armarx::CMakePackageFinder
The CMakePackageFinder class provides an interface to the CMake Package finder capabilities.
Definition: CMakePackageFinder.h:53
armarx::GraspTrajectory::Length::pos
float pos
Definition: GraspTrajectory.h:81
armarx::JPathNavigator
Definition: JPathNavigator.h:35
armarx::GraspTrajectory::GetTcpDerivative
Eigen::Vector6f GetTcpDerivative(float t)
Definition: GraspTrajectory.cpp:286
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::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
armarx::GraspTrajectoryPtr
std::shared_ptr< class GraspTrajectory > GraspTrajectoryPtr
Definition: GraspTrajectory.h:51
armarx::GraspTrajectory::GraspTrajectory
GraspTrajectory()=default
armarx::JPathNavigator::select
std::vector< JPathNavigator > select(const std::string &expr, bool limitToOne=false) const
Definition: JPathNavigator.cpp:101
armarx::GraspTrajectory::GetPositionDerivative
Eigen::Vector3f GetPositionDerivative(float t)
Definition: GraspTrajectory.cpp:270
armarx::GraspTrajectory::removeKeypoint
void removeKeypoint(size_t index)
Definition: GraspTrajectory.cpp:122
armarx::SimpleJsonLoggerEntry::obj
JsonObjectPtr obj
Definition: SimpleJsonLoggerEntry.h:59
armarx::GraspTrajectory::GetHandValues
Eigen::VectorXf GetHandValues(float t)
Definition: GraspTrajectory.cpp:261
armarx::GraspTrajectory::calculateLength
Length calculateLength() const
Definition: GraspTrajectory.cpp:307
armarx::CMakePackageFinder::getDataDir
std::string getDataDir() const
Definition: CMakePackageFinder.h:176
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::SimpleJsonLoggerEntry::Add
void Add(const std::string &key, const std::string &value)
Definition: SimpleJsonLoggerEntry.cpp:59
armarx::GraspTrajectory::getTransformed
GraspTrajectoryPtr getTransformed(const Eigen::Matrix4f &transform)
Definition: GraspTrajectory.cpp:343
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::RapidXmlReaderNode
Definition: RapidXmlReader.h:68
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::Length::ori
float ori
Definition: GraspTrajectory.h:82
armarx::GraspTrajectory::getTransformedToGraspPose
GraspTrajectoryPtr getTransformedToGraspPose(const Eigen::Matrix4f &target, const Eigen::Vector3f &handForward=Eigen::Vector3f::UnitZ())
Definition: GraspTrajectory.cpp:359
armarx::GraspTrajectory::Length
Definition: GraspTrajectory.h:79
ExpressionException.h
armarx::StructuralJsonParser::parse
void parse()
Definition: StructuralJsonParser.cpp:53
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:600
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::GraspTrajectory::GetHandJointCount
int GetHandJointCount() const
Definition: GraspTrajectory.cpp:327
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::RapidXmlWriter::saveToFile
void saveToFile(const std::string &path, bool indent)
Definition: RapidXmlWriter.h:126
armarx::GraspTrajectory::getKeypoint
KeypointPtr & getKeypoint(int i)
Definition: GraspTrajectory.cpp:169
armarx::GraspTrajectory::Keypoint::Keypoint
Keypoint(const Eigen::Matrix4f &tcpTarget, const Eigen::VectorXf &handJointsTarget)
Definition: GraspTrajectory.cpp:31
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::RapidXmlReaderNode::nodes
std::vector< RapidXmlReaderNode > nodes(const char *name=nullptr) const
Definition: RapidXmlReader.h:158
armarx::GraspTrajectory::GetOrientation
Eigen::Matrix3f GetOrientation(float t)
Definition: GraspTrajectory.cpp:211
armarx::RapidXmlWriter::createRootNode
RapidXmlWriterNode createRootNode(const std::string &name)
Definition: RapidXmlWriter.h:113
armarx::RapidXmlWriterNode::append_string_node
RapidXmlWriterNode & append_string_node(const std::string &name, const std::string &value)
Definition: RapidXmlWriter.h:85
angle
double angle(const Point &a, const Point &b, const Point &c)
Definition: point.hpp:100
GraspTrajectory.h
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
armarx::JPathNavigator::selectSingleNode
JPathNavigator selectSingleNode(const std::string &expr) const
Definition: JPathNavigator.cpp:110
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::JPathNavigator::asFloat
float asFloat() const
Definition: JPathNavigator.cpp:209
ARMARX_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
armarx::SimpleJsonLoggerEntry
Definition: SimpleJsonLoggerEntry.h:35
armarx::GraspTrajectory::getClone
GraspTrajectoryPtr getClone()
Definition: GraspTrajectory.cpp:354
armarx::RapidXmlWriterNode
Definition: RapidXmlWriter.h:34
armarx::StructuralJsonParser
Definition: StructuralJsonParser.h:35
armarx::StructuralJsonParser::parsedJson
JsonDataPtr parsedJson
Definition: StructuralJsonParser.h:47
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
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
norm
double norm(const Point &a)
Definition: point.hpp:94