kinematic_tree.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020, University of Edinburgh, University of Oxford
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #include <algorithm>
31 #include <iostream>
32 #include <queue>
33 #include <set>
34 
39 #include <octomap_msgs/Octomap.h>
41 #include <tf_conversions/tf_kdl.h>
42 #include <kdl/frames_io.hpp>
44 
46 #include <exotica_core/server.h>
47 #include <exotica_core/tools.h>
48 
49 namespace exotica
50 {
52 
54 {
55  flags = _flags;
56  frame.resize(_size);
57  Phi.resize(_size);
58  if (flags & KIN_FK_VEL) Phi_dot.resize(_size);
59  KDL::Jacobian Jzero(_n);
60  Jzero.data.setZero();
61  Hessian Hzero = Hessian::Constant(6, Eigen::MatrixXd::Zero(_n, _n));
62  if (_flags & KIN_J) jacobian = ArrayJacobian::Constant(_size, Jzero);
63  if (_flags & KIN_H) hessian = ArrayHessian::Constant(_size, Hzero);
64  x.setZero(_n);
65 }
66 
68 
70 
71 KinematicFrameRequest::KinematicFrameRequest(std::string _frame_A_link_name, KDL::Frame _frame_A_offset, std::string _frame_B_link_name, KDL::Frame _frame_B_offset) : frame_A_link_name(_frame_A_link_name), frame_A_offset(_frame_A_offset), frame_B_link_name(_frame_B_link_name), frame_B_offset(_frame_B_offset)
72 {
73 }
74 
76 
77 KinematicSolution::KinematicSolution(int _start, int _length) : start(_start), length(_length)
78 {
79 }
80 
81 void KinematicSolution::Create(std::shared_ptr<KinematicResponse> solution)
82 {
83  if (start < 0 || length < 0) ThrowPretty("Kinematic solution was not initialized!");
84  new (&Phi) Eigen::Map<ArrayFrame>(solution->Phi.data() + start, length);
85  new (&X) Eigen::Map<Eigen::VectorXd>(solution->x.data(), solution->x.rows());
86  if (solution->flags & KIN_FK_VEL) new (&Phi_dot) Eigen::Map<ArrayTwist>(solution->Phi_dot.data() + start, length);
87  if (solution->flags & KIN_J) new (&jacobian) Eigen::Map<ArrayJacobian>(solution->jacobian.data() + start, length);
88  if (solution->flags & KIN_H) new (&hessian) Eigen::Map<ArrayHessian>(solution->hessian.data() + start, length);
89 }
90 
92 {
94 }
95 
97 {
98  return num_joints_;
99 }
100 
101 void KinematicTree::Instantiate(const std::string& joint_group, robot_model::RobotModelPtr model, const std::string& name)
102 {
103  if (!model) ThrowPretty("No robot model provided!");
104  model_joints_names_ = model->getVariableNames();
105  name_ = name;
106 
107  // Check if no joint group name is given - if so, default to all joints.
108  const robot_model::JointModelGroup* group = model->getJointModelGroup(joint_group);
109  if (!group)
110  {
111  auto names = model->getJointModelGroupNames();
112 
113  // If a particular joint group is desired, but we may have a user error and will throw an exception.
114  if (!joint_group.empty())
115  {
116  std::stringstream ss;
117  ss << "Joint group '" << joint_group << "' not defined in the robot model. " << names.size() << " joint groups available";
118  if (names.size() > static_cast<std::size_t>(0))
119  {
120  ss << ": ";
121  for (const auto& joint_group_name : names)
122  ss << joint_group_name << ", ";
123  }
124  ThrowPretty(ss.str());
125  }
126  else
127  {
128  // The joint group was left empty: We default to all _active_ joints (no fixed, no mimic).
129  // Alternatives: getJointModelNames, getVariableNames
130  for (auto joint_model : model->getActiveJointModels())
131  controlled_joints_names_.push_back(joint_model->getName());
132  }
133  }
134  else
135  {
136  // Use the joints from the desired joint group.
137  controlled_joints_names_ = group->getVariableNames();
138  }
139 
140  model_ = model;
141  KDL::Tree robot_kinematics;
142  if (kdl_parser::treeFromUrdfModel(*model_->getURDF(), robot_kinematics))
143  {
144  BuildTree(robot_kinematics);
145  }
146  else
147  {
148  ThrowPretty("Can't load URDF model!");
149  }
150 
151  if (Server::IsRos())
152  {
153  shapes_pub_ = Server::Advertise<visualization_msgs::MarkerArray>(name_ + (name_ == "" ? "" : "/") + "CollisionShapes", 1, true);
154  octomap_pub_ = Server::Advertise<octomap_msgs::Octomap>(name_ + (name_ == "" ? "" : "/") + "OctoMap", 1, true);
155  debug_scene_changed_ = true;
156  // Clear scene
157  visualization_msgs::MarkerArray msg;
158  msg.markers.resize(1);
159  msg.markers[0].action = 3; // DELETE_ALL
160  shapes_pub_.publish(msg);
161  }
162 }
163 
164 void KinematicTree::BuildTree(const KDL::Tree& robot_kinematics)
165 {
166  model_tree_.clear();
167  tree_.clear();
168  tree_map_.clear();
169  model_joints_map_.clear();
170  model_link_names_.clear();
171  controlled_link_names_.clear();
172 
173  // Handle the root joint
174  const robot_model::JointModel* root_joint = model_->getRootJoint();
175  root_joint_name_ = root_joint->getName();
176  std::string world_frame_name;
177  for (const srdf::Model::VirtualJoint& s : model_->getSRDF()->getVirtualJoints())
178  {
179  if (s.name_ == root_joint->getName())
180  {
181  world_frame_name = s.parent_frame_;
182  }
183  }
184  // if (world_frame_name == "") ThrowPretty("Can't initialize root joint!");
185  if (world_frame_name.empty())
186  {
187  world_frame_name = "world_frame";
188  WARNING_NAMED("KinematicTree", "No virtual joint defined. Defaulting world frame to " << world_frame_name)
189  }
190 
191  // Extract Root Inertial
192  double root_mass = 0.0;
193  KDL::Vector root_cog = KDL::Vector::Zero();
194  auto& urdf_root_inertial = model_->getURDF()->getRoot()->inertial;
195  if (urdf_root_inertial)
196  {
197  root_mass = urdf_root_inertial->mass;
198  root_cog = KDL::Vector(urdf_root_inertial->origin.position.x,
199  urdf_root_inertial->origin.position.y,
200  urdf_root_inertial->origin.position.z);
201  if (debug)
202  HIGHLIGHT_NAMED("Root Inertial", "Mass: " << root_mass
203  << " kg - CoG: " << root_cog);
204  }
205  // TODO: Note, this does not set the rotational inertia component, i.e. the
206  // inertial matrix would be wrong
207  KDL::RigidBodyInertia root_inertial(root_mass, root_cog);
208 
209  // Add general world_frame joint
210  model_tree_.push_back(std::make_shared<KinematicElement>(-1, nullptr, KDL::Segment(world_frame_name, KDL::Joint(root_joint->getName(), KDL::Joint::None))));
211  if (root_joint->getType() == robot_model::JointModel::FIXED)
212  {
214  }
215  else if (root_joint->getType() == robot_model::JointModel::FLOATING)
216  {
218  model_tree_.resize(7);
219  const KDL::Joint::JointType types[] = {KDL::Joint::TransX, KDL::Joint::TransY, KDL::Joint::TransZ, KDL::Joint::RotZ, KDL::Joint::RotY, KDL::Joint::RotX};
220  const std::vector<std::string> floating_base_suffix = {
221  "/trans_x", "/trans_y", "/trans_z",
222  "/rot_z", "/rot_y", "/rot_x"};
223  for (size_t i = 0; i < 6; ++i)
224  {
225  model_tree_[i + 1] = std::make_shared<KinematicElement>(i, model_tree_[i], KDL::Segment(world_frame_name + floating_base_suffix[i], KDL::Joint(root_joint_name_ + floating_base_suffix[i], types[i])));
226  model_tree_[i]->children.push_back(model_tree_[i + 1]);
227  }
228 
229  // The floating base rotation is defined as xyzw quaternion in the robot
230  // model, but we are following a RPY-fixed axis (YPR rotating axis)
231  // virtual joint convention in exotica - thus delete the rot_w from the
232  // list of joint names
233  auto RotW = std::find(controlled_joints_names_.begin(), controlled_joints_names_.end(), root_joint->getVariableNames()[6]);
234  if (RotW != controlled_joints_names_.end()) controlled_joints_names_.erase(RotW);
235  RotW = std::find(model_joints_names_.begin(), model_joints_names_.end(), root_joint->getVariableNames()[6]);
236  if (RotW != model_joints_names_.end()) model_joints_names_.erase(RotW);
237 
238  // NB: We do not want to swap the XYZ labels for the rotation joints
239  // to not change the order in which joint and model state are stored.
240  }
241  else if (root_joint->getType() == robot_model::JointModel::PLANAR)
242  {
244  model_tree_.resize(4);
245  const KDL::Joint::JointType types[] = {KDL::Joint::TransX, KDL::Joint::TransY,
246  KDL::Joint::RotZ};
247  for (int i = 0; i < 3; ++i)
248  {
249  model_tree_[i + 1] = std::make_shared<KinematicElement>(
250  i, model_tree_[i],
251  KDL::Segment(
252  root_joint->getVariableNames()[i],
253  KDL::Joint(root_joint->getVariableNames()[i], types[i])));
254  model_tree_[i]->children.push_back(model_tree_[i + 1]);
255  }
256  }
257  else
258  {
259  ThrowPretty("Unsupported root joint type: " << root_joint->getTypeName());
260  }
261 
262  AddElementFromSegmentMapIterator(robot_kinematics.getRootSegment(), *(model_tree_.end() - 1));
263 
264  // Set root inertial
265  if (root_joint->getType() == robot_model::JointModel::FIXED)
266  {
267  model_tree_[2]->segment.setInertia(root_inertial);
268  }
269  else if (root_joint->getType() == robot_model::JointModel::FLOATING)
270  {
271  model_tree_[7]->segment.setInertia(root_inertial);
272  }
273  else if (root_joint->getType() == robot_model::JointModel::PLANAR)
274  {
275  model_tree_[4]->segment.setInertia(root_inertial);
276  }
277 
278  for (auto element : model_tree_) tree_.push_back(element);
279 
280  UpdateModel();
281  tree_state_.setZero();
282 
283  if (debug)
284  {
285  for (int i = 0; i < tree_.size() - 1; ++i)
287  "Tree", "Joint: " << tree_[i].lock()->segment.getJoint().getName() << " - Link: " << tree_[i].lock()->segment.getName()
288  << ", parent: " << tree_[i].lock()->parent_name
289  << ", mass: " << tree_[i].lock()->segment.getInertia().getMass()
290  << ", CoM: " << tree_[i].lock()->segment.getInertia().getCOG());
291  }
292 
295  state_size_ = num_controlled_joints_; // TODO: We should probably deprecate state_size_
296  if (num_controlled_joints_ < 1) ThrowPretty("No update joints specified!");
298  for (std::shared_ptr<KinematicElement> Joint : model_tree_)
299  {
300  Joint->is_robot_link = true;
301  Joint->control_id = IsControlled(Joint);
302  Joint->is_controlled = Joint->control_id >= 0;
303  model_joints_map_[Joint->segment.getJoint().getName()] = Joint;
304  model_link_names_.push_back(Joint->segment.getName());
305  if (Joint->is_controlled)
306  {
307  controlled_joints_[Joint->control_id] = Joint;
308  controlled_joints_map_[Joint->segment.getJoint().getName()] = Joint;
309  controlled_link_names_.push_back(Joint->segment.getName());
310 
311  // The model_base_type_ defined above refers to the base type of the
312  // overall robot model - not of the set of controlled joints. E.g. a
313  // floating-base robot can have a scene defined where the
314  // floating-base virtual joint is _not_ part of the planning
315  // group/scene. Thus we need to establish the BaseType of the joint
316  // group, the controlled_base_type_ - if a controlled joint corresponds
317  // to a floating base joint, the controlled_base_type_ is the same as the
318  // model_base_type_.
319  if (Joint->segment.getJoint().getName().find(
320  root_joint->getName()) != std::string::npos)
322  }
323  }
324  model_tree_[0]->is_robot_link = false;
325 
326  joint_limits_ = Eigen::MatrixXd::Zero(num_controlled_joints_, 2);
327  velocity_limits_ = Eigen::VectorXd::Zero(num_controlled_joints_);
328  acceleration_limits_ = Eigen::VectorXd::Zero(num_controlled_joints_);
330 
331  if (debug) HIGHLIGHT_NAMED("KinematicTree::BuildTree", "Number of controlled joints: " << num_controlled_joints_ << " - Number of model joints: " << num_joints_);
332 
333  // Create random distributions for state sampling
334  generator_ = std::mt19937(rd_());
335 
336  // Get URDF links to set up additional properties, e.g. mimic joints and visual shapes
337  const urdf::ModelInterfaceSharedPtr& urdf = model_->getURDF();
338  std::vector<urdf::LinkSharedPtr> urdf_links;
339  urdf->getLinks(urdf_links);
340 
341  // Set up mimic joints
342  for (urdf::LinkSharedPtr urdf_link : urdf_links)
343  {
344  if (urdf_link->parent_joint != nullptr && urdf_link->parent_joint->mimic != nullptr)
345  {
346  const auto& mimic = urdf_link->parent_joint->mimic;
347  if (debug) HIGHLIGHT(urdf_link->name << " is a mimic joint; mimicking " << mimic->joint_name << "; multiplier=" << mimic->multiplier << ", offset=" << mimic->offset);
348 
349  std::shared_ptr<KinematicElement> mimicked_element = model_joints_map_[mimic->joint_name].lock();
350  std::shared_ptr<KinematicElement> element = tree_map_[urdf_link->name].lock();
351  element->is_mimic_joint = true;
352  element->mimic_multiplier = mimic->multiplier;
353  element->mimic_offset = mimic->offset;
354  element->mimic_joint_id = mimicked_element->id;
355  }
356  }
357 
358  // Add visual shapes
359  for (urdf::LinkSharedPtr urdf_link : urdf_links)
360  {
361  if (urdf_link->visual_array.size() > 0)
362  {
363  std::shared_ptr<KinematicElement> element = tree_map_[urdf_link->name].lock();
364  int i = 0;
365  element->visual.reserve(urdf_link->visual_array.size());
366  for (urdf::VisualSharedPtr urdf_visual : urdf_link->visual_array)
367  {
368  VisualElement visual;
369  visual.name = urdf_link->name + "_visual_" + std::to_string(i);
370  visual.frame = KDL::Frame(KDL::Rotation::Quaternion(urdf_visual->origin.rotation.x, urdf_visual->origin.rotation.y, urdf_visual->origin.rotation.z, urdf_visual->origin.rotation.w), KDL::Vector(urdf_visual->origin.position.x, urdf_visual->origin.position.y, urdf_visual->origin.position.z));
371  if (urdf_visual->material)
372  {
373  urdf::MaterialSharedPtr material = urdf_visual->material->name == "" ? urdf_visual->material : urdf->getMaterial(urdf_visual->material->name);
374  visual.color(0) = material->color.r;
375  visual.color(1) = material->color.g;
376  visual.color(2) = material->color.b;
377  visual.color(3) = material->color.a;
378  }
379  else
380  {
381  if (debug)
382  HIGHLIGHT("No material for " << visual.name);
383  }
384 
385  switch (urdf_visual->geometry->type)
386  {
387  case urdf::Geometry::BOX:
388  {
389  std::shared_ptr<urdf::Box> box = std::static_pointer_cast<urdf::Box>(ToStdPtr(urdf_visual->geometry));
390  visual.shape = std::shared_ptr<shapes::Box>(new shapes::Box(box->dim.x, box->dim.y, box->dim.z));
391  }
392  break;
393  case urdf::Geometry::SPHERE:
394  {
395  std::shared_ptr<urdf::Sphere> sphere = std::static_pointer_cast<urdf::Sphere>(ToStdPtr(urdf_visual->geometry));
396  visual.shape = std::shared_ptr<shapes::Sphere>(new shapes::Sphere(sphere->radius));
397  }
398  break;
399  case urdf::Geometry::CYLINDER:
400  {
401  std::shared_ptr<urdf::Cylinder> cylinder = std::static_pointer_cast<urdf::Cylinder>(ToStdPtr(urdf_visual->geometry));
402  visual.shape = std::shared_ptr<shapes::Cylinder>(new shapes::Cylinder(cylinder->radius, cylinder->length));
403  }
404  break;
405  case urdf::Geometry::MESH:
406  {
407  std::shared_ptr<urdf::Mesh> mesh = std::static_pointer_cast<urdf::Mesh>(ToStdPtr(urdf_visual->geometry));
408  visual.shape_resource_path = mesh->filename;
409  visual.scale = Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z);
410  visual.shape.reset(shapes::createMeshFromResource(mesh->filename));
411  }
412  break;
413  default:
414  ThrowPretty("Unknown geometry type: " << urdf_visual->geometry->type);
415  }
416  element->visual.push_back(visual);
417  ++i;
418  }
419  }
420  }
421 }
422 
424 {
425  root_ = tree_[0].lock();
426  tree_state_.conservativeResize(tree_.size());
427  for (std::weak_ptr<KinematicElement> joint : tree_)
428  {
429  tree_map_[joint.lock()->segment.getName()] = joint.lock();
430  }
431  debug_tree_.resize(tree_.size() - 1);
432  UpdateTree();
433  debug_scene_changed_ = true;
434 }
435 
437 {
438  collision_tree_map_.clear();
439  tree_map_.clear();
440  environment_tree_.clear();
441  tree_.resize(model_tree_.size());
442  UpdateModel();
443  debug_scene_changed_ = true;
444 
445  // Remove all CollisionShapes
446  if (Server::IsRos())
447  {
448  visualization_msgs::Marker mrk;
449  mrk.action = 3; // visualization_msgs::Marker::DELETEALL; // NB: enum only defined in ROS-jacobian and newer, functionality still there
450  marker_array_msg_.markers.push_back(mrk);
451  }
452 }
453 
454 void KinematicTree::ChangeParent(const std::string& name, const std::string& parent_name, const KDL::Frame& pose, bool relative)
455 {
456  if (tree_map_.find(name) == tree_map_.end()) ThrowPretty("Attempting to attach unknown frame '" << name << "'!");
457  std::shared_ptr<KinematicElement> child = tree_map_.find(name)->second.lock();
458  if (child->id < model_tree_.size()) ThrowPretty("Can't re-attach robot link '" << name << "'!");
459  if (child->shape) ThrowPretty("Can't re-attach collision shape without reattaching the object! ('" << name << "')");
460  std::shared_ptr<KinematicElement> parent;
461  if (parent_name == "")
462  {
463  if (tree_map_.find(root_->segment.getName()) == tree_map_.end()) ThrowPretty("Attempting to attach to unknown frame '" << root_->segment.getName() << "'!");
464  parent = tree_map_.find(root_->segment.getName())->second.lock();
465  }
466  else
467  {
468  if (tree_map_.find(parent_name) == tree_map_.end()) ThrowPretty("Attempting to attach to unknown frame '" << parent_name << "'!");
469  parent = tree_map_.find(parent_name)->second.lock();
470  }
471  if (parent->shape) ThrowPretty("Can't attach object to a collision shape object! ('" << parent_name << "')");
472  if (relative)
473  {
474  child->segment = KDL::Segment(child->segment.getName(), child->segment.getJoint(), pose, child->segment.getInertia());
475  }
476  else
477  {
478  child->segment = KDL::Segment(child->segment.getName(), child->segment.getJoint(), parent->frame.Inverse() * child->frame * pose, child->segment.getInertia());
479  }
480 
481  // Iterate over Parent's children to find child and then remove it
482  for (auto it = child->parent.lock()->children.begin(); it != child->parent.lock()->children.end();)
483  {
484  std::shared_ptr<KinematicElement> childOfParent = it->lock();
485  if (childOfParent == child)
486  {
487  child->parent.lock()->children.erase(it);
488  }
489  else
490  {
491  ++it;
492  }
493  }
494 
495  child->parent = parent;
496  child->parent_name = parent->segment.getName();
497  parent->children.push_back(child);
498  child->UpdateClosestRobotLink();
499  debug_scene_changed_ = true;
500 }
501 
502 std::shared_ptr<KinematicElement> KinematicTree::AddEnvironmentElement(const std::string& name, const Eigen::Isometry3d& transform, const std::string& parent, shapes::ShapeConstPtr shape, const KDL::RigidBodyInertia& inertia, const Eigen::Vector4d& color, const std::vector<VisualElement>& visual, bool is_controlled)
503 {
504  std::shared_ptr<KinematicElement> element = AddElement(name, transform, parent, shape, inertia, color, visual, is_controlled);
505  environment_tree_.push_back(element);
506  return element;
507 }
508 
509 std::shared_ptr<KinematicElement> KinematicTree::AddElement(const std::string& name, const Eigen::Isometry3d& transform, const std::string& parent, const std::string& shape_resource_path, Eigen::Vector3d scale, const KDL::RigidBodyInertia& inertia, const Eigen::Vector4d& color, const std::vector<VisualElement>& visual, bool is_controlled)
510 {
511  std::string shape_path(shape_resource_path);
512  if (shape_path.empty())
513  {
514  ThrowPretty("Shape path cannot be empty!");
515  }
516  // Exotica package path resolution
517  else if (shape_path.substr(0, 1) == "{")
518  {
519  shape_path = "file://" + ParsePath(shape_path);
520  }
521  // ROS resource path resolution
522  else if (shape_path.substr(0, 10) == "package://" || shape_path.substr(0, 8) == "file:///")
523  {
524  }
525  else
526  {
527  ThrowPretty("Path cannot be resolved.");
528  }
529 
531  std::shared_ptr<KinematicElement> element = AddElement(name, transform, parent, shape, inertia, color, visual, is_controlled);
532  element->shape_resource_path = shape_path;
533  element->scale = scale;
534  return element;
535 }
536 
537 std::shared_ptr<KinematicElement> KinematicTree::AddElement(const std::string& name, const Eigen::Isometry3d& transform, const std::string& parent, shapes::ShapeConstPtr shape, const KDL::RigidBodyInertia& inertia, const Eigen::Vector4d& color, const std::vector<VisualElement>& visual, bool is_controlled)
538 {
539  std::shared_ptr<KinematicElement> parent_element;
540  if (parent == "")
541  {
542  parent_element = root_;
543  }
544  else
545  {
546  bool found = false;
547  for (const auto& element : tree_)
548  {
549  if (element.lock()->segment.getName() == parent)
550  {
551  parent_element = element.lock();
552  found = true;
553  break;
554  }
555  }
556  if (!found) ThrowPretty("Can't find parent link named '" << parent << "'!");
557  }
558  KDL::Frame transform_kdl;
559  tf::transformEigenToKDL(transform, transform_kdl);
560  std::shared_ptr<KinematicElement> new_element = std::make_shared<KinematicElement>(tree_.size(), parent_element, KDL::Segment(name, KDL::Joint(KDL::Joint::None), transform_kdl, inertia));
561  if (shape)
562  {
563  new_element->shape = shape;
564  collision_tree_map_[new_element->segment.getName()] = new_element;
565 
566  // Set color if set. If all zeros, default to preset (grey).
567  if (color != Eigen::Vector4d::Zero()) new_element->color = color;
568  }
569  new_element->parent_name = parent;
570  new_element->is_controlled = is_controlled;
571  tree_.push_back(new_element);
572  parent_element->children.push_back(new_element);
573  new_element->UpdateClosestRobotLink();
574  tree_map_[name] = new_element;
575  new_element->visual = visual;
576  debug_scene_changed_ = true;
577  return new_element;
578 }
579 
580 void KinematicTree::AddElementFromSegmentMapIterator(KDL::SegmentMap::const_iterator segment, std::shared_ptr<KinematicElement> parent)
581 {
582  std::shared_ptr<KinematicElement> new_element = std::make_shared<KinematicElement>(model_tree_.size(), parent, segment->second.segment);
583  model_tree_.push_back(new_element);
584  if (parent) parent->children.push_back(new_element);
585  for (KDL::SegmentMap::const_iterator child : segment->second.children)
586  {
587  AddElementFromSegmentMapIterator(child, new_element);
588  }
589 }
590 
591 int KinematicTree::IsControlled(std::shared_ptr<KinematicElement> joint)
592 {
593  for (int i = 0; i < controlled_joints_names_.size(); ++i)
594  {
595  if (controlled_joints_names_[i] == joint->segment.getJoint().getName()) return i;
596  }
597  return -1;
598 }
599 
600 int KinematicTree::IsControlledLink(const std::string& link_name)
601 {
602  try
603  {
604  auto element = tree_map_[link_name].lock();
605 
606  if (element && element->is_controlled)
607  {
608  return element->control_id;
609  }
610 
611  while (element)
612  {
613  element = element->parent.lock();
614 
615  if (element && element->is_controlled)
616  {
617  return element->control_id;
618  }
619  }
620  }
621  catch (const std::out_of_range& e)
622  {
623  return -1;
624  }
625  return -1;
626 }
627 
628 std::shared_ptr<KinematicResponse> KinematicTree::RequestFrames(const KinematicsRequest& request)
629 {
630  flags_ = request.flags;
631  if (flags_ & KIN_H) flags_ = flags_ | KIN_J;
632  solution_.reset(new KinematicResponse(flags_, request.frames.size(), num_controlled_joints_));
633 
635 
636  for (int i = 0; i < request.frames.size(); ++i)
637  {
638  if (request.frames[i].frame_A_link_name == "")
639  solution_->frame[i].frame_A = root_;
640  else
641  try
642  {
643  solution_->frame[i].frame_A = tree_map_.at(request.frames[i].frame_A_link_name);
644  }
645  catch (const std::out_of_range& e)
646  {
647  ThrowPretty("No frame_A link exists named '" << request.frames[i].frame_A_link_name << "'");
648  }
649  if (request.frames[i].frame_B_link_name == "")
650  solution_->frame[i].frame_B = root_;
651  else
652  try
653  {
654  solution_->frame[i].frame_B = tree_map_.at(request.frames[i].frame_B_link_name);
655  }
656  catch (const std::out_of_range& e)
657  {
658  ThrowPretty("No frame_B link exists named '" << request.frames[i].frame_B_link_name << "'");
659  }
660 
661  solution_->frame[i].frame_A_offset = request.frames[i].frame_A_offset;
662  solution_->frame[i].frame_B_offset = request.frames[i].frame_B_offset;
663  }
664 
665  if (debug)
666  {
667  for (KinematicFrame& frame : solution_->frame)
668  {
669  HIGHLIGHT(frame.frame_B.lock()->segment.getName() << " " << (frame.frame_B_offset == KDL::Frame::Identity() ? "" : ToString(frame.frame_B_offset)) << " -> " << frame.frame_A.lock()->segment.getName() << " " << (frame.frame_A_offset == KDL::Frame::Identity() ? "" : ToString(frame.frame_A_offset)));
670  }
671  }
672 
673  debug_frames_.resize(solution_->frame.size() * 2);
674 
675  return solution_;
676 }
677 
679 {
680  if (x.size() != state_size_) ThrowPretty("Wrong state vector size! Got " << x.size() << " expected " << state_size_);
681 
682  for (int i = 0; i < num_controlled_joints_; ++i)
683  tree_state_(controlled_joints_[i].lock()->id) = x(i);
684 
685  // Store the updated state in the KinematicResponse (solution_)
686  solution_->x = x;
687 
688  UpdateTree();
689  UpdateFK();
690  if (flags_ & KIN_J) UpdateJ();
691  if (flags_ & KIN_J && flags_ & KIN_H) UpdateH();
692  if (debug) PublishFrames();
693 }
694 
696 {
697  std::queue<std::shared_ptr<KinematicElement>> elements;
698  elements.push(root_);
699  root_->RemoveExpiredChildren();
700  while (elements.size() > 0)
701  {
702  auto element = elements.front();
703  elements.pop();
704  // Elements with id > -1 have parent links.
705  // ID=-1 is the global world reference frame.
706  if (element->id > -1)
707  {
708  if (element->segment.getJoint().getType() != KDL::Joint::JointType::None)
709  {
710  if (!element->is_mimic_joint)
711  {
712  element->frame = element->parent.lock()->frame * element->GetPose(tree_state_(element->id));
713  }
714  else
715  {
716  element->frame = element->parent.lock()->frame * element->GetPose(tree_state_(element->mimic_joint_id));
717  }
718  }
719  else
720  {
721  element->frame = element->parent.lock()->frame * element->GetPose();
722  }
723  }
724  // Root of tree.
725  else
726  {
727  // NB: We could simply set KDL::Frame() here, however, to support
728  // trajectories for the base joint, we return GetPose();
729  element->frame = element->GetPose();
730  }
731  element->RemoveExpiredChildren();
732  for (std::weak_ptr<KinematicElement> child : element->children)
733  {
734  elements.push(child.lock());
735  }
736  }
737 }
738 
739 void KinematicTree::PublishFrames(const std::string& tf_prefix)
740 {
741  if (Server::IsRos())
742  {
743  const ros::Time timestamp = ros::Time::now();
744 
745  // Step 1: Publish frames for every element in the tree.
746  {
747  int i = 0;
748  for (std::weak_ptr<KinematicElement> element : tree_)
749  {
750  tf::Transform T;
751  tf::transformKDLToTF(element.lock()->frame, T);
752  if (i > 0) debug_tree_[i - 1] = tf::StampedTransform(T, timestamp, tf::resolve(tf_prefix, GetRootFrameName()), tf::resolve(tf_prefix, element.lock()->segment.getName()));
753  ++i;
754  }
756  i = 0;
757  for (KinematicFrame& frame : solution_->frame)
758  {
759  tf::Transform T;
760  tf::transformKDLToTF(frame.temp_B, T);
761  debug_frames_[i * 2] = tf::StampedTransform(T, timestamp, tf::resolve(tf_prefix, GetRootFrameName()), tf::resolve(tf_prefix, "Frame" + std::to_string(i) + "B" + frame.frame_B.lock()->segment.getName()));
762  tf::transformKDLToTF(frame.temp_AB, T);
763  debug_frames_[i * 2 + 1] = tf::StampedTransform(T, timestamp, tf::resolve(tf_prefix, "Frame" + std::to_string(i) + "B" + frame.frame_B.lock()->segment.getName()), tf::resolve(tf_prefix, "Frame" + std::to_string(i) + "A" + frame.frame_A.lock()->segment.getName()));
764  ++i;
765  }
767  }
768 
769  // Step 2: Publish visualisation markers for non-robot-model elements in the tree.
771  {
772  debug_scene_changed_ = false;
773  marker_array_msg_.markers.clear();
774  for (int i = 0; i < tree_.size(); ++i)
775  {
776  // Mesh from path
777  if (tree_[i].lock()->shape_resource_path != "")
778  {
779  visualization_msgs::Marker mrk;
780  mrk.action = visualization_msgs::Marker::ADD;
781  mrk.frame_locked = true;
782  mrk.id = i;
783  mrk.ns = "CollisionObjects";
784  mrk.color = GetColor(tree_[i].lock()->color);
785  mrk.header.frame_id = tf_prefix + "/" + tree_[i].lock()->segment.getName();
786  mrk.pose.orientation.w = 1.0;
787  mrk.type = visualization_msgs::Marker::MESH_RESOURCE;
788  mrk.mesh_resource = tree_[i].lock()->shape_resource_path;
789  mrk.mesh_use_embedded_materials = true;
790  mrk.scale.x = tree_[i].lock()->scale(0);
791  mrk.scale.y = tree_[i].lock()->scale(1);
792  mrk.scale.z = tree_[i].lock()->scale(2);
793  marker_array_msg_.markers.push_back(mrk);
794  }
795  // Non-robot collision objects
796  else if (tree_[i].lock()->shape && (!tree_[i].lock()->closest_robot_link.lock() || !tree_[i].lock()->closest_robot_link.lock()->is_robot_link))
797  {
798  if (tree_[i].lock()->shape->type != shapes::ShapeType::OCTREE)
799  {
800  visualization_msgs::Marker mrk;
801  shapes::constructMarkerFromShape(tree_[i].lock()->shape.get(), mrk);
802  mrk.action = visualization_msgs::Marker::ADD;
803  mrk.frame_locked = true;
804  mrk.id = i;
805  mrk.ns = "CollisionObjects";
806  mrk.color = GetColor(tree_[i].lock()->color);
807  mrk.header.frame_id = tf_prefix + "/" + tree_[i].lock()->segment.getName();
808  mrk.pose.orientation.w = 1.0;
809  marker_array_msg_.markers.push_back(mrk);
810  }
811  // Octree
812  else
813  {
814  // OcTree needs separate handling as it's not supported in constructMarkerFromShape
815  // NB: This only supports a single OctoMap in the KinematicTree as we only have one publisher!
816  octomap::OcTree my_octomap = *std::static_pointer_cast<const shapes::OcTree>(tree_[i].lock()->shape)->octree.get();
817  octomap_msgs::Octomap octomap_msg;
818  octomap_msgs::binaryMapToMsg(my_octomap, octomap_msg);
819  octomap_msg.header.frame_id = tf_prefix + "/" + tree_[i].lock()->segment.getName();
820  octomap_pub_.publish(octomap_msg);
821  }
822  }
823  }
825  }
826  }
827 }
828 
829 KDL::Frame KinematicTree::FK(KinematicFrame& frame) const
830 {
831  frame.temp_A = frame.frame_A.lock()->frame * frame.frame_A_offset;
832  frame.temp_B = frame.frame_B.lock()->frame * frame.frame_B_offset;
833  frame.temp_AB = frame.temp_B.Inverse() * frame.temp_A;
834  return frame.temp_AB;
835 }
836 
837 KDL::Frame KinematicTree::FK(std::shared_ptr<KinematicElement> element_A, const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B, const KDL::Frame& offset_b) const
838 {
839  if (!element_A) ThrowPretty("The pointer to KinematicElement A is dead.");
840  KinematicFrame frame;
841  frame.frame_A = element_A;
842  frame.frame_B = (element_B == nullptr) ? root_ : element_B;
843  frame.frame_A_offset = offset_a;
844  frame.frame_B_offset = offset_b;
845  return FK(frame);
846 }
847 
848 KDL::Frame KinematicTree::FK(const std::string& element_A, const KDL::Frame& offset_a, const std::string& element_B, const KDL::Frame& offset_b) const
849 {
850  std::string name_a = element_A == "" ? root_->segment.getName() : element_A;
851  std::string name_b = element_B == "" ? root_->segment.getName() : element_B;
852  auto A = tree_map_.find(name_a);
853  if (A == tree_map_.end()) ThrowPretty("Can't find link '" << name_a << "'!");
854  auto B = tree_map_.find(name_b);
855  if (B == tree_map_.end()) ThrowPretty("Can't find link '" << name_b << "'!");
856  return FK(A->second.lock(), offset_a, B->second.lock(), offset_b);
857 }
858 
860 {
861  int i = 0;
862  for (KinematicFrame& frame : solution_->frame)
863  {
864  solution_->Phi(i) = FK(frame);
865  ++i;
866  }
867 }
868 
869 Eigen::MatrixXd KinematicTree::Jacobian(std::shared_ptr<KinematicElement> element_A, const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B, const KDL::Frame& offset_b) const
870 {
871  if (!element_A) ThrowPretty("The pointer to KinematicElement A is dead.");
872  KinematicFrame frame;
873  frame.frame_A = element_A;
874  frame.frame_B = (element_B == nullptr) ? root_ : element_B;
875  frame.frame_A_offset = offset_a;
876  frame.frame_B_offset = offset_b;
877  KDL::Jacobian ret(num_controlled_joints_);
878  ComputeJ(frame, ret);
879  return ret.data;
880 }
881 
882 Eigen::MatrixXd KinematicTree::Jacobian(const std::string& element_A, const KDL::Frame& offset_a, const std::string& element_B, const KDL::Frame& offset_b) const
883 {
884  std::string name_a = element_A == "" ? root_->segment.getName() : element_A;
885  std::string name_b = element_B == "" ? root_->segment.getName() : element_B;
886  auto A = tree_map_.find(name_a);
887  if (A == tree_map_.end()) ThrowPretty("Can't find link '" << name_a << "'!");
888  auto B = tree_map_.find(name_b);
889  if (B == tree_map_.end()) ThrowPretty("Can't find link '" << name_b << "'!");
890  return Jacobian(A->second.lock(), offset_a, B->second.lock(), offset_b);
891 }
892 
893 exotica::Hessian KinematicTree::Hessian(std::shared_ptr<KinematicElement> element_A, const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B, const KDL::Frame& offset_b) const
894 {
895  if (!element_A) ThrowPretty("The pointer to KinematicElement A is dead.");
896  KinematicFrame frame;
897  frame.frame_A = element_A;
898  frame.frame_B = (element_B == nullptr) ? root_ : element_B;
899  frame.frame_A_offset = offset_a;
900  frame.frame_B_offset = offset_b;
901  KDL::Jacobian J(num_controlled_joints_);
902  ComputeJ(frame, J);
903  exotica::Hessian hessian = exotica::Hessian::Constant(6, Eigen::MatrixXd::Zero(num_controlled_joints_, num_controlled_joints_));
904  ComputeH(frame, J, hessian);
905  return hessian;
906 }
907 
908 exotica::Hessian KinematicTree::Hessian(const std::string& element_A, const KDL::Frame& offset_a, const std::string& element_B, const KDL::Frame& offset_b) const
909 {
910  std::string name_a = element_A == "" ? root_->segment.getName() : element_A;
911  std::string name_b = element_B == "" ? root_->segment.getName() : element_B;
912  auto A = tree_map_.find(name_a);
913  if (A == tree_map_.end()) ThrowPretty("Can't find link '" << name_a << "'!");
914  auto B = tree_map_.find(name_b);
915  if (B == tree_map_.end()) ThrowPretty("Can't find link '" << name_b << "'!");
916  return this->Hessian(A->second.lock(), offset_a, B->second.lock(), offset_b);
917 }
918 
919 void KinematicTree::ComputeJ(KinematicFrame& frame, KDL::Jacobian& jacobian) const
920 {
921  jacobian.data.setZero();
922  (void)FK(frame); // Create temporary offset frames
923  std::shared_ptr<KinematicElement> it = frame.frame_A.lock();
924  while (it != nullptr)
925  {
926  if (it->is_controlled)
927  {
928  KDL::Frame segment_reference;
929  if (it->parent.lock() != nullptr) segment_reference = it->parent.lock()->frame;
930  jacobian.setColumn(it->control_id, frame.temp_B.M.Inverse() * (segment_reference.M * it->segment.twist(tree_state_(it->id), 1.0)).RefPoint(frame.temp_A.p - it->frame.p));
931  }
932  it = it->parent.lock();
933  }
934  it = frame.frame_B.lock();
935  while (it != nullptr)
936  {
937  if (it->is_controlled)
938  {
939  KDL::Frame segment_reference;
940  if (it->parent.lock() != nullptr) segment_reference = it->parent.lock()->frame;
941  jacobian.setColumn(it->control_id, jacobian.getColumn(it->control_id) - (frame.temp_B.M.Inverse() * (segment_reference.M * it->segment.twist(tree_state_(it->id), 1.0)).RefPoint(frame.temp_A.p - it->frame.p)));
942  }
943  it = it->parent.lock();
944  }
945 }
946 
947 void KinematicTree::ComputeH(KinematicFrame& frame, const KDL::Jacobian& jacobian, exotica::Hessian& hessian) const
948 {
949  hessian.conservativeResize(6);
950  for (int i = 0; i < 6; ++i)
951  {
952  hessian(i).resize(jacobian.columns(), jacobian.columns());
953  hessian(i).setZero();
954  }
955 
956  KDL::Twist axis;
957 
958  for (int i = 0; i < jacobian.columns(); ++i)
959  {
960  axis.rot = jacobian.getColumn(i).rot;
961  for (int j = i; j < jacobian.columns(); ++j)
962  {
963  KDL::Twist Hij = axis * jacobian.getColumn(j);
964  hessian(0)(i, j) = Hij[0];
965  hessian(1)(i, j) = Hij[1];
966  hessian(2)(i, j) = Hij[2];
967  hessian(0)(j, i) = Hij[0];
968  hessian(1)(j, i) = Hij[1];
969  hessian(2)(j, i) = Hij[2];
970  if (i != j)
971  {
972  hessian(3)(j, i) = Hij[3];
973  hessian(4)(j, i) = Hij[4];
974  hessian(5)(j, i) = Hij[5];
975  }
976  }
977  }
978 }
979 
981 {
982  int i = 0;
983  for (KinematicFrame& frame : solution_->frame)
984  {
985  ComputeJ(frame, solution_->jacobian(i));
986  ++i;
987  }
988 }
989 
991 {
992  int i = 0;
993  for (KinematicFrame& frame : solution_->frame)
994  {
995  ComputeH(frame, solution_->jacobian(i), solution_->hessian(i));
996  ++i;
997  }
998 }
999 
1001 {
1002  return model_base_type_;
1003 }
1004 
1006 {
1007  return controlled_base_type_;
1008 }
1009 
1010 std::map<std::string, std::vector<double>> KinematicTree::GetUsedJointLimits() const
1011 {
1012  std::map<std::string, std::vector<double>> limits;
1013  for (auto it : controlled_joints_)
1014  {
1015  limits[it.lock()->segment.getJoint().getName()] = it.lock()->joint_limits;
1016  }
1017  return limits;
1018 }
1019 
1020 robot_model::RobotModelPtr KinematicTree::GetRobotModel() const
1021 {
1022  return model_;
1023 }
1024 
1026 {
1027  Eigen::VectorXd q_rand(num_controlled_joints_);
1028  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1029  {
1030  q_rand(i) = random_state_distributions_[i](generator_);
1031  }
1032  return q_rand;
1033 }
1034 
1036 {
1037  if (lower_in.rows() == num_controlled_joints_)
1038  {
1039  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1040  {
1041  controlled_joints_[i].lock()->joint_limits[LIMIT_POSITION_LOWER] = lower_in(i);
1042  }
1043  }
1044  else
1045  {
1046  ThrowPretty("Got " << lower_in.rows() << " but " << num_controlled_joints_ << " expected.");
1047  }
1048 
1050 }
1051 
1053 {
1054  if (upper_in.rows() == num_controlled_joints_)
1055  {
1056  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1057  {
1058  controlled_joints_[i].lock()->joint_limits[LIMIT_POSITION_UPPER] = upper_in(i);
1059  }
1060  }
1061  else
1062  {
1063  ThrowPretty("Got " << upper_in.rows() << " but " << num_controlled_joints_ << " expected.");
1064  }
1065 
1067 }
1068 
1070 {
1071  if (velocity_in.rows() == num_controlled_joints_)
1072  {
1073  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1074  {
1075  controlled_joints_[i].lock()->velocity_limit = velocity_in(i);
1076  }
1077  }
1078  else if (velocity_in.rows() == 1)
1079  {
1080  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1081  {
1082  controlled_joints_[i].lock()->velocity_limit = velocity_in(0);
1083  }
1084  }
1085  else
1086  {
1087  ThrowPretty("Got " << velocity_in.rows() << " but 1 or " << num_controlled_joints_ << " expected.");
1088  }
1089 
1091 }
1092 
1094 {
1095  if (acceleration_in.rows() == num_controlled_joints_)
1096  {
1097  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1098  {
1099  controlled_joints_[i].lock()->acceleration_limit = acceleration_in(i);
1100  }
1101 
1102  has_acceleration_limit_ = true;
1103  }
1104  else if (acceleration_in.rows() == 1)
1105  {
1106  for (unsigned int i = 0; i < num_controlled_joints_; ++i)
1107  {
1108  controlled_joints_[i].lock()->acceleration_limit = acceleration_in(0);
1109  }
1110 
1111  has_acceleration_limit_ = true;
1112  }
1113  else
1114  {
1115  ThrowPretty("Got " << acceleration_in.rows() << " but 1 or " << num_controlled_joints_ << " expected.");
1116  }
1117 
1119 }
1120 
1122  const std::vector<double>& lower, const std::vector<double>& upper)
1123 {
1125  {
1126  ThrowPretty("This is not a floating joint!");
1127  }
1128  if (lower.size() != 6 || upper.size() != 6)
1129  {
1130  ThrowPretty("Wrong limit data size!");
1131  }
1132  for (int i = 0; i < 6; ++i)
1133  {
1134  controlled_joints_[i].lock()->joint_limits = {lower[i], upper[i]};
1135  }
1136 
1138 }
1139 
1141  const std::vector<double>& lower, const std::vector<double>& upper, const std::vector<double>& velocity, const std::vector<double>& acceleration)
1142 {
1144  {
1145  ThrowPretty("This is not a floating joint!");
1146  }
1147  if (lower.size() != 6 || upper.size() != 6)
1148  {
1149  ThrowPretty("Wrong joint limit data size!");
1150  }
1151  if (velocity.size() != 6 && velocity.size() != 0)
1152  {
1153  ThrowPretty("Wrong velocity limit size!");
1154  }
1155  if (acceleration.size() != 6 && acceleration.size() != 0)
1156  {
1157  ThrowPretty("Wrong acceleration limit size!");
1158  }
1159  for (int i = 0; i < 6; ++i)
1160  {
1161  controlled_joints_[i].lock()->joint_limits = {lower[i], upper[i]};
1162  controlled_joints_[i].lock()->velocity_limit = {velocity.size() != 0 ? velocity[i] : inf};
1163  controlled_joints_[i].lock()->acceleration_limit = {acceleration.size() != 0 ? acceleration[i] : inf};
1164  }
1165 
1167 }
1168 
1170  const std::vector<double>& lower, const std::vector<double>& upper)
1171 {
1173  {
1174  ThrowPretty("This is not a planar joint!");
1175  }
1176  if (lower.size() != 3 || upper.size() != 3)
1177  {
1178  ThrowPretty("Wrong limit data size!");
1179  }
1180  for (int i = 0; i < 3; ++i)
1181  {
1182  controlled_joints_[i].lock()->joint_limits = {lower[i], upper[i]};
1183  }
1184 
1186 }
1187 
1189  const std::vector<double>& lower, const std::vector<double>& upper, const std::vector<double>& velocity, const std::vector<double>& acceleration)
1190 {
1192  {
1193  ThrowPretty("This is not a planar joint!");
1194  }
1195  if (lower.size() != 3 || upper.size() != 3)
1196  {
1197  ThrowPretty("Wrong joint limit data size!");
1198  }
1199  if (velocity.size() != 3 && velocity.size() != 0)
1200  {
1201  ThrowPretty("Wrong velocity limit size!");
1202  }
1203  if (acceleration.size() != 3 && acceleration.size() != 0)
1204  {
1205  ThrowPretty("Wrong acceleration limit size!");
1206  }
1207  for (int i = 0; i < 3; ++i)
1208  {
1209  controlled_joints_[i].lock()->joint_limits = {lower[i], upper[i]};
1210  controlled_joints_[i].lock()->velocity_limit = {velocity.size() != 0 ? velocity[i] : inf};
1211  controlled_joints_[i].lock()->acceleration_limit = {acceleration.size() != 0 ? acceleration[i] : inf};
1212  }
1213 
1215 }
1216 
1218 {
1219  std::vector<std::string> vars = model_->getVariableNames();
1220  for (int i = 0; i < vars.size(); ++i)
1221  {
1222  if (controlled_joints_map_.find(vars[i]) != controlled_joints_map_.end())
1223  {
1224  auto& ControlledJoint = controlled_joints_map_.at(vars[i]);
1225  int index = ControlledJoint.lock()->control_id;
1226 
1227  // moveit_core::RobotModel does not have effort limits
1228  // TODO: use urdf::Model instead
1229 
1230  // Check for bounds, else set limits to inf
1231  if (model_->getVariableBounds(vars[i]).position_bounded_)
1232  {
1233  controlled_joints_[index].lock()->joint_limits = {model_->getVariableBounds(vars[i]).min_position_, model_->getVariableBounds(vars[i]).max_position_};
1234  }
1235  else
1236  {
1237  controlled_joints_[index].lock()->joint_limits = {-inf, inf};
1238  }
1239  if (model_->getVariableBounds(vars[i]).velocity_bounded_)
1240  {
1241  controlled_joints_[index].lock()->velocity_limit = {model_->getVariableBounds(vars[i]).max_velocity_};
1242  }
1243  else
1244  {
1245  controlled_joints_[index].lock()->velocity_limit = {inf};
1246  }
1247  if (model_->getVariableBounds(vars[i]).acceleration_bounded_)
1248  {
1249  controlled_joints_[index].lock()->acceleration_limit = {model_->getVariableBounds(vars[i]).max_acceleration_};
1250  }
1251  else
1252  {
1253  controlled_joints_[index].lock()->acceleration_limit = {inf};
1254  }
1255  }
1256  }
1257 
1261  {
1262  controlled_joints_[0].lock()->joint_limits = {-inf, inf};
1263  controlled_joints_[1].lock()->joint_limits = {-inf, inf};
1264  controlled_joints_[2].lock()->joint_limits = {-inf, inf};
1265  controlled_joints_[3].lock()->joint_limits = {-pi, pi};
1266  controlled_joints_[4].lock()->joint_limits = {-pi, pi};
1267  controlled_joints_[5].lock()->joint_limits = {-pi, pi};
1268  }
1270  {
1271  controlled_joints_[0].lock()->joint_limits = {-inf, inf};
1272  controlled_joints_[1].lock()->joint_limits = {-inf, inf};
1273  controlled_joints_[2].lock()->joint_limits = {-pi, pi};
1274  }
1275 
1277 }
1278 
1280 {
1281  joint_limits_.setZero();
1282  for (int i = 0; i < num_controlled_joints_; ++i)
1283  {
1286  velocity_limits_(i) = controlled_joints_[i].lock()->velocity_limit;
1287  acceleration_limits_(i) = controlled_joints_[i].lock()->acceleration_limit;
1288  }
1289 
1290  // Update random state distributions for generating random controlled states
1292  for (int i = 0; i < num_controlled_joints_; ++i)
1293  {
1294  random_state_distributions_.push_back(std::uniform_real_distribution<double>(joint_limits_(i, LIMIT_POSITION_LOWER), joint_limits_(i, LIMIT_POSITION_UPPER)));
1295  // TODO: Implement random velocities and accelerations
1296  }
1297 }
1298 
1299 const std::string& KinematicTree::GetRootFrameName() const
1300 {
1301  return root_->segment.getName();
1302 }
1303 
1304 const std::string& KinematicTree::GetRootJointName() const
1305 {
1306  return root_joint_name_;
1307 }
1308 
1309 Eigen::VectorXd KinematicTree::GetModelState() const
1310 {
1311  Eigen::VectorXd ret(model_joints_names_.size());
1312 
1313  for (int i = 0; i < model_joints_names_.size(); ++i)
1314  {
1315  ret(i) = tree_state_(model_joints_map_.at(model_joints_names_[i]).lock()->id);
1316  }
1317  return ret;
1318 }
1319 
1320 std::map<std::string, double> KinematicTree::GetModelStateMap() const
1321 {
1322  std::map<std::string, double> ret;
1323  for (const std::string& joint_name : model_joints_names_)
1324  {
1325  ret[joint_name] = tree_state_(model_joints_map_.at(joint_name).lock()->id);
1326  }
1327  return ret;
1328 }
1329 
1330 std::vector<std::string> KinematicTree::GetKinematicChain(const std::string& begin, const std::string& end) const
1331 {
1332  // check existence of requested links
1333  for (const std::string& l : {begin, end})
1334  {
1335  if (!tree_map_.count(l))
1336  {
1337  ThrowPretty("Link '" + l + "' does not exist.");
1338  }
1339  }
1340 
1341  // get chain in reverse order, end...begin
1342  std::vector<std::string> chain;
1343  for (std::weak_ptr<KinematicElement> l = tree_map_.at(end);
1344  l.lock()->segment.getName() != begin;
1345  l = l.lock()->parent, chain.push_back(l.lock()->segment.getJoint().getName()))
1346  {
1347  if (l.lock()->parent.lock() == nullptr)
1348  {
1349  ThrowPretty("There is no connection between '" + begin + "' and '" + end + "'!");
1350  }
1351  }
1352 
1353  // return vector in order, begin...end
1354  std::reverse(chain.begin(), chain.end());
1355  return chain;
1356 }
1357 
1358 std::vector<std::string> KinematicTree::GetKinematicChainLinks(const std::string& begin, const std::string& end) const
1359 {
1360  // check existence of requested links
1361  for (const std::string& l : {begin, end})
1362  {
1363  if (!tree_map_.count(l))
1364  {
1365  ThrowPretty("Link '" + l + "' does not exist.");
1366  }
1367  }
1368 
1369  // get chain in reverse order, end...begin
1370  std::vector<std::string> chain;
1371  for (std::shared_ptr<const KinematicElement> l = tree_map_.at(end).lock(); l->segment.getName() != begin; l = l->parent.lock())
1372  {
1373  chain.push_back(l->segment.getName());
1374  if (l->parent.lock() == nullptr)
1375  {
1376  ThrowPretty("There is no connection between '" + begin + "' and '" + end + "'!");
1377  }
1378  }
1379 
1380  // return vector in order, begin...end
1381  std::reverse(chain.begin(), chain.end());
1382  return chain;
1383 }
1384 
1386 {
1387  // Work-around in case someone passed a vector of size num_controlled_joints_
1388  if (x.rows() == num_controlled_joints_)
1389  {
1390  Update(x);
1391  }
1392  else
1393  {
1394  if (x.rows() != model_joints_names_.size()) ThrowPretty("Model state vector has wrong size, expected " << model_joints_names_.size() << " got " << x.rows());
1395  for (int i = 0; i < model_joints_names_.size(); ++i)
1396  {
1397  tree_state_(model_joints_map_.at(model_joints_names_[i]).lock()->id) = x(i);
1398  }
1399  }
1400 
1401  UpdateTree();
1402  UpdateFK();
1403  if (flags_ & KIN_J) UpdateJ();
1404  if (debug) PublishFrames();
1405 }
1406 
1407 void KinematicTree::SetModelState(const std::map<std::string, double>& x)
1408 {
1409  for (auto& joint : x)
1410  {
1411  try
1412  {
1413  tree_state_(model_joints_map_.at(joint.first).lock()->id) = joint.second;
1414  }
1415  catch (const std::out_of_range& e)
1416  {
1417  WARNING("Robot model does not contain joint '" << joint.first << "' - ignoring.");
1418  }
1419  }
1420  UpdateTree();
1421  UpdateFK();
1422  if (flags_ & KIN_J) UpdateJ();
1423  if (debug) PublishFrames();
1424 }
1425 
1426 Eigen::VectorXd KinematicTree::GetControlledState() const
1427 {
1428  Eigen::VectorXd x(num_controlled_joints_);
1429  for (int i = 0; i < controlled_joints_.size(); ++i)
1430  {
1431  x(i) = tree_state_(controlled_joints_[i].lock()->id);
1432  }
1433  return x;
1434 }
1435 
1436 bool KinematicTree::HasModelLink(const std::string& link) const
1437 {
1438  return std::find(std::begin(model_link_names_), std::end(model_link_names_), link) != std::end(model_link_names_);
1439 }
1440 
1442 {
1443  Eigen::VectorXd x(num_controlled_joints_);
1444  for (int i = 0; i < controlled_joints_.size(); ++i)
1445  {
1446  x(i) = controlled_joints_[i].lock()->segment.getInertia().getMass();
1447  }
1448  return x;
1449 }
1450 
1451 std::map<std::string, shapes::ShapeType> KinematicTree::GetCollisionObjectTypes() const
1452 {
1453  std::map<std::string, shapes::ShapeType> ret;
1454  for (const auto& element : collision_tree_map_)
1455  {
1456  ret[element.second.lock()->segment.getName()] = element.second.lock()->shape->type;
1457  }
1458  return ret;
1459 }
1460 
1461 bool KinematicTree::DoesLinkWithNameExist(std::string name) const
1462 {
1463  // Check whether it exists in TreeMap, which should encompass both EnvironmentTree and model_tree_
1464  return tree_map_.find(name) != tree_map_.end();
1465 }
1466 
1467 std::shared_ptr<KinematicElement> KinematicTree::FindKinematicElementByName(const std::string& frame_name)
1468 {
1469  auto it = tree_map_.find(frame_name);
1470  if (it == tree_map_.end()) ThrowPretty("KinematicElement does not exist:" << frame_name);
1471 
1472  return it->second.lock();
1473 }
1474 } // namespace exotica
exotica::KinematicTree::RequestFrames
std::shared_ptr< KinematicResponse > RequestFrames(const KinematicsRequest &request)
Definition: kinematic_tree.cpp:628
robot_model.h
exotica::KIN_H
@ KIN_H
Definition: kinematic_tree.h:61
exotica::KinematicTree::Hessian
exotica::Hessian Hessian(std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
Definition: kinematic_tree.cpp:893
exotica::KinematicsRequest::frames
std::vector< KinematicFrameRequest > frames
Definition: kinematic_tree.h:97
exotica::KinematicTree::Update
void Update(Eigen::VectorXdRefConst x)
Definition: kinematic_tree.cpp:678
ToStdPtr
std::shared_ptr< T > ToStdPtr(const boost::shared_ptr< T > &p)
Definition: tools.h:148
exotica::KinematicTree::UpdateTree
void UpdateTree()
Definition: kinematic_tree.cpp:695
exotica::KinematicSolution::Phi
Eigen::Map< ArrayFrame > Phi
Definition: kinematic_tree.h:136
exotica::KinematicTree::num_controlled_joints_
int num_controlled_joints_
Number of controlled joints in the joint group.
Definition: kinematic_tree.h:278
exotica::KinematicTree::GetRootFrameName
const std::string & GetRootFrameName() const
Definition: kinematic_tree.cpp:1299
exotica::KinematicTree::marker_array_msg_
visualization_msgs::MarkerArray marker_array_msg_
Definition: kinematic_tree.h:305
exotica::KinematicTree::DoesLinkWithNameExist
bool DoesLinkWithNameExist(std::string name) const
Checks whether a link with this name exists in any of the trees.
Definition: kinematic_tree.cpp:1461
exotica::KinematicResponse::Phi
ArrayFrame Phi
Definition: kinematic_tree.h:120
exotica::PLANAR
@ PLANAR
Definition: kinematic_tree.h:53
exotica::KinematicTree::IsControlledLink
int IsControlledLink(const std::string &link_name)
Definition: kinematic_tree.cpp:600
exotica::KinematicSolution::KinematicSolution
KinematicSolution()
exotica::KinematicTree::model_link_names_
std::vector< std::string > model_link_names_
Definition: kinematic_tree.h:295
exotica::KinematicTree::rd_
std::random_device rd_
Definition: kinematic_tree.h:272
exotica::BaseType
BaseType
Definition: kinematic_tree.h:49
exotica::KinematicResponse::flags
KinematicRequestFlags flags
Definition: kinematic_tree.h:117
exotica::KinematicTree::acceleration_limits_
Eigen::VectorXd acceleration_limits_
Definition: kinematic_tree.h:267
exotica::KinematicTree::SetJointAccelerationLimits
void SetJointAccelerationLimits(Eigen::VectorXdRefConst acceleration_in)
Definition: kinematic_tree.cpp:1093
exotica::KinematicTree::Jacobian
Eigen::MatrixXd Jacobian(std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
Definition: kinematic_tree.cpp:869
exotica::KinematicResponse::jacobian
ArrayJacobian jacobian
Definition: kinematic_tree.h:122
MatrixCompareType::relative
@ relative
s
XmlRpcServer s
exotica::KinematicResponse::KinematicResponse
KinematicResponse()
exotica::GetColor
std_msgs::ColorRGBA GetColor(double r, double g, double b, double a=1.0)
Definition: tools.h:69
exotica::VisualElement::name
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string name
Definition: kinematic_element.h:46
exotica::KinematicTree::state_size_
int state_size_
Definition: kinematic_tree.h:280
exotica::KinematicTree::model_joints_names_
std::vector< std::string > model_joints_names_
Definition: kinematic_tree.h:293
exotica::KinematicTree::generator_
std::mt19937 generator_
Definition: kinematic_tree.h:273
exotica::KinematicFrame::temp_A
KDL::Frame temp_A
Definition: kinematic_tree.h:107
exotica::KinematicTree::model_tree_
std::vector< std::shared_ptr< KinematicElement > > model_tree_
Definition: kinematic_tree.h:285
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
mesh_operations.h
exotica::KinematicTree::UpdateModel
void UpdateModel()
Definition: kinematic_tree.cpp:423
exotica::KinematicTree::ChangeParent
void ChangeParent(const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
Definition: kinematic_tree.cpp:454
shapes::Cylinder
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
exotica::KinematicTree::GetNumControlledJoints
int GetNumControlledJoints() const
Definition: kinematic_tree.cpp:91
exotica::KinematicTree::controlled_joints_map_
std::map< std::string, std::weak_ptr< KinematicElement > > controlled_joints_map_
Definition: kinematic_tree.h:291
shape_operations.h
exotica::Server::SendTransform
static void SendTransform(const tf::StampedTransform &transform)
Definition: server.h:145
exotica::KinematicTree::HasModelLink
bool HasModelLink(const std::string &link) const
Definition: kinematic_tree.cpp:1436
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
tf::StampedTransform
exotica::KinematicTree::solution_
std::shared_ptr< KinematicResponse > solution_
Definition: kinematic_tree.h:297
exotica::KinematicTree::debug_scene_changed_
bool debug_scene_changed_
Definition: kinematic_tree.h:304
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
exotica
Definition: collision_scene.h:46
exotica::FLOATING
@ FLOATING
Definition: kinematic_tree.h:52
exotica::KinematicSolution::Phi_dot
Eigen::Map< ArrayTwist > Phi_dot
Definition: kinematic_tree.h:137
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
exotica::KinematicTree::GetKinematicChain
std::vector< std::string > GetKinematicChain(const std::string &begin, const std::string &end) const
GetKinematicChain get list of joints in a kinematic chain.
Definition: kinematic_tree.cpp:1330
exotica::Hessian
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
Definition: conversions.h:155
exotica::VisualElement::shape_resource_path
std::string shape_resource_path
Definition: kinematic_element.h:48
exotica::pi
constexpr double pi
Definition: kinematic_tree.h:71
exotica::KinematicTree::name_
std::string name_
Definition: kinematic_tree.h:306
exotica::KinematicTree::model_joints_map_
std::map< std::string, std::weak_ptr< KinematicElement > > model_joints_map_
Definition: kinematic_tree.h:292
exotica::KinematicFrame::frame_B_offset
KDL::Frame frame_B_offset
Definition: kinematic_tree.h:105
exotica::KinematicTree::BuildTree
void BuildTree(const KDL::Tree &RobotKinematics)
Definition: kinematic_tree.cpp:164
octomap::OcTree
exotica::LIMIT_POSITION_UPPER
@ LIMIT_POSITION_UPPER
Definition: kinematic_tree.h:67
exotica::KinematicTree::ResetModel
void ResetModel()
Definition: kinematic_tree.cpp:436
exotica::KinematicTree::GetRobotModel
robot_model::RobotModelPtr GetRobotModel() const
Definition: kinematic_tree.cpp:1020
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
octomap_msgs::binaryMapToMsg
static bool binaryMapToMsg(const OctomapT &octomap, Octomap &msg)
exotica::KinematicTree::GetRootJointName
const std::string & GetRootJointName() const
Definition: kinematic_tree.cpp:1304
A
exotica::KinematicsRequest::flags
KinematicRequestFlags flags
Definition: kinematic_tree.h:96
shapes::ShapePtr
std::shared_ptr< Shape > ShapePtr
tf::transformKDLToTF
void transformKDLToTF(const KDL::Frame &k, tf::Transform &t)
exotica::KinematicFrame::temp_AB
KDL::Frame temp_AB
Definition: kinematic_tree.h:106
exotica::KinematicFrameRequest::KinematicFrameRequest
KinematicFrameRequest()
exotica::KinematicTree::num_joints_
int num_joints_
Number of joints of the model (including floating/planar base, passive joints, and uncontrolled joint...
Definition: kinematic_tree.h:279
shapes::Box
name
std::string name
shapes::Sphere
exotica::KinematicTree::ComputeH
void ComputeH(KinematicFrame &frame, const KDL::Jacobian &jacobian, exotica::Hessian &hessian) const
Definition: kinematic_tree.cpp:947
exotica::KinematicTree::model_base_type_
BaseType model_base_type_
Definition: kinematic_tree.h:276
exotica::KinematicFrame
Definition: kinematic_tree.h:100
exotica::KinematicTree::SetJointLimitsLower
void SetJointLimitsLower(Eigen::VectorXdRefConst lower_in)
Definition: kinematic_tree.cpp:1035
exotica::KinematicSolution::jacobian
Eigen::Map< ArrayJacobian > jacobian
Definition: kinematic_tree.h:138
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:53
exotica::KinematicTree::debug_frames_
std::vector< tf::StampedTransform > debug_frames_
Definition: kinematic_tree.h:301
exotica::KinematicRequestFlags
KinematicRequestFlags
Definition: kinematic_tree.h:56
exotica::KinematicTree::UpdateFK
void UpdateFK()
Definition: kinematic_tree.cpp:859
exotica::KinematicTree::debug_tree_
std::vector< tf::StampedTransform > debug_tree_
Definition: kinematic_tree.h:300
exotica::KinematicTree::UpdateJ
void UpdateJ()
Definition: kinematic_tree.cpp:980
HIGHLIGHT
#define HIGHLIGHT(x)
Definition: printable.h:61
exotica::KinematicTree::debug
bool debug
Definition: kinematic_tree.h:251
exotica::KinematicTree::AddEnvironmentElement
std::shared_ptr< KinematicElement > AddEnvironmentElement(const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
Definition: kinematic_tree.cpp:502
exotica::KinematicsRequest::KinematicsRequest
KinematicsRequest()
tf::transformEigenToKDL
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
exotica::KinematicResponse::x
Eigen::VectorXd x
Definition: kinematic_tree.h:119
exotica::inf
constexpr double inf
Definition: kinematic_tree.h:70
exotica::KinematicTree::controlled_joints_
std::vector< std::weak_ptr< KinematicElement > > controlled_joints_
Definition: kinematic_tree.h:290
exotica::KinematicTree::environment_tree_
std::vector< std::shared_ptr< KinematicElement > > environment_tree_
Definition: kinematic_tree.h:286
exotica::KinematicTree::ComputeJ
void ComputeJ(KinematicFrame &frame, KDL::Jacobian &jacobian) const
Definition: kinematic_tree.cpp:919
exotica::KinematicTree::GetRandomControlledState
Eigen::VectorXd GetRandomControlledState()
Random state generation.
Definition: kinematic_tree.cpp:1025
exotica::KinematicTree::GetControlledState
Eigen::VectorXd GetControlledState() const
Definition: kinematic_tree.cpp:1426
shapes::createMeshFromResource
Mesh * createMeshFromResource(const std::string &resource)
exotica::VisualElement::scale
Eigen::Vector3d scale
Definition: kinematic_element.h:50
exotica::KinematicTree::IsControlled
int IsControlled(std::shared_ptr< KinematicElement > joint)
Definition: kinematic_tree.cpp:591
exotica::KinematicTree::flags_
KinematicRequestFlags flags_
Definition: kinematic_tree.h:298
shapes::constructMarkerFromShape
bool constructMarkerFromShape(const Shape *shape, visualization_msgs::Marker &mk, bool use_mesh_triangle_list=false)
tf::Transform
exotica::ParsePath
std::string ParsePath(const std::string &path)
Definition: tools.cpp:150
exotica::KinematicSolution::hessian
Eigen::Map< ArrayHessian > hessian
Definition: kinematic_tree.h:139
exotica::ToString
std::string ToString(const KDL::Frame &s)
Definition: printable.cpp:40
exotica::KinematicTree::tree_map_
std::map< std::string, std::weak_ptr< KinematicElement > > tree_map_
Definition: kinematic_tree.h:287
exotica::KinematicTree::GetModelState
Eigen::VectorXd GetModelState() const
Definition: kinematic_tree.cpp:1309
exotica::KinematicTree::root_joint_name_
std::string root_joint_name_
Definition: kinematic_tree.h:283
exotica::VisualElement
Definition: kinematic_element.h:41
exotica::KinematicTree::AddElementFromSegmentMapIterator
void AddElementFromSegmentMapIterator(KDL::SegmentMap::const_iterator segment, std::shared_ptr< KinematicElement > parent)
Definition: kinematic_tree.cpp:580
exotica::KIN_FK_VEL
@ KIN_FK_VEL
Definition: kinematic_tree.h:60
exotica::KinematicTree::controlled_joints_names_
std::vector< std::string > controlled_joints_names_
Definition: kinematic_tree.h:294
exotica::KinematicFrame::frame_A_offset
KDL::Frame frame_A_offset
Definition: kinematic_tree.h:103
kdl_parser.hpp
exotica::KinematicFrame::frame_A
std::weak_ptr< KinematicElement > frame_A
Definition: kinematic_tree.h:102
exotica::KinematicTree::FindKinematicElementByName
std::shared_ptr< KinematicElement > FindKinematicElementByName(const std::string &frame_name)
Definition: kinematic_tree.cpp:1467
exotica::KinematicTree::GetModelBaseType
BaseType GetModelBaseType() const
Definition: kinematic_tree.cpp:1000
exotica::KinematicTree::GetModelStateMap
std::map< std::string, double > GetModelStateMap() const
Definition: kinematic_tree.cpp:1320
exotica::KinematicTree::UpdateH
void UpdateH()
Definition: kinematic_tree.cpp:990
exotica::KinematicTree::SetJointVelocityLimits
void SetJointVelocityLimits(Eigen::VectorXdRefConst velocity_in)
Definition: kinematic_tree.cpp:1069
start
ROSCPP_DECL void start()
srdf::Model::VirtualJoint
exotica::KinematicFrame::temp_B
KDL::Frame temp_B
Definition: kinematic_tree.h:108
exotica::KinematicSolution::length
int length
Definition: kinematic_tree.h:134
ros::Time
exotica::KinematicFrame::frame_B
std::weak_ptr< KinematicElement > frame_B
Definition: kinematic_tree.h:104
exotica::KinematicTree::collision_tree_map_
std::map< std::string, std::weak_ptr< KinematicElement > > collision_tree_map_
Definition: kinematic_tree.h:288
exotica::KinematicTree::GetControlledBaseType
BaseType GetControlledBaseType() const
Definition: kinematic_tree.cpp:1005
exotica::KinematicTree::SetFloatingBaseLimitsPosXYZEulerZYX
void SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector< double > &lower, const std::vector< double > &upper)
Definition: kinematic_tree.cpp:1121
exotica::KinematicSolution::Create
void Create(std::shared_ptr< KinematicResponse > solution)
Definition: kinematic_tree.cpp:81
urdf
exotica::KinematicTree::controlled_link_names_
std::vector< std::string > controlled_link_names_
Definition: kinematic_tree.h:296
exotica::KinematicTree::controlled_base_type_
BaseType controlled_base_type_
Definition: kinematic_tree.h:277
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
exotica::KinematicResponse
The KinematicResponse is the container to keep kinematic update data. The corresponding KinematicSolu...
Definition: kinematic_tree.h:113
exotica::KinematicTree::AddElement
std::shared_ptr< KinematicElement > AddElement(const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
Definition: kinematic_tree.cpp:537
WARNING_NAMED
#define WARNING_NAMED(name, x)
Definition: printable.h:63
exotica::KinematicsRequest
Definition: kinematic_tree.h:93
exotica::VisualElement::frame
KDL::Frame frame
Definition: kinematic_element.h:49
tf_kdl.h
exotica::KinematicSolution::X
Eigen::Map< Eigen::VectorXd > X
Definition: kinematic_tree.h:135
WARNING
#define WARNING(x)
With endline.
Definition: printable.h:56
exotica::KinematicTree::shapes_pub_
ros::Publisher shapes_pub_
Definition: kinematic_tree.h:302
exotica::KinematicTree::GetKinematicChainLinks
std::vector< std::string > GetKinematicChainLinks(const std::string &begin, const std::string &end) const
GetKinematicChainLinks get the links between begin and end of kinematic chain.
Definition: kinematic_tree.cpp:1358
exotica::KinematicTree::velocity_limits_
Eigen::VectorXd velocity_limits_
Definition: kinematic_tree.h:266
index
unsigned int index
exotica::VisualElement::shape
shapes::ShapePtr shape
Definition: kinematic_element.h:47
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
conversions.h
x
double x
exotica::KinematicTree::SetPlanarBaseLimitsPosXYEulerZ
void SetPlanarBaseLimitsPosXYEulerZ(const std::vector< double > &lower, const std::vector< double > &upper)
Definition: kinematic_tree.cpp:1169
exotica::KinematicTree::octomap_pub_
ros::Publisher octomap_pub_
Definition: kinematic_tree.h:303
exotica::KinematicTree::ResetJointLimits
void ResetJointLimits()
Definition: kinematic_tree.cpp:1217
exotica::FIXED
@ FIXED
Definition: kinematic_tree.h:51
exotica::KinematicSolution::start
int start
Definition: kinematic_tree.h:133
exotica::KinematicTree::UpdateJointLimits
void UpdateJointLimits()
Definition: kinematic_tree.cpp:1279
eigen_kdl.h
exotica::KinematicTree::GetCollisionObjectTypes
std::map< std::string, shapes::ShapeType > GetCollisionObjectTypes() const
Definition: kinematic_tree.cpp:1451
exotica::KinematicResponse::frame
std::vector< KinematicFrame > frame
Definition: kinematic_tree.h:118
exotica::LIMIT_POSITION_LOWER
@ LIMIT_POSITION_LOWER
Definition: kinematic_tree.h:66
tools.h
exotica::KinematicResponse::Phi_dot
ArrayTwist Phi_dot
Definition: kinematic_tree.h:121
exotica::KinematicTree::SetModelState
void SetModelState(Eigen::VectorXdRefConst x)
Definition: kinematic_tree.cpp:1385
server.h
exotica::KinematicTree::tree_state_
Eigen::VectorXd tree_state_
Definition: kinematic_tree.h:281
exotica::KinematicTree::has_acceleration_limit_
bool has_acceleration_limit_
Definition: kinematic_tree.h:268
exotica::KinematicResponse::hessian
ArrayHessian hessian
Definition: kinematic_tree.h:123
exotica::KinematicTree::random_state_distributions_
std::vector< std::uniform_real_distribution< double > > random_state_distributions_
Definition: kinematic_tree.h:274
exotica::KinematicTree::GetNumModelJoints
int GetNumModelJoints() const
Definition: kinematic_tree.cpp:96
exotica::KinematicTree::Instantiate
void Instantiate(const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
Definition: kinematic_tree.cpp:101
exotica::Server::IsRos
static bool IsRos()
Definition: server.h:96
exotica::KinematicTree::PublishFrames
void PublishFrames(const std::string &tf_prefix="exotica")
Definition: kinematic_tree.cpp:739
exotica::KinematicTree::FK
KDL::Frame FK(KinematicFrame &frame) const
Definition: kinematic_tree.cpp:829
kinematic_tree.h
exotica::KinematicTree::SetJointLimitsUpper
void SetJointLimitsUpper(Eigen::VectorXdRefConst upper_in)
Definition: kinematic_tree.cpp:1052
exotica::KinematicTree::GetControlledLinkMass
Eigen::VectorXd GetControlledLinkMass() const
Definition: kinematic_tree.cpp:1441
exotica::KinematicTree::tree_
std::vector< std::weak_ptr< KinematicElement > > tree_
Definition: kinematic_tree.h:284
exotica::KinematicTree::root_
std::shared_ptr< KinematicElement > root_
Definition: kinematic_tree.h:289
exotica::KinematicTree::GetUsedJointLimits
std::map< std::string, std::vector< double > > GetUsedJointLimits() const
Definition: kinematic_tree.cpp:1010
exotica::KinematicTree::model_
robot_model::RobotModelPtr model_
Definition: kinematic_tree.h:282
ros::Time::now
static Time now()
exotica::KinematicTree::joint_limits_
Eigen::MatrixXd joint_limits_
Definition: kinematic_tree.h:265
exotica::VisualElement::color
Eigen::Vector4d color
Definition: kinematic_element.h:51


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sun Jun 2 2024 02:58:18