ofkt_state_solver.cpp
Go to the documentation of this file.
1 
34 #include <console_bridge/console.h>
35 #include <boost/graph/depth_first_search.hpp>
37 
44 #include <tesseract_common/utils.h>
45 
46 #include <mutex>
47 
48 namespace tesseract_scene_graph
49 {
51 struct ofkt_builder : public boost::dfs_visitor<>
52 {
53  ofkt_builder(OFKTStateSolver& tree, std::vector<JointLimits::ConstPtr>& new_joints_limits, std::string prefix = "")
54  : tree_(tree), new_joints_limits_(new_joints_limits), prefix_(std::move(prefix))
55  {
56  }
57 
58  template <class u, class g>
59  void discover_vertex(u vertex, const g& graph)
60  {
61  // Get incoming edges
62  auto num_in_edges = static_cast<int>(boost::in_degree(vertex, graph));
63  if (num_in_edges == 0) // The root of the tree will have not incoming edges
64  return;
65 
66  boost::graph_traits<tesseract_scene_graph::Graph>::in_edge_iterator ei, ei_end;
67  boost::tie(ei, ei_end) = boost::in_edges(vertex, graph);
69  const tesseract_scene_graph::Joint::ConstPtr& joint = boost::get(boost::edge_joint, graph)[e];
70  std::string joint_name = prefix_ + joint->getName();
71  std::string parent_link_name = prefix_ + joint->parent_link_name;
72  std::string child_link_name = prefix_ + joint->child_link_name;
73 
74  tree_.addNode(*joint, joint_name, parent_link_name, child_link_name, new_joints_limits_);
75  }
76 
77 protected:
78  OFKTStateSolver& tree_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
79  std::vector<JointLimits::ConstPtr>& new_joints_limits_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
80  std::string prefix_;
81 };
82 
83 void OFKTStateSolver::cloneHelper(OFKTStateSolver& cloned, const OFKTNode* node) const
84 {
85  OFKTNode* parent_node = cloned.link_map_[node->getLinkName()];
86  for (const OFKTNode* child : node->getChildren())
87  {
88  if (child->getType() == tesseract_scene_graph::JointType::FIXED)
89  {
90  auto n = std::make_unique<OFKTFixedNode>(
91  parent_node, child->getLinkName(), child->getJointName(), child->getStaticTransformation());
92  cloned.link_map_[child->getLinkName()] = n.get();
93  parent_node->addChild(n.get());
94  cloned.nodes_[child->getJointName()] = std::move(n);
95  }
96  else if (child->getType() == tesseract_scene_graph::JointType::FLOATING)
97  {
98  auto n = std::make_unique<OFKTFloatingNode>(
99  parent_node, child->getLinkName(), child->getJointName(), child->getStaticTransformation());
100  cloned.link_map_[child->getLinkName()] = n.get();
101  parent_node->addChild(n.get());
102  cloned.nodes_[child->getJointName()] = std::move(n);
103  }
104  else if (child->getType() == tesseract_scene_graph::JointType::REVOLUTE)
105  {
106  const auto* cn = static_cast<const OFKTRevoluteNode*>(child);
107 
108  auto n = std::make_unique<OFKTRevoluteNode>(
109  parent_node, cn->getLinkName(), cn->getJointName(), cn->getStaticTransformation(), cn->getAxis());
110  n->local_tf_ = cn->getLocalTransformation();
111  n->world_tf_ = cn->getWorldTransformation();
112  n->joint_value_ = cn->getJointValue();
113 
114  cloned.link_map_[cn->getLinkName()] = n.get();
115  parent_node->addChild(n.get());
116  cloned.nodes_[cn->getJointName()] = std::move(n);
117  }
118  else if (child->getType() == tesseract_scene_graph::JointType::CONTINUOUS)
119  {
120  const auto* cn = static_cast<const OFKTContinuousNode*>(child);
121 
122  auto n = std::make_unique<OFKTContinuousNode>(
123  parent_node, cn->getLinkName(), cn->getJointName(), cn->getStaticTransformation(), cn->getAxis());
124  n->local_tf_ = cn->getLocalTransformation();
125  n->world_tf_ = cn->getWorldTransformation();
126  n->joint_value_ = cn->getJointValue();
127 
128  cloned.link_map_[cn->getLinkName()] = n.get();
129  parent_node->addChild(n.get());
130  cloned.nodes_[cn->getJointName()] = std::move(n);
131  }
132  else if (child->getType() == tesseract_scene_graph::JointType::PRISMATIC)
133  {
134  const auto* cn = static_cast<const OFKTPrismaticNode*>(child);
135 
136  auto n = std::make_unique<OFKTPrismaticNode>(
137  parent_node, cn->getLinkName(), cn->getJointName(), cn->getStaticTransformation(), cn->getAxis());
138  n->local_tf_ = cn->getLocalTransformation();
139  n->world_tf_ = cn->getWorldTransformation();
140  n->joint_value_ = cn->getJointValue();
141 
142  cloned.link_map_[cn->getLinkName()] = n.get();
143  parent_node->addChild(n.get());
144  cloned.nodes_[cn->getJointName()] = std::move(n);
145  }
146  else
147  {
148  throw std::runtime_error("Unsupported OFKTNode type!"); // LCOV_EXCL_LINE
149  }
150 
151  cloneHelper(cloned, child);
152  }
153 }
154 
155 OFKTStateSolver::OFKTStateSolver(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& prefix)
156 {
157  initHelper(scene_graph, prefix);
158 }
159 
160 OFKTStateSolver::OFKTStateSolver(const std::string& root_name)
161 {
162  root_ = std::make_unique<OFKTRootNode>(root_name);
163  link_map_[root_name] = root_.get();
164  link_names_ = { root_name };
165  current_state_.link_transforms[root_name] = root_->getWorldTransformation();
166 }
167 
168 OFKTStateSolver::OFKTStateSolver(const OFKTStateSolver& other) { *this = other; }
169 
171 {
173  joint_names_ = other.joint_names_;
176  link_names_ = other.link_names_;
177  root_ = std::make_unique<OFKTRootNode>(other.root_->getLinkName());
178  link_map_[other.root_->getLinkName()] = root_.get();
179  limits_ = other.limits_;
180  revision_ = other.revision_;
181  cloneHelper(*this, other.root_.get());
182  return *this;
183 }
184 
186 {
187  std::shared_lock<std::shared_mutex> lock(mutex_);
188  return std::make_unique<OFKTStateSolver>(*this);
189 }
190 
192 {
193  std::unique_lock<std::shared_mutex> lock(mutex_);
194  revision_ = revision;
195 }
196 
198 {
199  std::shared_lock<std::shared_mutex> lock(mutex_);
200  return revision_;
201 }
202 
204 {
205  std::unique_lock<std::shared_mutex> lock(mutex_);
206 
208  joint_names_.clear();
209  active_joint_names_.clear();
210  floating_joint_names_.clear();
211  link_names_.clear();
212  nodes_.clear();
213  link_map_.clear();
215  root_ = nullptr;
216 }
217 
218 void OFKTStateSolver::setState(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
219  const tesseract_common::TransformMap& floating_joint_values)
220 {
221  std::unique_lock<std::shared_mutex> lock(mutex_);
222  assert(active_joint_names_.size() == static_cast<std::size_t>(joint_values.size()));
223  for (std::size_t i = 0; i < active_joint_names_.size(); ++i)
224  {
225  nodes_[active_joint_names_[i]]->storeJointValue(joint_values(static_cast<long>(i)));
226  current_state_.joints[active_joint_names_[i]] = joint_values(static_cast<long>(i));
227  }
228 
229  for (const auto& floating_joint_value : floating_joint_values)
230  {
231  current_state_.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
232  nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
233  }
234 
235  update(root_.get(), false);
236 }
237 
238 void OFKTStateSolver::setState(const std::unordered_map<std::string, double>& joint_values,
239  const tesseract_common::TransformMap& floating_joint_values)
240 {
241  std::unique_lock<std::shared_mutex> lock(mutex_);
242 
243  for (const auto& joint : joint_values)
244  {
245  nodes_[joint.first]->storeJointValue(joint.second);
246  current_state_.joints[joint.first] = joint.second;
247  }
248 
249  for (const auto& floating_joint_value : floating_joint_values)
250  {
251  current_state_.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
252  nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
253  }
254 
255  update(root_.get(), false);
256 }
257 
258 void OFKTStateSolver::setState(const std::vector<std::string>& joint_names,
259  const Eigen::Ref<const Eigen::VectorXd>& joint_values,
260  const tesseract_common::TransformMap& floating_joint_values)
261 {
262  std::unique_lock<std::shared_mutex> lock(mutex_);
263  assert(joint_names.size() == static_cast<std::size_t>(joint_values.size()));
264  Eigen::VectorXd jv = joint_values;
265  for (std::size_t i = 0; i < joint_names.size(); ++i)
266  {
267  nodes_[joint_names[i]]->storeJointValue(joint_values(static_cast<long>(i)));
268  current_state_.joints[joint_names[i]] = joint_values(static_cast<long>(i));
269  }
270 
271  for (const auto& floating_joint_value : floating_joint_values)
272  {
273  current_state_.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
274  nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
275  }
276 
277  update(root_.get(), false);
278 }
279 
281 {
282  std::unique_lock<std::shared_mutex> lock(mutex_);
283  for (const auto& floating_joint_value : floating_joint_values)
284  {
285  current_state_.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
286  nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
287  }
288 
289  update(root_.get(), false);
290 }
291 
292 SceneState OFKTStateSolver::getState(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
293  const tesseract_common::TransformMap& floating_joint_values) const
294 {
295  std::shared_lock<std::shared_mutex> lock(mutex_);
296  assert(static_cast<Eigen::Index>(active_joint_names_.size()) == joint_values.size());
297  auto state = SceneState(current_state_);
298  for (std::size_t i = 0; i < active_joint_names_.size(); ++i)
299  state.joints[active_joint_names_[i]] = joint_values[static_cast<long>(i)];
300 
301  for (const auto& floating_joint_value : floating_joint_values)
302  state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
303 
304  update(state, root_.get(), Eigen::Isometry3d::Identity(), false);
305  return state;
306 }
307 
308 SceneState OFKTStateSolver::getState(const std::unordered_map<std::string, double>& joint_values,
309  const tesseract_common::TransformMap& floating_joint_values) const
310 {
311  auto state = SceneState(current_state_);
312  for (const auto& joint : joint_values)
313  state.joints[joint.first] = joint.second;
314 
315  for (const auto& floating_joint_value : floating_joint_values)
316  state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
317 
318  update(state, root_.get(), Eigen::Isometry3d::Identity(), false);
319  return state;
320 }
321 
322 SceneState OFKTStateSolver::getState(const std::vector<std::string>& joint_names,
323  const Eigen::Ref<const Eigen::VectorXd>& joint_values,
324  const tesseract_common::TransformMap& floating_joint_values) const
325 {
326  std::shared_lock<std::shared_mutex> lock(mutex_);
327  assert(static_cast<Eigen::Index>(joint_names.size()) == joint_values.size());
328  auto state = SceneState(current_state_);
329  for (std::size_t i = 0; i < joint_names.size(); ++i)
330  state.joints[joint_names[i]] = joint_values[static_cast<long>(i)];
331 
332  for (const auto& floating_joint_value : floating_joint_values)
333  state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
334 
335  update(state, root_.get(), Eigen::Isometry3d::Identity(), false);
336  return state;
337 }
338 
340 {
341  std::shared_lock<std::shared_mutex> lock(mutex_);
342  auto state = SceneState(current_state_);
343  for (const auto& floating_joint_value : floating_joint_values)
344  state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
345 
346  update(state, root_.get(), Eigen::Isometry3d::Identity(), false);
347  return state;
348 }
349 
351 {
352  std::shared_lock<std::shared_mutex> lock(mutex_);
353  return current_state_;
354 }
355 
357 {
358  std::shared_lock<std::shared_mutex> lock(mutex_);
360 }
361 
362 Eigen::MatrixXd OFKTStateSolver::getJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
363  const std::string& link_name,
364  const tesseract_common::TransformMap& floating_joint_values) const
365 {
366  std::shared_lock<std::shared_mutex> lock(mutex_);
367  std::unordered_map<std::string, double> joints = current_state_.joints;
368  for (Eigen::Index i = 0; i < joint_values.rows(); ++i)
369  joints[active_joint_names_[static_cast<std::size_t>(i)]] = joint_values[i];
370 
372  for (const auto& floating_joint_value : floating_joint_values)
373  floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
374 
375  return calcJacobianHelper(joints, link_name, floating_joints);
376 }
377 
378 Eigen::MatrixXd OFKTStateSolver::getJacobian(const std::unordered_map<std::string, double>& joints_values,
379  const std::string& link_name,
380  const tesseract_common::TransformMap& floating_joint_values) const
381 {
382  std::shared_lock<std::shared_mutex> lock(mutex_);
383  std::unordered_map<std::string, double> joints = current_state_.joints;
384  for (const auto& joint : joints_values)
385  joints[joint.first] = joint.second;
386 
388  for (const auto& floating_joint_value : floating_joint_values)
389  floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
390 
391  return calcJacobianHelper(joints, link_name, floating_joints);
392 }
393 
394 Eigen::MatrixXd OFKTStateSolver::getJacobian(const std::vector<std::string>& joint_names,
395  const Eigen::Ref<const Eigen::VectorXd>& joint_values,
396  const std::string& link_name,
397  const tesseract_common::TransformMap& floating_joint_values) const
398 {
399  std::shared_lock<std::shared_mutex> lock(mutex_);
400  std::unordered_map<std::string, double> joints = current_state_.joints;
401  for (Eigen::Index i = 0; i < joint_values.rows(); ++i)
402  joints[joint_names[static_cast<std::size_t>(i)]] = joint_values[i];
403 
405  for (const auto& floating_joint_value : floating_joint_values)
406  floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
407 
408  return calcJacobianHelper(joints, link_name, floating_joints);
409 }
410 
411 Eigen::MatrixXd OFKTStateSolver::calcJacobianHelper(const std::unordered_map<std::string, double>& joints,
412  const std::string& link_name,
413  const tesseract_common::TransformMap& floating_joint_values) const
414 {
415  OFKTNode* node = link_map_.at(link_name);
416  Eigen::MatrixXd jacobian = Eigen::MatrixXd::Zero(6, static_cast<Eigen::Index>(active_joint_names_.size()));
417 
418  Eigen::Isometry3d total_tf{ Eigen::Isometry3d::Identity() };
419  while (node != root_.get())
420  {
421  if (node->getType() == JointType::FIXED)
422  {
423  total_tf = node->getLocalTransformation() * total_tf;
424  }
425  else if (node->getType() == JointType::FLOATING)
426  {
427  total_tf = floating_joint_values.at(node->getJointName()) * total_tf;
428  }
429  else
430  {
431  Eigen::Isometry3d local_tf = node->computeLocalTransformation(joints.at(node->getJointName()));
432  total_tf = local_tf * total_tf;
433 
434  Eigen::Index idx =
435  std::distance(active_joint_names_.begin(),
436  std::find(active_joint_names_.begin(), active_joint_names_.end(), node->getJointName()));
437  Eigen::VectorXd twist = node->getLocalTwist();
438  tesseract_common::twistChangeRefPoint(twist, total_tf.translation() - local_tf.translation());
439  tesseract_common::twistChangeBase(twist, total_tf.inverse());
440  jacobian.col(idx) = twist;
441  }
442 
443  node = node->getParent();
444  }
445 
446  tesseract_common::jacobianChangeBase(jacobian, total_tf);
447  return jacobian;
448 }
449 
450 std::vector<std::string> OFKTStateSolver::getJointNames() const
451 {
452  std::shared_lock<std::shared_mutex> lock(mutex_);
453  return joint_names_;
454 }
455 
456 std::vector<std::string> OFKTStateSolver::getFloatingJointNames() const
457 {
458  std::shared_lock<std::shared_mutex> lock(mutex_);
459  return floating_joint_names_;
460 }
461 
462 std::vector<std::string> OFKTStateSolver::getActiveJointNames() const
463 {
464  std::shared_lock<std::shared_mutex> lock(mutex_);
465  return active_joint_names_;
466 }
467 
469 {
470  std::shared_lock<std::shared_mutex> lock(mutex_);
471  return root_->getLinkName();
472 }
473 
474 std::vector<std::string> OFKTStateSolver::getLinkNames() const
475 {
476  std::shared_lock<std::shared_mutex> lock(mutex_);
477  return link_names_;
478 }
479 
480 std::vector<std::string> OFKTStateSolver::getActiveLinkNames() const
481 {
482  std::shared_lock<std::shared_mutex> lock(mutex_);
483  std::vector<std::string> link_names;
484  link_names.reserve(nodes_.size());
485  loadActiveLinkNamesRecursive(link_names, root_.get(), false);
486  return link_names;
487 }
488 
489 std::vector<std::string> OFKTStateSolver::getStaticLinkNames() const
490 {
491  std::shared_lock<std::shared_mutex> lock(mutex_);
492  std::vector<std::string> link_names;
493  link_names.reserve(nodes_.size());
494  loadStaticLinkNamesRecursive(link_names, root_.get());
495  return link_names;
496 }
497 
498 bool OFKTStateSolver::isActiveLinkName(const std::string& link_name) const
499 {
500  std::shared_lock<std::shared_mutex> lock(mutex_);
501  std::vector<std::string> active_link_names = getActiveLinkNames();
502  return (std::find(active_link_names.begin(), active_link_names.end(), link_name) != active_link_names.end());
503 }
504 
505 bool OFKTStateSolver::hasLinkName(const std::string& link_name) const
506 {
507  std::shared_lock<std::shared_mutex> lock(mutex_);
508  return (std::find(link_names_.begin(), link_names_.end(), link_name) != link_names_.end());
509 }
510 
512 {
514  link_tfs.reserve(current_state_.link_transforms.size());
515  for (const auto& link_name : link_names_)
516  link_tfs.push_back(current_state_.link_transforms.at(link_name));
517 
518  return link_tfs;
519 }
520 
521 Eigen::Isometry3d OFKTStateSolver::getLinkTransform(const std::string& link_name) const
522 {
523  return current_state_.link_transforms.at(link_name);
524 }
525 
526 Eigen::Isometry3d OFKTStateSolver::getRelativeLinkTransform(const std::string& from_link_name,
527  const std::string& to_link_name) const
528 {
529  return current_state_.link_transforms.at(from_link_name).inverse() * current_state_.link_transforms.at(to_link_name);
530 }
531 
533 {
534  std::shared_lock<std::shared_mutex> lock(mutex_);
535  return limits_;
536 }
537 
538 bool OFKTStateSolver::addLink(const Link& link, const Joint& joint)
539 {
540  std::unique_lock<std::shared_mutex> lock(mutex_);
541  if (link_map_.find(link.getName()) != link_map_.end())
542  {
543  return false;
544  }
545 
546  if (nodes_.find(joint.getName()) != nodes_.end())
547  {
548  return false;
549  }
550 
551  std::vector<JointLimits::ConstPtr> new_joint_limits;
552  addNode(joint, joint.getName(), joint.parent_link_name, joint.child_link_name, new_joint_limits);
553  addNewJointLimits(new_joint_limits);
554 
555  update(root_.get(), false);
556 
557  return true;
558 }
559 
566 {
567  std::unique_lock<std::shared_mutex> lock(mutex_);
568  auto it = nodes_.find(joint.getName());
569  if (it == nodes_.end())
570  {
571  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to replace joint '%s' which does not exist!",
572  joint.getName().c_str());
573  return false;
574  }
575 
576  if (link_map_.find(joint.parent_link_name) == link_map_.end())
577  {
578  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to replace joint '%s' with parent link name that does not exist!",
579  joint.getName().c_str());
580  return false;
581  }
582 
583  if (it->second->getLinkName() != joint.child_link_name)
584  {
585  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to replace joint '%s' with different child link name!",
586  joint.getName().c_str());
587  return false;
588  }
589 
590  std::vector<JointLimits::ConstPtr> new_joint_limits;
591  replaceJointHelper(new_joint_limits, joint);
592  addNewJointLimits(new_joint_limits);
593 
594  update(root_.get(), false);
595 
596  return true;
597 }
598 
600 {
601  std::unique_lock<std::shared_mutex> lock(mutex_);
602 
603  if (link_map_.find(joint.child_link_name) == link_map_.end())
604  {
605  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to link '%s' that does not exist!", joint.child_link_name.c_str());
606  return false;
607  }
608 
609  if (link_map_.find(joint.parent_link_name) == link_map_.end())
610  {
611  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to move link to parent link '%s' that does not exist!",
612  joint.parent_link_name.c_str());
613  return false;
614  }
615 
616  std::vector<JointLimits::ConstPtr> new_joint_limits;
617  moveLinkHelper(new_joint_limits, joint);
618  addNewJointLimits(new_joint_limits);
619 
620  update(root_.get(), false);
621 
622  return true;
623 }
624 
625 bool OFKTStateSolver::removeLink(const std::string& name)
626 {
627  std::unique_lock<std::shared_mutex> lock(mutex_);
628  auto it = link_map_.find(name);
629  if (it == link_map_.end())
630  {
631  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to remove link '%s' which does not exist!", name.c_str());
632  return false;
633  }
634 
635  std::vector<std::string> removed_links;
636  removed_links.reserve(nodes_.size());
637 
638  std::vector<std::string> removed_joints;
639  removed_joints.reserve(nodes_.size());
640 
641  std::vector<std::string> removed_active_joints;
642  removed_active_joints.reserve(nodes_.size());
643 
644  std::vector<long> removed_active_joints_indices;
645  removed_active_joints_indices.reserve(nodes_.size());
646 
647  removeNode(it->second, removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
648 
649  // Remove deleted joints
650  removeJointHelper(removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
651 
652  update(root_.get(), false);
653 
654  return true;
655 }
656 
657 bool OFKTStateSolver::removeJoint(const std::string& name)
658 {
659  std::unique_lock<std::shared_mutex> lock(mutex_);
660  auto it = nodes_.find(name);
661  if (it == nodes_.end())
662  {
663  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to remove joint '%s' which does not exist!", name.c_str());
664  return false;
665  }
666 
667  std::vector<std::string> removed_links;
668  removed_links.reserve(nodes_.size());
669 
670  std::vector<std::string> removed_joints;
671  removed_joints.reserve(nodes_.size());
672 
673  std::vector<std::string> removed_active_joints;
674  removed_active_joints.reserve(nodes_.size());
675 
676  std::vector<long> removed_active_joints_indices;
677  removed_active_joints_indices.reserve(nodes_.size());
678 
679  removeNode(it->second.get(), removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
680 
681  // Remove deleted joints
682  removeJointHelper(removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
683 
684  update(root_.get(), false);
685 
686  return true;
687 }
688 
689 bool OFKTStateSolver::moveJoint(const std::string& name, const std::string& parent_link)
690 {
691  std::unique_lock<std::shared_mutex> lock(mutex_);
692  auto it = nodes_.find(name);
693  if (it == nodes_.end())
694  {
695  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to move joint '%s' which does not exist!", name.c_str());
696  return false;
697  }
698 
699  if (link_map_.find(parent_link) == link_map_.end())
700  {
701  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to move joint '%s' to parent link '%s' which does not exist!",
702  name.c_str(),
703  parent_link.c_str());
704  return false;
705  }
706 
707  auto& n = it->second;
708  n->getParent()->removeChild(n.get());
709  OFKTNode* new_parent = link_map_[parent_link];
710  n->setParent(new_parent);
711  new_parent->addChild(n.get());
712 
713  update(root_.get(), false);
714 
715  return true;
716 }
717 
718 bool OFKTStateSolver::changeJointOrigin(const std::string& name, const Eigen::Isometry3d& new_origin)
719 {
720  std::unique_lock<std::shared_mutex> lock(mutex_);
721  auto it = nodes_.find(name);
722  if (it == nodes_.end())
723  {
724  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to change joint '%s' origin which does not exist!", name.c_str());
725  return false;
726  }
727 
728  it->second->setStaticTransformation(new_origin);
729  if (it->second->getType() == JointType::FLOATING)
730  current_state_.floating_joints[name] = new_origin;
731 
732  update(root_.get(), false);
733 
734  return true;
735 }
736 
737 bool OFKTStateSolver::changeJointPositionLimits(const std::string& name, double lower, double upper)
738 {
739  std::unique_lock<std::shared_mutex> lock(mutex_);
740  auto it = nodes_.find(name);
741  if (it == nodes_.end())
742  {
743  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
744  name.c_str());
745  return false;
746  }
747 
748  long idx = std::distance(active_joint_names_.begin(),
749  std::find(active_joint_names_.begin(), active_joint_names_.end(), name));
750  limits_.joint_limits(idx, 0) = lower;
751  limits_.joint_limits(idx, 1) = upper;
752  return true;
753 }
754 
755 bool OFKTStateSolver::changeJointVelocityLimits(const std::string& name, double limit)
756 {
757  std::unique_lock<std::shared_mutex> lock(mutex_);
758  auto it = nodes_.find(name);
759  if (it == nodes_.end())
760  {
761  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
762  name.c_str());
763  return false;
764  }
765 
766  long idx = std::distance(active_joint_names_.begin(),
767  std::find(active_joint_names_.begin(), active_joint_names_.end(), name));
768  limits_.velocity_limits(idx, 0) = -limit;
769  limits_.velocity_limits(idx, 1) = limit;
770  return true;
771 }
772 
773 bool OFKTStateSolver::changeJointAccelerationLimits(const std::string& name, double limit)
774 {
775  std::unique_lock<std::shared_mutex> lock(mutex_);
776  auto it = nodes_.find(name);
777  if (it == nodes_.end())
778  {
779  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
780  name.c_str());
781  return false;
782  }
783 
784  long idx = std::distance(active_joint_names_.begin(),
785  std::find(active_joint_names_.begin(), active_joint_names_.end(), name));
786  limits_.acceleration_limits(idx, 0) = -limit;
787  limits_.acceleration_limits(idx, 1) = limit;
788  return true;
789 }
790 
791 bool OFKTStateSolver::changeJointJerkLimits(const std::string& name, double limit)
792 {
793  std::unique_lock<std::shared_mutex> lock(mutex_);
794  auto it = nodes_.find(name);
795  if (it == nodes_.end())
796  {
797  CONSOLE_BRIDGE_logError("OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
798  name.c_str());
799  return false;
800  }
801 
802  long idx = std::distance(active_joint_names_.begin(),
803  std::find(active_joint_names_.begin(), active_joint_names_.end(), name));
804  limits_.jerk_limits(idx, 0) = -limit;
805  limits_.jerk_limits(idx, 1) = limit;
806  return true;
807 }
808 
809 bool OFKTStateSolver::insertSceneGraph(const SceneGraph& scene_graph, const Joint& joint, const std::string& prefix)
810 {
811  std::unique_lock<std::shared_mutex> lock(mutex_);
812  if (root_ == nullptr)
813  return false; // LCOV_EXCL_LINE
814 
815  std::string parent_link = joint.parent_link_name;
816  std::string child_link = joint.child_link_name;
817 
818  // Assumes the joint already contains the prefix in the parent and child link names
819  if (!prefix.empty())
820  child_link.erase(0, prefix.length());
821 
822  if (link_map_.find(parent_link) == link_map_.end() || scene_graph.getLink(child_link) == nullptr)
823  {
824  CONSOLE_BRIDGE_logError("OFKTStateSolver, Failed to add inserted graph, provided joint link names do not exist in "
825  "inserted graph!");
826  return false;
827  }
828 
829  if (nodes_.find(joint.getName()) != nodes_.end())
830  {
831  CONSOLE_BRIDGE_logError("OFKTStateSolver, Failed to add inserted graph, provided joint name %s already exists!",
832  joint.getName().c_str());
833  return false;
834  }
835 
836  std::vector<JointLimits::ConstPtr> new_joints_limits;
837  new_joints_limits.reserve(boost::num_edges(scene_graph));
838 
839  addNode(joint, joint.getName(), joint.parent_link_name, joint.child_link_name, new_joints_limits);
840 
841  ofkt_builder builder(*this, new_joints_limits, prefix);
842 
843  std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t> index_map;
844  boost::associative_property_map<std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t>> prop_index_map(
845  index_map);
846 
847  int c = 0;
848  tesseract_scene_graph::Graph::vertex_iterator i, iend;
849  for (boost::tie(i, iend) = boost::vertices(scene_graph); i != iend; ++i, ++c)
850  boost::put(prop_index_map, *i, c);
851 
852  boost::depth_first_search(static_cast<const tesseract_scene_graph::Graph&>(scene_graph),
853  boost::visitor(builder)
854  .root_vertex(scene_graph.getVertex(scene_graph.getRoot()))
855  .vertex_index_map(prop_index_map));
856 
857  // Populate Joint Limits
858  addNewJointLimits(new_joints_limits);
859 
860  update(root_.get(), false);
861  return true;
862 }
863 
864 void OFKTStateSolver::loadActiveLinkNamesRecursive(std::vector<std::string>& active_link_names,
865  const OFKTNode* node,
866  bool active) const
867 {
868  if (active)
869  {
870  active_link_names.push_back(node->getLinkName());
871  for (const auto* child : node->getChildren())
872  loadActiveLinkNamesRecursive(active_link_names, child, active);
873  }
874  else
875  {
878  {
879  for (const auto* child : node->getChildren())
880  loadActiveLinkNamesRecursive(active_link_names, child, active);
881  }
882  else
883  {
884  active_link_names.push_back(node->getLinkName());
885  for (const auto* child : node->getChildren())
886  loadActiveLinkNamesRecursive(active_link_names, child, true);
887  }
888  }
889 }
890 
891 void OFKTStateSolver::loadStaticLinkNamesRecursive(std::vector<std::string>& static_link_names,
892  const OFKTNode* node) const
893 {
896  {
897  static_link_names.push_back(node->getLinkName());
898  for (const auto* child : node->getChildren())
899  loadStaticLinkNamesRecursive(static_link_names, child);
900  }
901 }
902 
903 void OFKTStateSolver::update(OFKTNode* node, bool update_required)
904 {
905  if (node->hasJointValueChanged())
906  {
908  update_required = true;
909  }
910 
912  update_required = true;
913 
914  if (update_required)
915  {
919  }
920 
921  for (auto* child : node->getChildren())
922  update(child, update_required);
923 }
924 
926  const OFKTNode* node,
927  const Eigen::Isometry3d& parent_world_tf,
928  bool update_required) const
929 {
930  Eigen::Isometry3d updated_parent_world_tf{ Eigen::Isometry3d::Identity() };
932  {
933  updated_parent_world_tf = parent_world_tf * node->getLocalTransformation();
934  }
936  {
937  const auto& tf = state.floating_joints.at(node->getJointName());
938  updated_parent_world_tf = parent_world_tf * tf;
939  if (!tf.isApprox(node->getLocalTransformation(), 1e-8))
940  update_required = true;
941  }
942  else
943  {
944  double jv = state.joints[node->getJointName()];
946  {
947  updated_parent_world_tf = parent_world_tf * node->computeLocalTransformation(jv);
948  update_required = true;
949  }
950  else
951  {
952  updated_parent_world_tf = parent_world_tf * node->getLocalTransformation();
953  }
954  }
955 
956  if (update_required)
957  {
958  state.link_transforms[node->getLinkName()] = updated_parent_world_tf;
959  state.joint_transforms[node->getJointName()] = updated_parent_world_tf;
960  }
961 
962  for (const auto* child : node->getChildren())
963  update(state, child, updated_parent_world_tf, update_required);
964 }
965 
966 bool OFKTStateSolver::initHelper(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& prefix)
967 {
968  clear();
969 
970  if (scene_graph.isEmpty())
971  return true;
972 
973  assert(scene_graph.isTree());
974 
975  const std::string& root_name = prefix + scene_graph.getRoot();
976 
977  root_ = std::make_unique<OFKTRootNode>(root_name);
978  link_map_[root_name] = root_.get();
979  current_state_.link_transforms[root_name] = root_->getWorldTransformation();
980  link_names_.push_back(root_name);
981 
982  std::vector<JointLimits::ConstPtr> new_joints_limits;
983  new_joints_limits.reserve(scene_graph.getJoints().size());
984  ofkt_builder builder(*this, new_joints_limits, prefix);
985 
986  std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t> index_map;
987  boost::associative_property_map<std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t>> prop_index_map(
988  index_map);
989 
990  int c = 0;
991  tesseract_scene_graph::Graph::vertex_iterator i, iend;
992  for (boost::tie(i, iend) = boost::vertices(scene_graph); i != iend; ++i, ++c)
993  boost::put(prop_index_map, *i, c);
994 
995  boost::depth_first_search(
996  static_cast<const tesseract_scene_graph::Graph&>(scene_graph),
997  boost::visitor(builder).root_vertex(scene_graph.getVertex(root_name)).vertex_index_map(prop_index_map));
998 
999  // Populate Joint Limits
1000  addNewJointLimits(new_joints_limits);
1001 
1002  // Update transforms
1003  update(root_.get(), false);
1004 
1005  return true;
1006 }
1007 
1008 void OFKTStateSolver::moveLinkHelper(std::vector<std::shared_ptr<const JointLimits>>& new_joint_limits,
1009  const Joint& joint)
1010 {
1011  auto* old_node = link_map_[joint.child_link_name];
1012  const std::string old_joint_name = old_node->getJointName();
1013  old_node->getParent()->removeChild(old_node);
1014 
1015  auto it = std::find(active_joint_names_.begin(), active_joint_names_.end(), old_joint_name);
1016  std::vector<std::string> removed_links;
1017  removed_links.push_back(joint.child_link_name);
1018 
1019  std::vector<std::string> removed_joints;
1020  std::vector<std::string> removed_active_joints;
1021  std::vector<long> removed_active_joints_indices;
1022  removed_joints.push_back(old_joint_name);
1023  if (it != active_joint_names_.end())
1024  {
1025  removed_active_joints.push_back(old_joint_name);
1026  removed_active_joints_indices.push_back(std::distance(active_joint_names_.begin(), it));
1027  }
1028 
1029  // store to add to new node
1030  std::vector<OFKTNode*> children = old_node->getChildren();
1031 
1032  // erase node
1033  nodes_.erase(old_joint_name);
1034  removeJointHelper(removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
1035  current_state_.joints.erase(old_joint_name);
1036  current_state_.floating_joints.erase(old_joint_name);
1037  current_state_.joint_transforms.erase(old_joint_name);
1038 
1039  addNode(joint, joint.getName(), joint.parent_link_name, joint.child_link_name, new_joint_limits);
1040 
1041  auto& replaced_node = nodes_[joint.getName()];
1042 
1043  // add back original nodes children and update parents
1044  for (auto* child : children)
1045  {
1046  replaced_node->addChild(child);
1047  child->setParent(replaced_node.get());
1048  }
1049 
1050  update(replaced_node.get(), true);
1051 }
1052 
1053 void OFKTStateSolver::replaceJointHelper(std::vector<std::shared_ptr<const JointLimits>>& new_joint_limits,
1054  const Joint& joint)
1055 {
1056  auto& n = nodes_[joint.getName()];
1057 
1058  if (n->getType() == joint.type && n->getParent()->getLinkName() == joint.parent_link_name)
1059  {
1060  n->getParent()->removeChild(n.get());
1061  n->setStaticTransformation(joint.parent_to_joint_origin_transform);
1062  if (n->getType() == JointType::FLOATING)
1064 
1065  OFKTNode* new_parent = link_map_[joint.parent_link_name];
1066  n->setParent(new_parent);
1067  new_parent->addChild(n.get());
1068  }
1069  else
1070  {
1071  moveLinkHelper(new_joint_limits, joint);
1072  }
1073 }
1074 
1075 void OFKTStateSolver::removeJointHelper(const std::vector<std::string>& removed_links,
1076  const std::vector<std::string>& removed_joints,
1077  const std::vector<std::string>& removed_active_joints,
1078  const std::vector<long>& removed_active_joints_indices)
1079 {
1080  if (!removed_links.empty())
1081  {
1082  link_names_.erase(std::remove_if(link_names_.begin(),
1083  link_names_.end(),
1084  [removed_links](const std::string& link_name) {
1085  return (std::find(removed_links.begin(), removed_links.end(), link_name) !=
1086  removed_links.end());
1087  }),
1088  link_names_.end());
1089  }
1090 
1091  if (!removed_joints.empty())
1092  {
1093  joint_names_.erase(std::remove_if(joint_names_.begin(),
1094  joint_names_.end(),
1095  [removed_joints](const std::string& joint_name) {
1096  return (std::find(removed_joints.begin(), removed_joints.end(), joint_name) !=
1097  removed_joints.end());
1098  }),
1099  joint_names_.end());
1100 
1101  floating_joint_names_.erase(std::remove_if(floating_joint_names_.begin(),
1102  floating_joint_names_.end(),
1103  [removed_joints](const std::string& joint_name) {
1104  return (std::find(removed_joints.begin(),
1105  removed_joints.end(),
1106  joint_name) != removed_joints.end());
1107  }),
1108  floating_joint_names_.end());
1109  }
1110 
1111  if (!removed_active_joints.empty())
1112  {
1113  active_joint_names_.erase(std::remove_if(active_joint_names_.begin(),
1114  active_joint_names_.end(),
1115  [removed_active_joints](const std::string& joint_name) {
1116  return (std::find(removed_active_joints.begin(),
1117  removed_active_joints.end(),
1118  joint_name) != removed_active_joints.end());
1119  }),
1120  active_joint_names_.end());
1121 
1123  l1.joint_limits.resize(static_cast<long int>(active_joint_names_.size()), 2);
1124  l1.velocity_limits.resize(static_cast<long int>(active_joint_names_.size()), 2);
1125  l1.acceleration_limits.resize(static_cast<long int>(active_joint_names_.size()), 2);
1126  l1.jerk_limits.resize(static_cast<long int>(active_joint_names_.size()), 2);
1127 
1128  long cnt = 0;
1129  for (long i = 0; i < limits_.joint_limits.rows(); ++i)
1130  {
1131  if (std::find(removed_active_joints_indices.begin(), removed_active_joints_indices.end(), i) ==
1132  removed_active_joints_indices.end())
1133  {
1134  l1.joint_limits.row(cnt) = limits_.joint_limits.row(i);
1135  l1.velocity_limits.row(cnt) = limits_.velocity_limits.row(i);
1136  l1.acceleration_limits.row(cnt) = limits_.acceleration_limits.row(i);
1137  l1.jerk_limits.row(cnt) = limits_.jerk_limits.row(i);
1138  ++cnt;
1139  }
1140  }
1141 
1142  limits_ = l1;
1143  }
1144 }
1145 
1147  const std::string& joint_name,
1148  const std::string& parent_link_name,
1149  const std::string& child_link_name,
1150  std::vector<std::shared_ptr<const JointLimits>>& new_joint_limits)
1151 {
1152  switch (joint.type)
1153  {
1155  {
1156  OFKTNode* parent_node = link_map_[parent_link_name];
1157  assert(parent_node != nullptr);
1158  auto n = std::make_unique<OFKTFixedNode>(
1159  parent_node, child_link_name, joint_name, joint.parent_to_joint_origin_transform);
1160  link_map_[child_link_name] = n.get();
1161  parent_node->addChild(n.get());
1162  current_state_.link_transforms[n->getLinkName()] = n->getWorldTransformation();
1163  current_state_.joint_transforms[n->getJointName()] = n->getWorldTransformation();
1164  joint_names_.push_back(joint_name);
1165  link_names_.push_back(n->getLinkName());
1166  nodes_[joint_name] = std::move(n);
1167  break;
1168  }
1170  {
1171  OFKTNode* parent_node = link_map_[parent_link_name];
1172  assert(parent_node != nullptr);
1173  auto n = std::make_unique<OFKTRevoluteNode>(
1174  parent_node, child_link_name, joint_name, joint.parent_to_joint_origin_transform, joint.axis);
1175  link_map_[child_link_name] = n.get();
1176  parent_node->addChild(n.get());
1177  current_state_.joints[joint_name] = 0;
1178  current_state_.link_transforms[n->getLinkName()] = n->getWorldTransformation();
1179  current_state_.joint_transforms[n->getJointName()] = n->getWorldTransformation();
1180  joint_names_.push_back(joint_name);
1181  active_joint_names_.push_back(joint_name);
1182  link_names_.push_back(n->getLinkName());
1183  new_joint_limits.push_back(joint.limits);
1184  nodes_[joint_name] = std::move(n);
1185  break;
1186  }
1188  {
1189  OFKTNode* parent_node = link_map_[parent_link_name];
1190  assert(parent_node != nullptr);
1191  auto n = std::make_unique<OFKTContinuousNode>(
1192  parent_node, child_link_name, joint_name, joint.parent_to_joint_origin_transform, joint.axis);
1193  link_map_[child_link_name] = n.get();
1194  parent_node->addChild(n.get());
1195  current_state_.joints[joint_name] = 0;
1196  current_state_.link_transforms[n->getLinkName()] = n->getWorldTransformation();
1197  current_state_.joint_transforms[n->getJointName()] = n->getWorldTransformation();
1198  joint_names_.push_back(joint_name);
1199  active_joint_names_.push_back(joint_name);
1200  link_names_.push_back(n->getLinkName());
1201  new_joint_limits.push_back(joint.limits);
1202  nodes_[joint_name] = std::move(n);
1203  break;
1204  }
1206  {
1207  OFKTNode* parent_node = link_map_[parent_link_name];
1208  assert(parent_node != nullptr);
1209  auto n = std::make_unique<OFKTPrismaticNode>(
1210  parent_node, child_link_name, joint_name, joint.parent_to_joint_origin_transform, joint.axis);
1211  link_map_[child_link_name] = n.get();
1212  parent_node->addChild(n.get());
1213  current_state_.joints[joint_name] = 0;
1214  current_state_.link_transforms[n->getLinkName()] = n->getWorldTransformation();
1215  current_state_.joint_transforms[n->getJointName()] = n->getWorldTransformation();
1216  joint_names_.push_back(joint_name);
1217  active_joint_names_.push_back(joint_name);
1218  link_names_.push_back(n->getLinkName());
1219  new_joint_limits.push_back(joint.limits);
1220  nodes_[joint_name] = std::move(n);
1221  break;
1222  }
1224  {
1225  OFKTNode* parent_node = link_map_[parent_link_name];
1226  assert(parent_node != nullptr);
1227  auto n = std::make_unique<OFKTFloatingNode>(
1228  parent_node, child_link_name, joint_name, joint.parent_to_joint_origin_transform);
1229  link_map_[child_link_name] = n.get();
1230  parent_node->addChild(n.get());
1231  current_state_.link_transforms[n->getLinkName()] = n->getWorldTransformation();
1232  current_state_.joint_transforms[n->getJointName()] = n->getWorldTransformation();
1233  current_state_.floating_joints[n->getJointName()] = n->getLocalTransformation();
1234  joint_names_.push_back(joint_name);
1235  floating_joint_names_.push_back(joint_name);
1236  link_names_.push_back(n->getLinkName());
1237  nodes_[joint_name] = std::move(n);
1238  break;
1239  }
1240  // LCOV_EXCL_START
1241  default:
1242  {
1243  throw std::runtime_error("Unsupported joint type for joint '" + joint_name + "'");
1244  }
1245  // LCOV_EXCL_STOP
1246  }
1247 }
1248 
1250  std::vector<std::string>& removed_links,
1251  std::vector<std::string>& removed_joints,
1252  std::vector<std::string>& removed_active_joints,
1253  std::vector<long>& removed_active_joints_indices)
1254 {
1255  removed_links.push_back(node->getLinkName());
1256  removed_joints.push_back(node->getJointName());
1257 
1258  auto it = std::find(active_joint_names_.begin(), active_joint_names_.end(), node->getJointName());
1259  if (it != active_joint_names_.end())
1260  {
1261  removed_active_joints.push_back(node->getJointName());
1262  removed_active_joints_indices.push_back(std::distance(active_joint_names_.begin(), it));
1263  }
1264 
1266  current_state_.joints.erase(node->getJointName());
1269 
1270  std::vector<OFKTNode*> children = node->getChildren();
1271  for (auto* child : children)
1272  removeNode(child, removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
1273 
1274  if (node->getParent() != nullptr)
1275  node->getParent()->removeChild(node);
1276 
1277  link_map_.erase(node->getLinkName());
1278  nodes_.erase(node->getJointName());
1279 }
1280 
1281 void OFKTStateSolver::addNewJointLimits(const std::vector<std::shared_ptr<const JointLimits>>& new_joint_limits)
1282 {
1283  // Populate Joint Limits
1284  if (!new_joint_limits.empty())
1285  {
1287  long s = limits_.joint_limits.rows() + static_cast<long>(new_joint_limits.size());
1288  l.joint_limits.resize(s, 2);
1289  l.velocity_limits.resize(s, 2);
1290  l.acceleration_limits.resize(s, 2);
1291  l.jerk_limits.resize(s, 2);
1292 
1293  l.joint_limits.block(0, 0, limits_.joint_limits.rows(), 2) = limits_.joint_limits;
1294  l.velocity_limits.block(0, 0, limits_.velocity_limits.rows(), 2) = limits_.velocity_limits;
1296  l.jerk_limits.block(0, 0, limits_.jerk_limits.rows(), 2) = limits_.jerk_limits;
1297 
1298  long cnt = limits_.joint_limits.rows();
1299  for (const auto& limits : new_joint_limits)
1300  {
1301  l.joint_limits(cnt, 0) = limits->lower;
1302  l.joint_limits(cnt, 1) = limits->upper;
1303  l.velocity_limits(cnt, 0) = -limits->velocity;
1304  l.velocity_limits(cnt, 1) = limits->velocity;
1305  l.acceleration_limits(cnt, 0) = -limits->acceleration;
1306  l.acceleration_limits(cnt, 1) = limits->acceleration;
1307  l.jerk_limits(cnt, 0) = -limits->jerk;
1308  l.jerk_limits(cnt, 1) = limits->jerk;
1309  ++cnt;
1310  }
1311  limits_ = l;
1312  }
1313 }
1314 
1315 } // namespace tesseract_scene_graph
tesseract_scene_graph::OFKTStateSolver::changeJointOrigin
bool changeJointOrigin(const std::string &name, const Eigen::Isometry3d &new_origin) override final
Changes the "origin" transform of the joint and recomputes the associated edge.
Definition: ofkt_state_solver.cpp:718
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_scene_graph::JointType::REVOLUTE
@ REVOLUTE
tesseract_scene_graph::Graph
boost::adjacency_list< boost::listS, boost::listS, boost::bidirectionalS, VertexProperty, EdgeProperty, GraphProperty > Graph
boost::edge_joint
edge_joint
graph.h
tesseract_scene_graph::SceneState::floating_joints
tesseract_common::TransformMap floating_joints
tesseract_scene_graph::OFKTNode::getLocalTwist
virtual Eigen::Matrix< double, 6, 1 > getLocalTwist() const =0
Return the twist of the node in its local frame.
tesseract_scene_graph::OFKTStateSolver::getActiveLinkNames
std::vector< std::string > getActiveLinkNames() const override final
Get the vector of active link names.
Definition: ofkt_state_solver.cpp:480
tesseract_scene_graph::OFKTStateSolver::joint_names_
std::vector< std::string > joint_names_
Definition: ofkt_state_solver.h:171
tesseract_common::generateRandomNumber
Eigen::VectorXd generateRandomNumber(const Eigen::Ref< const Eigen::MatrixX2d > &limits)
tesseract_scene_graph::OFKTStateSolver::getJointNames
std::vector< std::string > getJointNames() const override final
Get the vector of joint names.
Definition: ofkt_state_solver.cpp:450
tesseract_scene_graph::JointType::FLOATING
@ FLOATING
tesseract_scene_graph::OFKTContinuousNode
Definition: ofkt_nodes.h:215
tesseract_scene_graph::OFKTNode::getJointValue
virtual double getJointValue() const =0
Get the current joint value.
tesseract_scene_graph::ofkt_builder::prefix_
std::string prefix_
Definition: ofkt_state_solver.cpp:80
tesseract_scene_graph::OFKTStateSolver::revision_
int revision_
Definition: ofkt_state_solver.h:179
tesseract_scene_graph::SceneGraph::isTree
bool isTree() const
utils.h
tesseract_scene_graph::SceneGraph::getJoints
std::vector< std::shared_ptr< const Joint > > getJoints() const
tesseract_scene_graph::OFKTStateSolver::update
void update(OFKTNode *node, bool update_required)
This update the local and world transforms.
Definition: ofkt_state_solver.cpp:903
tesseract_scene_graph::OFKTStateSolver::hasLinkName
bool hasLinkName(const std::string &link_name) const override final
Check if link name exists.
Definition: ofkt_state_solver.cpp:505
tesseract_common::KinematicLimits
tesseract_scene_graph::OFKTStateSolver::getLimits
tesseract_common::KinematicLimits getLimits() const override final
Getter for kinematic limits.
Definition: ofkt_state_solver.cpp:532
tesseract_scene_graph::OFKTStateSolver::getActiveJointNames
std::vector< std::string > getActiveJointNames() const override final
Get the vector of joint names which align with the limits.
Definition: ofkt_state_solver.cpp:462
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_common::almostEqualRelativeAndAbs
bool almostEqualRelativeAndAbs(const Eigen::Ref< const Eigen::VectorXd > &v1, const Eigen::Ref< const Eigen::VectorXd > &v2, const Eigen::Ref< const Eigen::VectorXd > &max_diff, const Eigen::Ref< const Eigen::VectorXd > &max_rel_diff)
tesseract_scene_graph::OFKTStateSolver::current_state_
SceneState current_state_
Definition: ofkt_state_solver.h:170
tesseract_scene_graph::OFKTStateSolver::removeLink
bool removeLink(const std::string &name) override final
Removes a link from the graph.
Definition: ofkt_state_solver.cpp:625
tesseract_scene_graph::SceneGraph::Edge
SceneGraph::edge_descriptor Edge
tesseract_scene_graph::OFKTStateSolver::insertSceneGraph
bool insertSceneGraph(const SceneGraph &scene_graph, const Joint &joint, const std::string &prefix="") override final
Merge a scene into the current solver.
Definition: ofkt_state_solver.cpp:809
tesseract_scene_graph::OFKTStateSolver::setState
void setState(const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) override final
Set the current state of the solver.
Definition: ofkt_state_solver.cpp:218
tesseract_scene_graph::OFKTStateSolver::link_map_
std::unordered_map< std::string, OFKTNode * > link_map_
Definition: ofkt_state_solver.h:176
joint.h
tesseract_scene_graph::Joint::parent_to_joint_origin_transform
Eigen::Isometry3d parent_to_joint_origin_transform
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::ofkt_builder::new_joints_limits_
std::vector< JointLimits::ConstPtr > & new_joints_limits_
Definition: ofkt_state_solver.cpp:79
tesseract_scene_graph::Joint::axis
Eigen::Vector3d axis
tesseract_common::twistChangeBase
void twistChangeBase(Eigen::Ref< Eigen::VectorXd > twist, const Eigen::Isometry3d &change_base)
ofkt_nodes.h
A implementation of the Optimized Forward Kinematic Tree Nodes.
tesseract_scene_graph::SceneGraph
tesseract_scene_graph::Joint::ConstPtr
std::shared_ptr< const Joint > ConstPtr
tesseract_scene_graph::OFKTStateSolver::root_
std::unique_ptr< OFKTNode > root_
Definition: ofkt_state_solver.h:178
tesseract_common::KinematicLimits::jerk_limits
Eigen::MatrixX2d jerk_limits
tesseract_scene_graph::OFKTStateSolver::operator=
OFKTStateSolver & operator=(const OFKTStateSolver &other)
Definition: ofkt_state_solver.cpp:170
tesseract_scene_graph::OFKTStateSolver::removeJoint
bool removeJoint(const std::string &name) override final
Removes a joint from the graph.
Definition: ofkt_state_solver.cpp:657
tesseract_scene_graph::OFKTStateSolver::changeJointJerkLimits
bool changeJointJerkLimits(const std::string &name, double limit) override final
Changes the jerk limits associated with a joint.
Definition: ofkt_state_solver.cpp:791
tesseract_scene_graph::OFKTNode::getLinkName
virtual const std::string & getLinkName() const =0
Get the link name associated with the node.
tesseract_scene_graph::OFKTStateSolver::initHelper
bool initHelper(const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &prefix)
Definition: ofkt_state_solver.cpp:966
tesseract_scene_graph::SceneState
tesseract_common::twistChangeRefPoint
void twistChangeRefPoint(Eigen::Ref< Eigen::VectorXd > twist, const Eigen::Ref< const Eigen::Vector3d > &ref_point)
tesseract_scene_graph::OFKTStateSolver::clear
void clear()
Definition: ofkt_state_solver.cpp:203
tesseract_scene_graph::OFKTNode::getLocalTransformation
virtual const Eigen::Isometry3d & getLocalTransformation() const =0
Get the local transformation: 'L = S * J'.
tesseract_scene_graph::OFKTStateSolver::getLinkNames
std::vector< std::string > getLinkNames() const override final
Get the vector of link names.
Definition: ofkt_state_solver.cpp:474
tesseract_scene_graph::OFKTPrismaticNode
Definition: ofkt_nodes.h:243
tesseract_scene_graph::OFKTNode::hasJointValueChanged
virtual bool hasJointValueChanged() const =0
Indicates that the joint value has changed and that local and world transformation need to be recompu...
tesseract_scene_graph::Joint::child_link_name
std::string child_link_name
tesseract_scene_graph::Joint::limits
JointLimits::Ptr limits
tesseract_scene_graph::OFKTStateSolver::removeNode
void removeNode(OFKTNode *node, std::vector< std::string > &removed_links, std::vector< std::string > &removed_joints, std::vector< std::string > &removed_active_joints, std::vector< long > &removed_active_joints_indices)
Remove a node and all of its children.
Definition: ofkt_state_solver.cpp:1249
ofkt_state_solver.h
A implementation of the Optimized Forward Kinematic Tree as a state solver.
tesseract_scene_graph::OFKTStateSolver::moveLinkHelper
void moveLinkHelper(std::vector< std::shared_ptr< const JointLimits >> &new_joint_limits, const Joint &joint)
This a helper function for moving a link.
Definition: ofkt_state_solver.cpp:1008
tesseract_scene_graph::OFKTStateSolver::mutex_
std::shared_mutex mutex_
The state solver can be accessed from multiple threads, need use mutex throughout.
Definition: ofkt_state_solver.h:182
tesseract_scene_graph::OFKTStateSolver::changeJointAccelerationLimits
bool changeJointAccelerationLimits(const std::string &name, double limit) override final
Changes the acceleration limits associated with a joint.
Definition: ofkt_state_solver.cpp:773
tesseract_scene_graph::OFKTStateSolver::calcJacobianHelper
Eigen::MatrixXd calcJacobianHelper(const std::unordered_map< std::string, double > &joints, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const
Given a set of joint values calculate the jacobian for the provided link_name.
Definition: ofkt_state_solver.cpp:411
tesseract_scene_graph::JointType::PRISMATIC
@ PRISMATIC
tesseract_scene_graph::OFKTStateSolver::addNewJointLimits
void addNewJointLimits(const std::vector< std::shared_ptr< const JointLimits >> &new_joint_limits)
appends the new joint limits
Definition: ofkt_state_solver.cpp:1281
tesseract_scene_graph::OFKTStateSolver::getRandomState
SceneState getRandomState() const override final
Get the random state of the environment.
Definition: ofkt_state_solver.cpp:356
tesseract_scene_graph::OFKTNode
The OFKT node is contains multiple trasformation which are described below.
Definition: ofkt_node.h:55
tesseract_scene_graph::SceneState::joints
std::unordered_map< std::string, double > joints
tesseract_scene_graph::OFKTNode::getType
virtual JointType getType() const =0
Get the type of joint associated with the node.
tesseract_scene_graph::OFKTStateSolver::addLink
bool addLink(const Link &link, const Joint &joint) override final
Adds a link/joint to the solver.
Definition: ofkt_state_solver.cpp:538
tesseract_scene_graph::OFKTStateSolver::getStaticLinkNames
std::vector< std::string > getStaticLinkNames() const override final
Get a vector of static link names in the environment.
Definition: ofkt_state_solver.cpp:489
tesseract_scene_graph::OFKTStateSolver::getBaseLinkName
std::string getBaseLinkName() const override final
Get the base link name.
Definition: ofkt_state_solver.cpp:468
tesseract_scene_graph::OFKTStateSolver
An implementation of the Optimized Forward Kinematic Tree as a stat solver.
Definition: ofkt_state_solver.h:56
tesseract_scene_graph::OFKTStateSolver::cloneHelper
void cloneHelper(OFKTStateSolver &cloned, const OFKTNode *node) const
A helper function used for cloning the OFKTStateSolver.
Definition: ofkt_state_solver.cpp:83
tesseract_scene_graph::OFKTStateSolver::limits_
tesseract_common::KinematicLimits limits_
Definition: ofkt_state_solver.h:177
tesseract_scene_graph::OFKTStateSolver::changeJointVelocityLimits
bool changeJointVelocityLimits(const std::string &name, double limit) override final
Changes the velocity limits associated with a joint.
Definition: ofkt_state_solver.cpp:755
tesseract_scene_graph::OFKTStateSolver::isActiveLinkName
bool isActiveLinkName(const std::string &link_name) const override final
Check if link is an active link.
Definition: ofkt_state_solver.cpp:498
tesseract_scene_graph::ofkt_builder
Every time a vertex is visited for the first time add a new node to the tree.
Definition: ofkt_state_solver.cpp:51
tesseract_scene_graph::OFKTStateSolver::addNode
void addNode(const Joint &joint, const std::string &joint_name, const std::string &parent_link_name, const std::string &child_link_name, std::vector< std::shared_ptr< const JointLimits >> &new_joint_limits)
Add a node to the tree.
Definition: ofkt_state_solver.cpp:1146
tesseract_scene_graph::StateSolver::UPtr
std::unique_ptr< StateSolver > UPtr
Definition: state_solver.h:50
tesseract_scene_graph::JointType::CONTINUOUS
@ CONTINUOUS
tesseract_scene_graph::Joint
tesseract_scene_graph::OFKTStateSolver::moveLink
bool moveLink(const Joint &joint) override final
Move a link.
Definition: ofkt_state_solver.cpp:599
tesseract_scene_graph::OFKTStateSolver::nodes_
std::unordered_map< std::string, std::unique_ptr< OFKTNode > > nodes_
Definition: ofkt_state_solver.h:175
tesseract_scene_graph::SceneState::joint_transforms
tesseract_common::TransformMap joint_transforms
tesseract_scene_graph::OFKTStateSolver::changeJointPositionLimits
bool changeJointPositionLimits(const std::string &name, double lower, double upper) override final
Changes the position limits associated with a joint.
Definition: ofkt_state_solver.cpp:737
tesseract_scene_graph::OFKTStateSolver::active_joint_names_
std::vector< std::string > active_joint_names_
Definition: ofkt_state_solver.h:172
tesseract_scene_graph::SceneGraph::isEmpty
bool isEmpty() const
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_scene_graph::ofkt_builder::tree_
OFKTStateSolver & tree_
Definition: ofkt_state_solver.cpp:78
tesseract_scene_graph::OFKTStateSolver::getJacobian
Eigen::MatrixXd getJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const override final
Get the jacobian of the solver given the joint values.
Definition: ofkt_state_solver.cpp:362
tesseract_scene_graph::SceneGraph::getRoot
const std::string & getRoot() const
tesseract_scene_graph::OFKTNode::addChild
virtual void addChild(OFKTNode *node)=0
Add a child node.
tesseract_scene_graph::ofkt_builder::discover_vertex
void discover_vertex(u vertex, const g &graph)
Definition: ofkt_state_solver.cpp:59
tesseract_scene_graph::OFKTStateSolver::getRevision
int getRevision() const override final
Get the state solver revision number.
Definition: ofkt_state_solver.cpp:197
tesseract_common::jacobianChangeBase
void jacobianChangeBase(Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Isometry3d &change_base)
tesseract_scene_graph::OFKTStateSolver::loadStaticLinkNamesRecursive
void loadStaticLinkNamesRecursive(std::vector< std::string > &static_link_names, const OFKTNode *node) const
load the static link names
Definition: ofkt_state_solver.cpp:891
tesseract_scene_graph::OFKTStateSolver::link_names_
std::vector< std::string > link_names_
Definition: ofkt_state_solver.h:174
tesseract_scene_graph::OFKTNode::computeAndStoreLocalTransformation
virtual void computeAndStoreLocalTransformation()=0
Compute and save the local transformation 'L = S * J(Joint Value)'.
tesseract_scene_graph::OFKTStateSolver::OFKTStateSolver
OFKTStateSolver(const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &prefix="")
Definition: ofkt_state_solver.cpp:155
tesseract_scene_graph::OFKTNode::removeChild
virtual void removeChild(const OFKTNode *node)=0
Remove a child node assiciated with this node.
tesseract_scene_graph::OFKTStateSolver::floating_joint_names_
std::vector< std::string > floating_joint_names_
Definition: ofkt_state_solver.h:173
tesseract_common::KinematicLimits::acceleration_limits
Eigen::MatrixX2d acceleration_limits
tesseract_scene_graph::OFKTNode::getChildren
virtual std::vector< OFKTNode * > & getChildren()=0
Get a vector of child nodes associated with this node.
tesseract_common::KinematicLimits::velocity_limits
Eigen::MatrixX2d velocity_limits
tesseract_scene_graph::OFKTRevoluteNode
Definition: ofkt_nodes.h:186
tesseract_scene_graph::ofkt_builder::ofkt_builder
ofkt_builder(OFKTStateSolver &tree, std::vector< JointLimits::ConstPtr > &new_joints_limits, std::string prefix="")
Definition: ofkt_state_solver.cpp:53
tesseract_scene_graph::Joint::type
JointType type
tesseract_scene_graph::OFKTStateSolver::moveJoint
bool moveJoint(const std::string &name, const std::string &parent_link) override final
Move joint to new parent link.
Definition: ofkt_state_solver.cpp:689
tesseract_scene_graph::SceneGraph::getLink
std::shared_ptr< const Link > getLink(const std::string &name) const
tesseract_scene_graph::OFKTNode::getParent
virtual OFKTNode * getParent()=0
Get the parent node.
tesseract_scene_graph::Joint::getName
const std::string & getName() const
ofkt_node.h
A implementation of the Optimized Forward Kinematic Tree Node.
tesseract_scene_graph::OFKTNode::computeLocalTransformation
virtual Eigen::Isometry3d computeLocalTransformation(double joint_value) const =0
Compute the local tranformation but do not save.
tesseract_scene_graph::SceneGraph::getVertex
Vertex getVertex(const std::string &name) const
tesseract_scene_graph::SceneState::link_transforms
tesseract_common::TransformMap link_transforms
tesseract_scene_graph::OFKTNode::updateWorldTransformationRequired
virtual bool updateWorldTransformationRequired() const =0
Indicates if an update of the world transformation is required.
tesseract_scene_graph::OFKTStateSolver::replaceJoint
bool replaceJoint(const Joint &joint) override final
Replace and existing joint with the provided one.
Definition: ofkt_state_solver.cpp:565
macros.h
tesseract_scene_graph::OFKTStateSolver::getLinkTransforms
tesseract_common::VectorIsometry3d getLinkTransforms() const override final
Get all of the links transforms.
Definition: ofkt_state_solver.cpp:511
tesseract_scene_graph::OFKTNode::getJointName
virtual const std::string & getJointName() const =0
Get the joint name associated with the node.
tesseract_scene_graph::OFKTStateSolver::setRevision
void setRevision(int revision) override final
Set the state solver revision number.
Definition: ofkt_state_solver.cpp:191
tesseract_scene_graph::OFKTStateSolver::loadActiveLinkNamesRecursive
void loadActiveLinkNamesRecursive(std::vector< std::string > &active_link_names, const OFKTNode *node, bool active) const
load the active link names
Definition: ofkt_state_solver.cpp:864
tesseract_scene_graph
tesseract_scene_graph::OFKTStateSolver::removeJointHelper
void removeJointHelper(const std::vector< std::string > &removed_links, const std::vector< std::string > &removed_joints, const std::vector< std::string > &removed_active_joints, const std::vector< long > &removed_active_joints_indices)
This will clean up member variables joint_names_ and limits_.
Definition: ofkt_state_solver.cpp:1075
tesseract_common::KinematicLimits::joint_limits
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::MatrixX2d joint_limits
tesseract_scene_graph::OFKTNode::computeAndStoreWorldTransformation
virtual void computeAndStoreWorldTransformation()=0
Compute and store the nodes world transformation.
tesseract_scene_graph::OFKTNode::getWorldTransformation
virtual const Eigen::Isometry3d & getWorldTransformation() const =0
Get the nodes world transformation.
tesseract_scene_graph::OFKTStateSolver::getRelativeLinkTransform
Eigen::Isometry3d getRelativeLinkTransform(const std::string &from_link_name, const std::string &to_link_name) const override final
Get transform between two links using the current state.
Definition: ofkt_state_solver.cpp:526
tesseract_scene_graph::Joint::parent_link_name
std::string parent_link_name
tesseract_scene_graph::OFKTStateSolver::getFloatingJointNames
std::vector< std::string > getFloatingJointNames() const override final
Get the vector of floating joint names.
Definition: ofkt_state_solver.cpp:456
tesseract_scene_graph::OFKTStateSolver::clone
StateSolver::UPtr clone() const override final
This should clone the object so it may be used in a multi threaded application where each thread woul...
Definition: ofkt_state_solver.cpp:185
tesseract_scene_graph::OFKTStateSolver::getState
SceneState getState() const override final
Get the current state of the scene.
Definition: ofkt_state_solver.cpp:350
tesseract_scene_graph::JointType::FIXED
@ FIXED
tesseract_scene_graph::OFKTStateSolver::replaceJointHelper
void replaceJointHelper(std::vector< std::shared_ptr< const JointLimits >> &new_joint_limits, const Joint &joint)
This is a helper function for replacing a joint.
Definition: ofkt_state_solver.cpp:1053
tesseract_scene_graph::OFKTStateSolver::getLinkTransform
Eigen::Isometry3d getLinkTransform(const std::string &link_name) const override final
Get the transform corresponding to the link.
Definition: ofkt_state_solver.cpp:521


tesseract_state_solver
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:10