moveit2
The MoveIt Motion Planning Framework for ROS 2.
ros_bullet_utils.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD-2-Clause)
3  *
4  * Copyright (c) 2021, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  *********************************************************************/
31 
32 /* Author: Jorge Nicho*/
33 
35 
36 #include <rclcpp/logger.hpp>
37 #include <rclcpp/logging.hpp>
38 #include <moveit/utils/logger.hpp>
39 
41 {
42 void getActiveLinkNamesRecursive(std::vector<std::string>& active_links, const urdf::LinkConstSharedPtr& urdf_link,
43  bool active)
44 {
45  if (active)
46  {
47  active_links.push_back(urdf_link->name);
48  for (const auto& child_link : urdf_link->child_links)
49  {
50  getActiveLinkNamesRecursive(active_links, child_link, active);
51  }
52  }
53  else
54  {
55  for (std::size_t i = 0; i < urdf_link->child_links.size(); ++i)
56  {
57  const urdf::LinkConstSharedPtr child_link = urdf_link->child_links[i];
58  if ((child_link->parent_joint) && (child_link->parent_joint->type != urdf::Joint::FIXED))
59  {
60  getActiveLinkNamesRecursive(active_links, child_link, true);
61  }
62  else
63  {
64  getActiveLinkNamesRecursive(active_links, child_link, active);
65  }
66  }
67  }
68 }
69 
70 shapes::ShapePtr constructShape(const urdf::Geometry* geom)
71 {
72  shapes::Shape* result = nullptr;
73  switch (geom->type)
74  {
75  case urdf::Geometry::SPHERE:
76  result = new shapes::Sphere(static_cast<const urdf::Sphere*>(geom)->radius);
77  break;
78  case urdf::Geometry::BOX:
79  {
80  urdf::Vector3 dim = static_cast<const urdf::Box*>(geom)->dim;
81  result = new shapes::Box(dim.x, dim.y, dim.z);
82  }
83  break;
84  case urdf::Geometry::CYLINDER:
85  result = new shapes::Cylinder(static_cast<const urdf::Cylinder*>(geom)->radius,
86  static_cast<const urdf::Cylinder*>(geom)->length);
87  break;
88  case urdf::Geometry::MESH:
89  {
90  const urdf::Mesh* mesh = static_cast<const urdf::Mesh*>(geom);
91  if (!mesh->filename.empty())
92  {
93  Eigen::Vector3d scale(mesh->scale.x, mesh->scale.y, mesh->scale.z);
94  shapes::Mesh* m = shapes::createMeshFromResource(mesh->filename, scale);
95  result = m;
96  }
97  }
98  break;
99  default:
100  RCLCPP_ERROR(getLogger(), "Unknown geometry type: %d", static_cast<int>(geom->type));
101  break;
102  }
103 
104  return shapes::ShapePtr(result);
105 }
106 
107 Eigen::Isometry3d urdfPose2Eigen(const urdf::Pose& pose)
108 {
109  Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
110  Eigen::Isometry3d result;
111  result.translation() = Eigen::Vector3d(pose.position.x, pose.position.y, pose.position.z);
112  result.linear() = q.toRotationMatrix();
113  return result;
114 }
115 
116 rclcpp::Logger getLogger()
117 {
118  return moveit::getLogger("collision_detection_bullet");
119 }
120 } // namespace collision_detection_bullet
Eigen::Isometry3d urdfPose2Eigen(const urdf::Pose &pose)
void getActiveLinkNamesRecursive(std::vector< std::string > &active_links, const urdf::LinkConstSharedPtr &urdf_link, bool active)
Recursively traverses robot from root to get all active links.
shapes::ShapePtr constructShape(const urdf::Geometry *geom)
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79