scene.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
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 
34 
36 #include <exotica_core/scene.h>
37 #include <exotica_core/server.h>
38 #include <exotica_core/setup.h>
39 
40 #include <exotica_core/attach_link_initializer.h>
41 #include <exotica_core/box_shape_initializer.h>
42 #include <exotica_core/collision_scene_initializer.h>
43 #include <exotica_core/cylinder_shape_initializer.h>
44 #include <exotica_core/link_initializer.h>
45 #include <exotica_core/mesh_shape_initializer.h>
46 #include <exotica_core/octree_shape_initializer.h>
47 #include <exotica_core/shape_initializer.h>
48 #include <exotica_core/sphere_shape_initializer.h>
49 #include <exotica_core/trajectory_initializer.h>
50 
51 #include <moveit/version.h>
52 
53 namespace exotica
54 {
55 Scene::Scene() = default;
56 
57 Scene::Scene(const std::string& name) : request_needs_updating_(false)
58 {
59  object_name_ = name;
60 }
61 
62 Scene::~Scene() = default;
63 
64 const std::string& Scene::GetName() const
65 {
66  return object_name_;
67 }
68 
69 void Scene::Instantiate(const SceneInitializer& init)
70 {
71  Object::InstantiateObject(SceneInitializer(init));
72  this->parameters_ = init;
74 
75  // Load robot model and set up kinematics (KinematicTree)
76  robot_model::RobotModelPtr model;
77  if (init.URDF == "" || init.SRDF == "")
78  {
79  Server::Instance()->GetModel(init.RobotDescription, model);
80  }
81  else
82  {
83  Server::Instance()->GetModel(init.URDF, model, init.URDF, init.SRDF);
84  }
85  kinematica_.Instantiate(init.JointGroup, model, object_name_);
86  ps_.reset(new planning_scene::PlanningScene(model));
87 
88  // Write URDF/SRDF to ROS param server
89  if (Server::IsRos() && init.SetRobotDescriptionRosParams && init.URDF != "" && init.SRDF != "")
90  {
91  if (debug_) HIGHLIGHT_NAMED(object_name_, "Setting robot_description and robot_description_semantic from URDF and SRDF initializers");
92  const std::string urdf_string = PathExists(init.URDF) ? LoadFile(init.URDF) : init.URDF;
93  const std::string srdf_string = PathExists(init.SRDF) ? LoadFile(init.SRDF) : init.SRDF;
94  Server::SetParam("/robot_description", urdf_string);
95  Server::SetParam("/robot_description_semantic", srdf_string);
96  }
97 
98  // Set up debug topics if running in ROS mode
99  if (Server::IsRos())
100  {
101  ps_pub_ = Server::Advertise<moveit_msgs::PlanningScene>(object_name_ + (object_name_ == "" ? "" : "/") + "PlanningScene", 1, true);
102  proxy_pub_ = Server::Advertise<visualization_msgs::Marker>(object_name_ + (object_name_ == "" ? "" : "/") + "CollisionProxies", 1, true);
103  if (debug_)
104  HIGHLIGHT_NAMED(object_name_, "Running in debug mode, planning scene will be published to '" << Server::Instance()->GetName() << "/" << object_name_ << "/PlanningScene'");
105  }
106 
107  // Note: Using the LoadScene initializer does not support custom offsets/poses, assumes Identity transform to world_frame
108  if (init.LoadScene != "")
109  {
110  std::vector<std::string> files = ParseList(init.LoadScene, ';');
111  for (const std::string& file : files) LoadSceneFile(file, Eigen::Isometry3d::Identity(), false);
112  }
113 
114  // Add custom links
115  for (const exotica::Initializer& linkInit : init.Links)
116  {
117  LinkInitializer link(linkInit);
118 
119  shapes::ShapePtr link_shape = nullptr;
120  Eigen::Vector4d link_color = Eigen::Vector4d::Zero();
121  if (link.Shape.size() == 1)
122  {
123  ShapeInitializer shape(link.Shape[0]);
124  link_color = shape.Color;
125 
126  if (shape.Type == "Box")
127  {
128  BoxShapeInitializer box(link.Shape[0]);
129  std::cout << "BOX: " << box.Dimensions.transpose() << std::endl;
130  link_shape.reset(new shapes::Box(box.Dimensions.x(), box.Dimensions.y(), box.Dimensions.z()));
131  }
132  else if (shape.Type == "Cylinder")
133  {
134  CylinderShapeInitializer cylinder(link.Shape[0]);
135  link_shape.reset(new shapes::Cylinder(cylinder.Radius, cylinder.Length));
136  }
137  else if (shape.Type == "Mesh")
138  {
139  MeshShapeInitializer mesh(link.Shape[0]);
140  // TODO: This will not support textures.
141  link_shape.reset(shapes::createMeshFromResource(ParsePath(mesh.MeshFilePath), mesh.Scale));
142  }
143  else if (shape.Type == "Octree")
144  {
145  OctreeShapeInitializer octree(link.Shape[0]);
146  link_shape = LoadOctreeAsShape(ParsePath(octree.OctreeFilePath));
147  }
148  else if (shape.Type == "Sphere")
149  {
150  SphereShapeInitializer sphere(link.Shape[0]);
151  link_shape.reset(new shapes::Sphere(sphere.Radius));
152  }
153  else
154  {
155  ThrowPretty("Unrecognized ShapeType: " << shape.Type);
156  }
157  }
158  else if (link.Shape.size() > 1)
159  {
160  ThrowPretty("Only one Shape per Link allowed, given: " << link.Shape.size());
161  }
162 
163  AddObject(link.Name, GetFrame(link.Transform), link.Parent, link_shape, KDL::RigidBodyInertia(link.Mass, GetFrame(link.CenterOfMass).p), link_color, false); // false since CollisionScene is not yet setup
164  }
165 
166  // Check list of robot links to exclude from CollisionScene
167  if (init.RobotLinksToExcludeFromCollisionScene.size() > 0)
168  {
169  for (const auto& link : init.RobotLinksToExcludeFromCollisionScene)
170  {
172  if (debug_) HIGHLIGHT_NAMED("RobotLinksToExcludeFromCollisionScene", link);
173  }
174  }
175 
176  // Check list of world links to exclude from CollisionScene
177  if (init.WorldLinksToExcludeFromCollisionScene.size() > 0)
178  {
179  for (const auto& link : init.WorldLinksToExcludeFromCollisionScene)
180  {
182  if (debug_) HIGHLIGHT_NAMED("WorldLinksToExcludeFromCollisionScene", link);
183  }
184  }
185 
186  // Initialize CollisionScene
187  force_collision_ = init.AlwaysUpdateCollisionScene;
188  if (!init.DoNotInstantiateCollisionScene)
189  {
190  if (init.CollisionScene.size() == 0)
191  {
192  // Not set ==> Default to CollisionSceneFCLLatest for backwards compatibility.
193  collision_scene_ = Setup::CreateCollisionScene("CollisionSceneFCLLatest"); // NB: This is an implicit run-time dependency and thus dangerous! But we don't want to break existing configs...
194  }
195  else if (init.CollisionScene.size() == 1)
196  {
197  collision_scene_ = Setup::CreateCollisionScene(init.CollisionScene[0]);
198  }
199  else
200  {
201  // Only one dynamics solver per scene is allowed, i.e., throw if more than one provided:
202  ThrowPretty("Only one CollisionScene per scene allowed - " << init.CollisionScene.size() << " provided");
203  }
204 
205  collision_scene_->debug_ = this->debug_; // Backwards compatibility - TODO: Remove
206  // collision_scene_->ns_ = ns_ + "/" + collision_scene_->GetObjectName();
207  collision_scene_->Setup(); // TODO: Trigger from Initializer
208  collision_scene_->AssignScene(shared_from_this());
209  collision_scene_->SetAlwaysExternallyUpdatedCollisionScene(force_collision_);
210  }
211 
213  UpdateInternalFrames(false);
214 
215  // Attach links
216  for (const exotica::Initializer& linkInit : init.AttachLinks)
217  {
218  AttachLinkInitializer link(linkInit);
219  if (link.Local)
220  {
221  AttachObjectLocal(link.Name, link.Parent, GetFrame(link.Transform));
222  }
223  else
224  {
225  AttachObject(link.Name, link.Parent);
226  }
227  }
228 
229  // Set up allowed collision matrix (i.e., collision pairs that are filtered/ignored)
231  std::vector<std::string> acm_names;
232  ps_->getAllowedCollisionMatrix().getAllEntryNames(acm_names);
233  for (auto& name1 : acm_names)
234  {
235  for (auto& name2 : acm_names)
236  {
237  collision_detection::AllowedCollision::Type type = collision_detection::AllowedCollision::Type::ALWAYS;
238  ps_->getAllowedCollisionMatrix().getAllowedCollision(name1, name2, type);
239  if (type == collision_detection::AllowedCollision::Type::ALWAYS)
240  {
241  acm.setEntry(name1, name2);
242  }
243  }
244  }
245  if (collision_scene_ != nullptr) collision_scene_->SetACM(acm);
246 
247  // Set up trajectory generators
248  for (const exotica::Initializer& it : init.Trajectories)
249  {
250  TrajectoryInitializer trajInit(it);
251  if (trajInit.File != "")
252  {
253  AddTrajectoryFromFile(trajInit.Link, trajInit.File);
254  }
255  else
256  {
257  AddTrajectory(trajInit.Link, trajInit.Trajectory);
258  }
259  }
260 
261  // Set up DynamicsSolver (requires a fully initialised scene)
262  if (init.DynamicsSolver.size() > 0)
263  {
264  // Only one dynamics solver per scene is allowed, i.e., throw if more than one provided:
265  if (init.DynamicsSolver.size() > 1) ThrowPretty("Only one DynamicsSolver per scene allowed - " << init.DynamicsSolver.size() << " provided");
266 
267  // Create dynamics solver
268  dynamics_solver_ = Setup::CreateDynamicsSolver(init.DynamicsSolver.at(0));
269  dynamics_solver_->AssignScene(shared_from_this());
270  dynamics_solver_->ns_ = ns_ + "/" + dynamics_solver_->GetObjectName();
271 
272  num_positions_ = dynamics_solver_->get_num_positions();
273  num_velocities_ = dynamics_solver_->get_num_velocities();
274  num_controls_ = dynamics_solver_->get_num_controls();
275  num_state_ = dynamics_solver_->get_num_state();
276  num_state_derivative_ = dynamics_solver_->get_num_state_derivative();
277  }
278  else
279  {
281  num_velocities_ = 0;
282  num_controls_ = 0;
285  }
286 
287  // Check if the system has a floating-base, and if so, if it contains a quaternion.
288  // Will need to trigger special logic below to handle this (w.r.t. normalisation).
290 
291  if (debug_) INFO_NAMED(object_name_, "Exotica Scene initialized");
292 }
293 
294 void Scene::RequestKinematics(KinematicsRequest& request, std::function<void(std::shared_ptr<KinematicResponse>)> callback)
295 {
296  kinematic_request_ = request;
297  kinematic_request_callback_ = callback;
300  request_needs_updating_ = false;
301 }
302 
304 {
305  for (auto& it : trajectory_generators_)
306  {
307  it.second.first.lock()->generated_offset = it.second.second->GetPosition(t);
308  }
309 }
310 
312 {
314  {
316  }
317 
319  kinematica_.Update(x);
320  if (force_collision_ && collision_scene_ != nullptr) collision_scene_->UpdateCollisionObjectTransforms();
321  if (debug_) PublishScene();
322 }
323 
325 {
326  std::map<std::string, double> modelState = GetModelStateMap();
327  for (const auto& joint : modelState)
328  {
329  try
330  {
331  ps_->getCurrentStateNonConst().setVariablePosition(joint.first, joint.second);
332  }
333  catch (const std::out_of_range& e)
334  {
335  HIGHLIGHT("Could not find Kinematica joint name in MoveIt: " + joint.first);
336  }
337  }
338 
339  // The floating base joint in MoveIt uses quaternion, while Kinematica uses
340  // RPY [but using rot_x, rot_y, and rot_z as joint names]. Thus, we need to
341  // fix the orientation of the virtual floating base by extracting the RPY
342  // values, converting them to quaternion, and then updating the planning
343  // scene.
345  {
346  KDL::Rotation rot = KDL::Rotation::RPY(modelState[kinematica_.GetRootJointName() + "/rot_x"], modelState[kinematica_.GetRootJointName() + "/rot_y"], modelState[kinematica_.GetRootJointName() + "/rot_z"]);
347  Eigen::Quaterniond quat(Eigen::Map<const Eigen::Matrix3d>(rot.data).transpose());
348  ps_->getCurrentStateNonConst().setVariablePosition(kinematica_.GetRootJointName() + "/rot_x", quat.x());
349  ps_->getCurrentStateNonConst().setVariablePosition(kinematica_.GetRootJointName() + "/rot_y", quat.y());
350  ps_->getCurrentStateNonConst().setVariablePosition(kinematica_.GetRootJointName() + "/rot_z", quat.z());
351  ps_->getCurrentStateNonConst().setVariablePosition(kinematica_.GetRootJointName() + "/rot_w", quat.w());
352  }
353 }
354 
356 {
357  if (Server::IsRos())
358  {
360  }
361 }
362 
363 void Scene::PublishProxies(const std::vector<CollisionProxy>& proxies)
364 {
365  if (Server::IsRos())
366  {
368  }
369 }
370 
371 visualization_msgs::Marker Scene::ProxyToMarker(const std::vector<CollisionProxy>& proxies, const std::string& frame)
372 {
373  visualization_msgs::Marker ret;
374  ret.header.frame_id = "exotica/" + frame;
375  ret.action = visualization_msgs::Marker::ADD;
376  ret.frame_locked = false;
377  ret.ns = "Proxies";
378  ret.color.a = 1.0;
379  ret.id = 0;
380  ret.type = visualization_msgs::Marker::LINE_LIST;
381  ret.points.resize(proxies.size() * 6);
382  ret.colors.resize(proxies.size() * 6);
383  ret.scale.x = 0.005;
384  ret.pose.orientation.w = 1.0;
385  double normalLength = 0.01;
386  std_msgs::ColorRGBA normal = GetColor(0.8, 0.8, 0.8);
387  std_msgs::ColorRGBA far = GetColor(0.5, 0.5, 0.5);
388  std_msgs::ColorRGBA colliding = GetColor(1, 0, 0);
389  for (int i = 0; i < proxies.size(); ++i)
390  {
391  KDL::Vector c1 = KDL::Vector(proxies[i].contact1(0), proxies[i].contact1(1), proxies[i].contact1(2));
392  KDL::Vector c2 = KDL::Vector(proxies[i].contact2(0), proxies[i].contact2(1), proxies[i].contact2(2));
393  KDL::Vector n1 = KDL::Vector(proxies[i].normal1(0), proxies[i].normal1(1), proxies[i].normal1(2));
394  KDL::Vector n2 = KDL::Vector(proxies[i].normal2(0), proxies[i].normal2(1), proxies[i].normal2(2));
395  tf::pointKDLToMsg(c1, ret.points[i * 6]);
396  tf::pointKDLToMsg(c2, ret.points[i * 6 + 1]);
397  tf::pointKDLToMsg(c1, ret.points[i * 6 + 2]);
398  tf::pointKDLToMsg(c1 + n1 * normalLength, ret.points[i * 6 + 3]);
399  tf::pointKDLToMsg(c2, ret.points[i * 6 + 4]);
400  tf::pointKDLToMsg(c2 + n2 * normalLength, ret.points[i * 6 + 5]);
401  ret.colors[i * 6] = ret.colors[i * 6 + 1] = proxies[i].distance > 0 ? far : colliding;
402  ret.colors[i * 6 + 2] = ret.colors[i * 6 + 3] = ret.colors[i * 6 + 4] = ret.colors[i * 6 + 5] = normal;
403  }
404  return ret;
405 }
406 
407 void Scene::UpdatePlanningScene(const moveit_msgs::PlanningScene& scene)
408 {
409  ps_->usePlanningSceneMsg(scene);
412 }
413 
414 void Scene::UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr& world)
415 {
416  ps_->processPlanningSceneWorldMsg(*world);
419 }
420 
422 {
423  if (collision_scene_ != nullptr) collision_scene_->UpdateCollisionObjects(kinematica_.GetCollisionTreeMap());
424 }
425 
427 {
428  if (collision_scene_ == nullptr) ThrowPretty("No CollisionScene initialized!");
429  return collision_scene_;
430 }
431 
432 std::shared_ptr<DynamicsSolver> Scene::GetDynamicsSolver() const
433 {
434  return dynamics_solver_;
435 }
436 
438 {
439  return kinematica_.GetRootFrameName();
440 }
441 
443 {
444  return kinematica_.GetRootJointName();
445 }
446 
447 moveit_msgs::PlanningScene Scene::GetPlanningSceneMsg()
448 {
449  // Update the joint positions in the PlanningScene from Kinematica - we do
450  // not do this on every Update() as it is only required when publishing
451  // the scene and would take unnecessary time otherwise.
453 
454  moveit_msgs::PlanningScene msg;
455  ps_->getPlanningSceneMsg(msg);
456 
457  // The robot link paddings and scales are applied in the CollisionScene
458  // and are not propagated back to the internal MoveIt PlanningScene. Here
459  // we set them in the message that is being returned.
460  msg.link_padding.clear();
461  msg.link_scale.clear();
462  for (auto robot_link : msg.robot_state.joint_state.name)
463  {
464  moveit_msgs::LinkPadding padding;
465  padding.link_name = robot_link;
466  padding.padding = (collision_scene_ != nullptr) ? collision_scene_->GetRobotLinkPadding() : 0.0;
467  msg.link_padding.push_back(padding);
468 
469  moveit_msgs::LinkScale scale;
470  scale.link_name = robot_link;
471  scale.scale = (collision_scene_ != nullptr) ? collision_scene_->GetRobotLinkScale() : 1.0;
472  msg.link_scale.push_back(scale);
473  }
474 
475  // As we cannot apply world link scalings in the message itself, we need to
476  // manually scale the objects.
477  // TODO(wxm): Recreate as updated poses won't be reflected (e.g. trajectories)
478  if (collision_scene_ != nullptr && (collision_scene_->GetWorldLinkScale() != 1.0 || collision_scene_->GetWorldLinkPadding() > 0.0))
479  {
480  for (auto it : msg.world.collision_objects)
481  {
482  // Primitives
483  for (auto primitive : it.primitives)
484  {
486  tmp->scaleAndPadd(collision_scene_->GetWorldLinkScale(), collision_scene_->GetWorldLinkPadding());
487  shapes::ShapeMsg tmp_msg;
488  shapes::constructMsgFromShape(const_cast<shapes::Shape*>(tmp.get()), tmp_msg);
489  primitive = boost::get<shape_msgs::SolidPrimitive>(tmp_msg);
490  }
491 
492  // Meshes
493  for (auto mesh : it.meshes)
494  {
496  tmp->scaleAndPadd(collision_scene_->GetWorldLinkScale(), collision_scene_->GetWorldLinkPadding());
497  shapes::ShapeMsg tmp_msg;
498  shapes::constructMsgFromShape(const_cast<shapes::Shape*>(tmp.get()), tmp_msg);
499  mesh = boost::get<shape_msgs::Mesh>(tmp_msg);
500  }
501 
502  // NB: Scaling and padding does not apply to planes
503  }
504  }
505 
506  return msg;
507 }
508 
510 {
511  return kinematica_;
512 }
513 
514 std::vector<std::string> Scene::GetControlledJointNames()
515 {
517 }
518 
519 std::vector<std::string> Scene::GetControlledLinkNames()
520 {
522 }
523 
524 std::vector<std::string> Scene::GetModelLinkNames()
525 {
527 }
528 
529 std::vector<std::string> Scene::GetModelJointNames()
530 {
532 }
533 
534 Eigen::VectorXd Scene::GetModelState()
535 {
536  return kinematica_.GetModelState();
537 }
538 
539 std::map<std::string, double> Scene::GetModelStateMap()
540 {
541  return kinematica_.GetModelStateMap();
542 }
543 
544 std::map<std::string, std::weak_ptr<KinematicElement>> Scene::GetTreeMap()
545 {
546  return kinematica_.GetTreeMap();
547 }
548 
549 void Scene::SetModelState(Eigen::VectorXdRefConst x, double t, bool update_traj)
550 {
552  {
554  }
555 
556  if (update_traj) UpdateTrajectoryGenerators(t);
557  // Update Kinematica internal state
559 
560  if (force_collision_ && collision_scene_ != nullptr) collision_scene_->UpdateCollisionObjectTransforms();
561  if (debug_) PublishScene();
562 }
563 
564 void Scene::SetModelState(const std::map<std::string, double>& x, double t, bool update_traj)
565 {
567  {
569  }
570 
571  if (update_traj) UpdateTrajectoryGenerators(t);
572  // Update Kinematica internal state
574 
575  if (force_collision_ && collision_scene_ != nullptr) collision_scene_->UpdateCollisionObjectTransforms();
576  if (debug_) PublishScene();
577 }
578 
579 Eigen::VectorXd Scene::GetControlledState()
580 {
582 }
583 
584 void Scene::LoadScene(const std::string& scene, const KDL::Frame& offset, bool update_collision_scene)
585 {
586  Eigen::Isometry3d tmp_offset;
587  tf::transformKDLToEigen(offset, tmp_offset);
588  LoadScene(scene, tmp_offset, update_collision_scene);
589 }
590 
591 void Scene::LoadScene(const std::string& scene, const Eigen::Isometry3d& offset, bool update_collision_scene)
592 {
593  std::stringstream ss(scene);
594  LoadSceneFromStringStream(ss, offset, update_collision_scene);
595 }
596 
597 void Scene::LoadSceneFile(const std::string& file_name, const KDL::Frame& offset, bool update_collision_scene)
598 {
599  Eigen::Isometry3d tmp_offset;
600  tf::transformKDLToEigen(offset, tmp_offset);
601  LoadSceneFile(file_name, tmp_offset, update_collision_scene);
602 }
603 
604 void Scene::LoadSceneFile(const std::string& file_name, const Eigen::Isometry3d& offset, bool update_collision_scene)
605 {
606  std::ifstream ss(ParsePath(file_name));
607  if (!ss.is_open()) ThrowPretty("Cant read file '" << ParsePath(file_name) << "'!");
608  LoadSceneFromStringStream(ss, offset, update_collision_scene);
609 }
610 
611 void Scene::LoadSceneFromStringStream(std::istream& in, const Eigen::Isometry3d& offset, bool update_collision_scene)
612 {
613 #if ROS_VERSION_MINIMUM(1, 14, 0) // if ROS version >= ROS_MELODIC
614  ps_->loadGeometryFromStream(in, offset);
615 #else
616  ps_->loadGeometryFromStream(in, Eigen::Affine3d(offset));
617 #endif
618 
620  if (update_collision_scene) UpdateInternalFrames();
621 }
622 
623 std::string Scene::GetScene()
624 {
625  std::stringstream ss;
626  ps_->saveGeometryToStream(ss);
627  // TODO: include all custom environment scene objects
628  return ss.str();
629 }
630 
632 {
633  ps_->removeAllCollisionObjects();
634  // TODO: remove all custom environment scene objects
636 }
637 
638 void Scene::UpdateInternalFrames(bool update_request)
639 {
640  for (auto& it : custom_links_)
641  {
642  Eigen::Isometry3d pose;
643  tf::transformKDLToEigen(it->segment.getFrameToTip(), pose);
644  std::string shape_resource_path = it->shape_resource_path;
645  Eigen::Vector3d scale = it->scale;
646  it = kinematica_.AddElement(it->segment.getName(), pose, it->parent_name, it->shape, it->segment.getInertia(), it->color, it->visual, it->is_controlled);
647  it->shape_resource_path = shape_resource_path;
648  it->scale = scale;
649  }
650 
651  auto trajectory_generators_copy = trajectory_generators_;
652  trajectory_generators_.clear();
653  for (auto& traj : trajectory_generators_copy)
654  {
655  AddTrajectory(traj.first, traj.second.second);
656  }
657 
658  for (auto& link : attached_objects_)
659  {
660  AttachObjectLocal(link.first, link.second.parent, link.second.pose);
661  }
662 
664 
665  if (update_request)
666  {
669  }
670 
672 
673  request_needs_updating_ = false;
674 }
675 
677 {
679 
680  // Add world objects
681  std::map<std::string, int> visual_map;
682  for (const auto& object : *ps_->getWorld())
683  {
684  if (object.second->shapes_.size())
685  {
686  // Use the first collision shape as the origin of the object
687  Eigen::Isometry3d obj_transform;
688  obj_transform.translation() = object.second->shape_poses_[0].translation();
689  obj_transform.linear() = object.second->shape_poses_[0].rotation();
690  std::shared_ptr<KinematicElement> element = kinematica_.AddEnvironmentElement(object.first, obj_transform);
691  std::vector<VisualElement> visuals;
692  for (int i = 0; i < object.second->shape_poses_.size(); ++i)
693  {
694  Eigen::Isometry3d shape_transform;
695  shape_transform.translation() = object.second->shape_poses_[i].translation();
696  shape_transform.linear() = object.second->shape_poses_[i].rotation();
697  Eigen::Isometry3d trans = obj_transform.inverse() * shape_transform;
698  VisualElement visual;
699  std::string name = object.first;
700  // Check for name duplicates after loading from scene files
701  const auto& it = visual_map.find(name);
702  if (it != visual_map.end())
703  {
704  it->second++;
705  name = name + "_" + std::to_string(it->second);
706  }
707  else
708  {
709  visual_map[name] = 0;
710  }
711  visual.name = name;
712  visual.shape = shapes::ShapePtr(object.second->shapes_[i]->clone());
713  tf::transformEigenToKDL(trans, visual.frame);
714  if (ps_->hasObjectColor(object.first))
715  {
716  auto color_msg = ps_->getObjectColor(object.first);
717  visual.color = Eigen::Vector4d(color_msg.r, color_msg.g, color_msg.b, color_msg.a);
718  kinematica_.AddEnvironmentElement(object.first + "_collision_" + std::to_string(i), trans, object.first, object.second->shapes_[i], KDL::RigidBodyInertia::Zero(), visual.color);
719  }
720  else
721  {
722  kinematica_.AddEnvironmentElement(object.first + "_collision_" + std::to_string(i), trans, object.first, object.second->shapes_[i]);
723  }
724  if (visual.shape) visuals.push_back(visual);
725  }
726  element->visual = visuals;
727  }
728  else
729  {
730  HIGHLIGHT("Object with no shapes ('" << object.first << "')");
731  }
732  }
733 
734  // Add robot collision objects
735  ps_->getCurrentStateNonConst().update(true);
736 #if MOVEIT_VERSION_MAJOR >= 1 && MOVEIT_VERSION_MINOR >= 1
737  const std::vector<const robot_model::LinkModel*>& links = ps_->getCollisionEnv()->getRobotModel()->getLinkModelsWithCollisionGeometry();
738 #else
739  const std::vector<const robot_model::LinkModel*>& links = ps_->getCollisionRobot()->getRobotModel()->getLinkModelsWithCollisionGeometry();
740 #endif
741 
742  int last_controlled_joint_id = -1;
743  std::string last_controlled_joint_name = "";
747  for (int i = 0; i < links.size(); ++i)
748  {
749  // Check whether link is excluded from collision checking
751  {
752  continue;
753  }
754 
755  Eigen::Isometry3d obj_transform;
756  obj_transform.translation() = ps_->getCurrentState().getGlobalLinkTransform(links[i]).translation();
757  obj_transform.linear() = ps_->getCurrentState().getGlobalLinkTransform(links[i]).rotation();
758 
759  int joint_id = GetKinematicTree().IsControlledLink(links[i]->getName());
760  if (joint_id != -1)
761  {
762  if (last_controlled_joint_id != joint_id)
763  {
764  last_controlled_joint_name = GetKinematicTree().GetControlledJointNames()[joint_id];
765  last_controlled_joint_id = joint_id;
766  }
767  }
768 
769  for (int j = 0; j < links[i]->getShapes().size(); ++j)
770  {
771  // // Workaround for issue #172
772  // // To disable collisions with visual tags, we define a sphere of radius 0 which we will ignore here
773  // // This is in contrast to IHMC's convention where a sphere of radius 0 in the SDF is a desired contact point
774  // if (links[i]->getShapes()[j]->type == shapes::ShapeType::SPHERE)
775  // if (static_cast<const shapes::Sphere*>(links[i]->getShapes()[j].get())->radius == 0.0)
776  // continue;
777 
778  Eigen::Affine3d collisionBodyTransform_affine = ps_->getCurrentState().getCollisionBodyTransform(links[i], j);
779  Eigen::Isometry3d collisionBodyTransform;
780  collisionBodyTransform.translation() = collisionBodyTransform_affine.translation();
781  collisionBodyTransform.linear() = collisionBodyTransform_affine.rotation();
782  Eigen::Isometry3d trans = obj_transform.inverse(Eigen::Isometry) * collisionBodyTransform;
783 
784  std::string collision_element_name = links[i]->getName() + "_collision_" + std::to_string(j);
785  std::shared_ptr<KinematicElement> element = kinematica_.AddElement(collision_element_name, trans, links[i]->getName(), links[i]->getShapes()[j]);
786  model_link_to_collision_element_map_[links[i]->getName()].push_back(element);
787 
788  // Set up mappings
789  model_link_to_collision_link_map_[links[i]->getName()].push_back(collision_element_name);
790 
791  if (last_controlled_joint_name != "")
792  {
793  controlled_joint_to_collision_link_map_[last_controlled_joint_name].push_back(collision_element_name);
794  }
795  }
796  }
797 
799 
801 }
802 
803 void Scene::AddObject(const std::string& name, const KDL::Frame& transform, const std::string& parent, shapes::ShapeConstPtr shape, const KDL::RigidBodyInertia& inertia, const Eigen::Vector4d& color, bool update_collision_scene)
804 {
805  if (kinematica_.DoesLinkWithNameExist(name)) ThrowPretty("Link '" << name << "' already exists in the scene!");
806  std::string parent_name = (parent == "") ? kinematica_.GetRootFrameName() : parent;
807  if (!kinematica_.DoesLinkWithNameExist(parent_name)) ThrowPretty("Can't find parent '" << parent_name << "'!");
808  Eigen::Isometry3d pose;
809  tf::transformKDLToEigen(transform, pose);
810  custom_links_.push_back(kinematica_.AddElement(name, pose, parent_name, shape, inertia, color));
811  if (update_collision_scene) UpdateCollisionObjects();
812 }
813 
814 void Scene::AddObject(const std::string& name, const KDL::Frame& transform, const std::string& parent, const std::string& shape_resource_path, const Eigen::Vector3d& scale, const KDL::RigidBodyInertia& inertia, const Eigen::Vector4d& color, bool update_collision_scene)
815 {
816  if (kinematica_.DoesLinkWithNameExist(name)) ThrowPretty("Link '" << name << "' already exists in the scene!");
817  std::string parent_name = (parent == "") ? kinematica_.GetRootFrameName() : parent;
818  if (!kinematica_.DoesLinkWithNameExist(parent_name)) ThrowPretty("Can't find parent '" << parent_name << "'!");
819  Eigen::Isometry3d pose;
820  tf::transformKDLToEigen(transform, pose);
821  custom_links_.push_back(kinematica_.AddElement(name, pose, parent_name, shape_resource_path, scale, inertia, color));
824  if (update_collision_scene) UpdateCollisionObjects();
825 }
826 
827 void Scene::AddObjectToEnvironment(const std::string& name, const KDL::Frame& transform, shapes::ShapeConstPtr shape, const Eigen::Vector4d& color, const bool update_collision_scene)
828 {
829  if (kinematica_.HasModelLink(name))
830  {
831  throw std::runtime_error("link '" + name + "' already exists in kinematic tree");
832  }
833  Eigen::Isometry3d pose;
834  tf::transformKDLToEigen(transform, pose);
835  ps_->getWorldNonConst()->addToObject(name, shape, pose);
836  ps_->setObjectColor(name, GetColor(color));
838  if (update_collision_scene) UpdateInternalFrames();
839 }
840 
841 void Scene::RemoveObject(const std::string& name)
842 {
843  auto it = std::begin(custom_links_);
844  while (it != std::end(custom_links_))
845  {
846  if ((*it)->segment.getName() == name)
847  {
848  custom_links_.erase(it);
851  return;
852  }
853  else
854  {
855  ++it;
856  }
857  }
858  ThrowPretty("Link " << name << " not removed as it cannot be found.");
859 }
860 
861 void Scene::AttachObject(const std::string& name, const std::string& parent)
862 {
863  kinematica_.ChangeParent(name, parent, KDL::Frame::Identity(), false);
864  attached_objects_[name] = AttachedObject(parent);
865 }
866 
867 void Scene::AttachObjectLocal(const std::string& name, const std::string& parent, const KDL::Frame& pose)
868 {
869  kinematica_.ChangeParent(name, parent, pose, true);
870  attached_objects_[name] = AttachedObject(parent, pose);
871 }
872 
873 void Scene::AttachObjectLocal(const std::string& name, const std::string& parent, const Eigen::VectorXd& pose)
874 {
875  AttachObjectLocal(name, parent, GetFrame(pose));
876 }
877 
878 void Scene::DetachObject(const std::string& name)
879 {
880  if (!HasAttachedObject(name)) ThrowPretty("'" << name << "' is not attached to the robot!");
881  auto object = attached_objects_.find(name);
882  kinematica_.ChangeParent(name, "", KDL::Frame::Identity(), false);
883  attached_objects_.erase(object);
884 }
885 
886 bool Scene::HasAttachedObject(const std::string& name)
887 {
888  return attached_objects_.find(name) != attached_objects_.end();
889 }
890 
891 void Scene::AddTrajectoryFromFile(const std::string& link, const std::string& traj)
892 {
893  AddTrajectory(link, LoadFile(traj));
894 }
895 
896 void Scene::AddTrajectory(const std::string& link, const std::string& traj)
897 {
898  AddTrajectory(link, std::shared_ptr<Trajectory>(new Trajectory(traj)));
899 }
900 
901 void Scene::AddTrajectory(const std::string& link, std::shared_ptr<Trajectory> traj)
902 {
903  const auto& tree = kinematica_.GetTreeMap();
904  const auto& it = tree.find(link);
905  if (it == tree.end()) ThrowPretty("Can't find link '" << link << "'!");
906  if (traj->GetDuration() == 0.0) ThrowPretty("The trajectory is empty!");
907  trajectory_generators_[link] = std::pair<std::weak_ptr<KinematicElement>, std::shared_ptr<Trajectory>>(it->second, traj);
908  it->second.lock()->is_trajectory_generated = true;
909 }
910 
911 std::shared_ptr<Trajectory> Scene::GetTrajectory(const std::string& link)
912 {
913  const auto& it = trajectory_generators_.find(link);
914  if (it == trajectory_generators_.end()) ThrowPretty("No trajectory generator defined for link '" << link << "'!");
915  return it->second.second;
916 }
917 
918 void Scene::RemoveTrajectory(const std::string& link)
919 {
920  const auto& it = trajectory_generators_.find(link);
921  if (it == trajectory_generators_.end()) ThrowPretty("No trajectory generator defined for link '" << link << "'!");
922  it->second.first.lock()->is_trajectory_generated = false;
923  trajectory_generators_.erase(it);
924 }
925 
927 {
928  return num_positions_;
929 }
930 
932 {
933  return num_velocities_;
934 }
935 
937 {
938  return num_controls_;
939 }
940 
942 {
943  return num_state_;
944 }
945 
947 {
948  return num_state_derivative_;
949 }
950 
952 {
954 }
955 
956 } // namespace exotica
bool PathExists(const std::string &path)
Definition: tools.cpp:199
void AddTrajectory(const std::string &link, const std::string &traj)
Definition: scene.cpp:896
void LoadSceneFromStringStream(std::istream &in, const Eigen::Isometry3d &offset, bool update_collision_scene)
Definition: scene.cpp:611
#define HIGHLIGHT(x)
Definition: printable.h:61
void UpdateCollisionObjects()
Definition: scene.cpp:421
virtual ~Scene()
void PublishScene()
Definition: scene.cpp:355
planning_scene::PlanningScenePtr ps_
Internal MoveIt planning scene.
Definition: scene.h:210
std::map< std::string, double > GetModelStateMap() const
std::vector< std::string > GetControlledJointNames()
Definition: scene.cpp:514
static std::shared_ptr< exotica::CollisionScene > CreateCollisionScene(const std::string &type, bool prepend=true)
Definition: setup.h:66
std::string GetScene()
Definition: scene.cpp:623
bool DoesLinkWithNameExist(std::string name) const
Checks whether a link with this name exists in any of the trees.
bool get_has_quaternion_floating_base() const
Definition: scene.cpp:951
void Update(Eigen::VectorXdRefConst x)
void publish(const boost::shared_ptr< M > &message) const
const std::vector< std::string > & GetControlledLinkNames() const
void LoadSceneFile(const std::string &file_name, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
Definition: scene.cpp:604
std::vector< std::string > GetModelJointNames()
Definition: scene.cpp:529
std::string GetRootFrameName()
Definition: scene.cpp:437
void UpdateMoveItPlanningScene()
Updates the internal state of the MoveIt PlanningScene from Kinematica.
Definition: scene.cpp:324
void PublishProxies(const std::vector< CollisionProxy > &proxies)
Definition: scene.cpp:363
BaseType GetModelBaseType() const
void InstantiateObject(const Initializer &init)
Definition: object.h:71
void SetModelState(Eigen::VectorXdRefConst x, double t=0, bool update_traj=true)
Definition: scene.cpp:549
int get_num_positions() const
Definition: scene.cpp:926
std::string getName(void *handle)
int get_num_state() const
Definition: scene.cpp:941
std::vector< std::string > ParseList(const std::string &value, char token= ',')
Definition: conversions.h:321
std::shared_ptr< DynamicsSolver > GetDynamicsSolver() const
Returns a pointer to the CollisionScene.
Definition: scene.cpp:432
#define ThrowPretty(m)
Definition: exception.h:36
std::vector< std::shared_ptr< KinematicElement > > custom_links_
List of frames/links added on top of robot links and scene objects defined in the MoveIt scene...
Definition: scene.h:221
void AddTrajectoryFromFile(const std::string &link, const std::string &traj)
Definition: scene.cpp:891
void AddObject(const std::string &name, const KDL::Frame &transform=KDL::Frame(), 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 bool update_collision_scene=true)
Definition: scene.cpp:803
void LoadScene(const std::string &scene, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
Definition: scene.cpp:591
std_msgs::ColorRGBA GetColor(double r, double g, double b, double a=1.0)
Definition: tools.h:69
std::string LoadFile(const std::string &path)
Definition: tools.cpp:184
void RemoveObject(const std::string &name)
Definition: scene.cpp:841
visualization_msgs::Marker ProxyToMarker(const std::vector< CollisionProxy > &proxies, const std::string &frame)
Definition: scene.cpp:371
std::shared_ptr< Shape > ShapePtr
const std::vector< std::string > & GetModelLinkNames() const
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
const std::string & GetRootJointName() const
static std::shared_ptr< Server > Instance()
Get the server.
Definition: server.h:65
exotica::KinematicTree kinematica_
The kinematica tree.
Definition: scene.h:195
shapes::ShapePtr shape
Eigen::VectorXd GetModelState() const
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)
int num_state_derivative_
"ndx"
Definition: scene.h:207
std::string ns_
Definition: object.h:84
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetTreeMap() const
void UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr &world)
Update the collision scene from a moveit_msgs::PlanningSceneWorld.
Definition: scene.cpp:414
std::string object_name_
Definition: object.h:85
void Instantiate(const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
int GetNumModelJoints() const
std::set< std::string > robot_links_to_exclude_from_collision_scene_
List of robot links to be excluded from the collision scene.
Definition: scene.h:235
std::shared_ptr< KinematicResponse > kinematic_solution_
Definition: scene.h:241
std::set< std::string > world_links_to_exclude_from_collision_scene_
List of world links to be excluded from the collision scene.
Definition: scene.h:238
Eigen::VectorXd GetControlledState() const
bool force_collision_
Definition: scene.h:225
std::string GetRootJointName()
Definition: scene.cpp:442
void Update(Eigen::VectorXdRefConst x, double t=0)
Definition: scene.cpp:311
static Rotation RPY(double roll, double pitch, double yaw)
bool debug_
Definition: object.h:86
int num_controls_
"nu"
Definition: scene.h:205
std::shared_ptr< DynamicsSolver > dynamics_solver_
The dynamics solver.
Definition: scene.h:201
Eigen::VectorXd GetModelState()
Definition: scene.cpp:534
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetCollisionTreeMap() const
const std::vector< std::string > & GetModelJointNames() const
ros::Publisher proxy_pub_
Definition: scene.h:214
const std::string & GetRootFrameName() const
int IsControlledLink(const std::string &link_name)
bool HasModelLink(const std::string &link) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string name
void DetachObject(const std::string &name)
Detaches an object and leaves it a at its current world location. This effectively attaches the objec...
Definition: scene.cpp:878
moveit_msgs::PlanningScene GetPlanningSceneMsg()
Returns the current robot configuration and collision environment as a moveit_msgs::PlanningScene.
Definition: scene.cpp:447
std::map< std::string, double > GetModelStateMap()
Definition: scene.cpp:539
std::shared_ptr< Trajectory > GetTrajectory(const std::string &link)
Definition: scene.cpp:911
void setEntry(const std::string &name1, const std::string &name2)
static RigidBodyInertia Zero()
void AttachObjectLocal(const std::string &name, const std::string &parent, const KDL::Frame &pose)
Attaches existing object to a new parent specifying an offset in the new parent local frame...
Definition: scene.cpp:867
virtual std::string type() const
Type Information wrapper: must be virtual so that it is polymorphic...
Definition: object.h:61
const CollisionScenePtr & GetCollisionScene() const
Returns a pointer to the CollisionScene.
Definition: scene.cpp:426
void AttachObject(const std::string &name, const std::string &parent)
Attaches existing object to a new parent. E.g. attaching a grasping target to the end-effector...
Definition: scene.cpp:861
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
static std::shared_ptr< exotica::DynamicsSolver > CreateDynamicsSolver(const std::string &type, bool prepend=true)
Definition: setup.h:67
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
int GetNumControlledJoints() const
void ChangeParent(const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
std::map< std::string, std::vector< std::string > > controlled_joint_to_collision_link_map_
Mapping between controlled joint name and collision links.
Definition: scene.h:232
const std::string & GetName() const
Definition: scene.cpp:64
ros::Publisher ps_pub_
Visual debug.
Definition: scene.h:213
KinematicsRequest kinematic_request_
Definition: scene.h:240
static void SetParam(const std::string &name, T &param)
Definition: server.h:110
void UpdatePlanningScene(const moveit_msgs::PlanningScene &scene)
Update the collision scene from a moveit_msgs::PlanningScene.
Definition: scene.cpp:407
CollisionScenePtr collision_scene_
The collision scene.
Definition: scene.h:198
#define INFO_NAMED(name, x)
Definition: printable.h:64
int num_positions_
"nq"
Definition: scene.h:203
int get_num_state_derivative() const
Definition: scene.cpp:946
const std::vector< std::string > & GetControlledJointNames() const
std::vector< std::string > GetModelLinkNames()
Definition: scene.cpp:524
std::string ParsePath(const std::string &path)
Definition: tools.cpp:145
std::vector< std::string > GetControlledLinkNames()
Definition: scene.cpp:519
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
Mesh * createMeshFromResource(const std::string &resource)
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
std::map< std::string, std::weak_ptr< KinematicElement > > GetTreeMap()
Definition: scene.cpp:544
std::map< std::string, AttachedObject > attached_objects_
List of attached objects These objects will be reattached if the scene gets reloaded.
Definition: scene.h:218
exotica::KinematicTree & GetKinematicTree()
Definition: scene.cpp:509
std::shared_ptr< CollisionScene > CollisionScenePtr
void UpdateSceneFrames()
Updates exotica scene object frames from the MoveIt scene.
Definition: scene.cpp:676
static Frame Identity()
void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m)
std::map< std::string, std::pair< std::weak_ptr< KinematicElement >, std::shared_ptr< Trajectory > > > trajectory_generators_
Definition: scene.h:223
std::function< void(std::shared_ptr< KinematicResponse >)> kinematic_request_callback_
Definition: scene.h:242
std::shared_ptr< shapes::Shape > LoadOctreeAsShape(const std::string &file_path)
Definition: tools.cpp:126
std::map< std::string, std::vector< std::string > > model_link_to_collision_link_map_
Mapping between model link names and collision links.
Definition: scene.h:228
Eigen::VectorXd GetControlledState()
Definition: scene.cpp:579
void transformKDLToEigen(const KDL::Frame &k, Eigen::Affine3d &e)
int num_state_
"nx"
Definition: scene.h:206
int get_num_controls() const
Definition: scene.cpp:936
static bool IsRos()
Definition: server.h:96
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)
bool request_needs_updating_
Definition: scene.h:243
void RequestKinematics(KinematicsRequest &request, std::function< void(std::shared_ptr< KinematicResponse >)> callback)
Definition: scene.cpp:294
std::shared_ptr< KinematicResponse > RequestFrames(const KinematicsRequest &request)
KDL::Frame GetFrame(Eigen::VectorXdRefConst val)
Definition: conversions.cpp:52
void UpdateInternalFrames(bool update_request=true)
Definition: scene.cpp:638
std::map< std::string, std::vector< std::shared_ptr< KinematicElement > > > model_link_to_collision_element_map_
Definition: scene.h:229
bool HasAttachedObject(const std::string &name)
Definition: scene.cpp:886
void RemoveTrajectory(const std::string &link)
Definition: scene.cpp:918
void SetModelState(Eigen::VectorXdRefConst x)
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
void AddObjectToEnvironment(const std::string &name, const KDL::Frame &transform=KDL::Frame(), shapes::ShapeConstPtr shape=nullptr, const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const bool update_collision_scene=true)
Definition: scene.cpp:827
int num_velocities_
"nv"
Definition: scene.h:204
void UpdateTrajectoryGenerators(double t=0)
Definition: scene.cpp:303
bool has_quaternion_floating_base_
Whether the state includes a SE(3) floating base.
Definition: scene.h:185
void CleanScene()
Definition: scene.cpp:631
virtual void Instantiate(const SceneInitializer &init)
Definition: scene.cpp:69
double data[9]
std::shared_ptr< const Shape > ShapeConstPtr
int get_num_velocities() const
Definition: scene.cpp:931


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:49