moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
collision_common_distance_field.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
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 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: E. Gil Jones */
36
38#include <rclcpp/duration.hpp>
39#include <rclcpp/logger.hpp>
40#include <rclcpp/logging.hpp>
41#include <rclcpp/time.hpp>
42#include <tf2_eigen/tf2_eigen.hpp>
43#include <memory>
44#include <mutex>
46
47namespace collision_detection
48{
49namespace
50{
51rclcpp::Logger getLogger()
52{
53 return moveit::getLogger("moveit.core.collision_common_distance_field");
54}
55} // namespace
56
58{
59 using Comperator = std::owner_less<shapes::ShapeConstWeakPtr>;
60 using Map = std::map<shapes::ShapeConstWeakPtr, BodyDecompositionConstPtr, Comperator>;
61
65 static const unsigned int MAX_CLEAN_COUNT{ 100 };
67 unsigned int clean_count_;
68 std::mutex lock_;
69};
70
72{
73 static BodyDecompositionCache cache;
74 return cache;
75}
76
77BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr& shape, double resolution)
78{
79 // TODO - deal with changing resolution?
81 shapes::ShapeConstWeakPtr wptr(shape);
82 {
83 std::scoped_lock slock(cache.lock_);
84 BodyDecompositionCache::Map::const_iterator cache_it = cache.map_.find(wptr);
85 if (cache_it != cache.map_.end())
86 {
87 return cache_it->second;
88 }
89 }
90
91 BodyDecompositionConstPtr bdcp = std::make_shared<const BodyDecomposition>(shape, resolution);
92 {
93 std::scoped_lock slock(cache.lock_);
94 cache.map_[wptr] = bdcp;
95 cache.clean_count_++;
96 return bdcp;
97 }
98 // TODO - clean cache
99}
100
101PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object& obj,
102 double resolution)
103{
104 PosedBodyPointDecompositionVectorPtr ret = std::make_shared<PosedBodyPointDecompositionVector>();
105 for (unsigned int i = 0; i < obj.shapes_.size(); ++i)
106 {
107 PosedBodyPointDecompositionPtr pbd(
109 ret->addToVector(pbd);
110 ret->updatePose(ret->getSize() - 1, obj.global_shape_poses_[i]);
111 }
112 return ret;
113}
114
115PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const moveit::core::AttachedBody* att,
116 double resolution)
117{
118 PosedBodySphereDecompositionVectorPtr ret = std::make_shared<PosedBodySphereDecompositionVector>();
119 for (unsigned int i{ 0 }; i < att->getShapes().size(); ++i)
120 {
121 PosedBodySphereDecompositionPtr pbd(
123 pbd->updatePose(att->getGlobalCollisionBodyTransforms()[i]);
124 ret->addToVector(pbd);
125 }
126 return ret;
127}
128
129PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const moveit::core::AttachedBody* att,
130 double resolution)
131{
132 PosedBodyPointDecompositionVectorPtr ret = std::make_shared<PosedBodyPointDecompositionVector>();
133 for (unsigned int i{ 0 }; i < att->getShapes().size(); ++i)
134 {
135 PosedBodyPointDecompositionPtr pbd =
136 std::make_shared<PosedBodyPointDecomposition>(getBodyDecompositionCacheEntry(att->getShapes()[i], resolution));
137 ret->addToVector(pbd);
138 ret->updatePose(ret->getSize() - 1, att->getGlobalCollisionBodyTransforms()[i]);
139 }
140 return ret;
141}
142
143void getBodySphereVisualizationMarkers(const GroupStateRepresentationConstPtr& gsr, const std::string& reference_frame,
144 visualization_msgs::msg::MarkerArray& body_marker_array)
145{
146 // creating namespaces
147 std::string robot_ns = gsr->dfce_->group_name_ + "_sphere_decomposition";
148 std::string attached_ns = "attached_sphere_decomposition";
149
150 // creating colors
151 std_msgs::msg::ColorRGBA robot_color;
152 robot_color.r = 0;
153 robot_color.b = 0.8f;
154 robot_color.g = 0;
155 robot_color.a = 0.5;
156
157 std_msgs::msg::ColorRGBA attached_color;
158 attached_color.r = 1;
159 attached_color.g = 1;
160 attached_color.b = 0;
161 attached_color.a = 0.5;
162
163 // creating sphere marker
164 visualization_msgs::msg::Marker sphere_marker;
165 sphere_marker.header.frame_id = reference_frame;
166 sphere_marker.header.stamp = rclcpp::Time(0);
167 sphere_marker.ns = robot_ns;
168 sphere_marker.id = 0;
169 sphere_marker.type = visualization_msgs::msg::Marker::SPHERE;
170 sphere_marker.action = visualization_msgs::msg::Marker::ADD;
171 sphere_marker.pose.orientation.x = 0;
172 sphere_marker.pose.orientation.y = 0;
173 sphere_marker.pose.orientation.z = 0;
174 sphere_marker.pose.orientation.w = 1;
175 sphere_marker.color = robot_color;
176 sphere_marker.lifetime = rclcpp::Duration(0, 0);
177
178 const moveit::core::RobotState& state = *(gsr->dfce_->state_);
179 unsigned int id{ 0 };
180 for (unsigned int i{ 0 }; i < gsr->dfce_->link_names_.size(); ++i)
181 {
182 const moveit::core::LinkModel* ls = state.getLinkModel(gsr->dfce_->link_names_[i]);
183 if (gsr->dfce_->link_has_geometry_[i])
184 {
185 gsr->link_body_decompositions_[i]->updatePose(state.getFrameTransform(ls->getName()));
186
187 collision_detection::PosedBodySphereDecompositionConstPtr sphere_representation =
188 gsr->link_body_decompositions_[i];
189 for (unsigned int j = 0; j < sphere_representation->getCollisionSpheres().size(); ++j)
190 {
191 sphere_marker.pose.position = tf2::toMsg(sphere_representation->getSphereCenters()[j]);
192 sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z =
193 sphere_representation->getCollisionSpheres()[j].radius_;
194 sphere_marker.id = id;
195 id++;
196
197 body_marker_array.markers.push_back(sphere_marker);
198 }
199 }
200 }
201
202 sphere_marker.ns = attached_ns;
203 sphere_marker.color = attached_color;
204 for (unsigned int i{ 0 }; i < gsr->dfce_->attached_body_names_.size(); ++i)
205 {
206 const moveit::core::AttachedBody* att = state.getAttachedBody(gsr->dfce_->attached_body_names_[i]);
207 if (!att)
208 {
209 RCLCPP_WARN(getLogger(),
210 "Attached body '%s' was not found, skipping sphere "
211 "decomposition visualization",
212 gsr->dfce_->attached_body_names_[i].c_str());
213 continue;
214 }
215
216 if (gsr->attached_body_decompositions_[i]->getSize() != att->getShapes().size())
217 {
218 RCLCPP_WARN(getLogger(), "Attached body size discrepancy");
219 continue;
220 }
221
222 for (unsigned int j{ 0 }; j < att->getShapes().size(); ++j)
223 {
224 PosedBodySphereDecompositionVectorPtr sphere_decp = gsr->attached_body_decompositions_[i];
225 sphere_decp->updatePose(j, att->getGlobalCollisionBodyTransforms()[j]);
226
227 sphere_marker.pose.position = tf2::toMsg(sphere_decp->getSphereCenters()[j]);
228 sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z =
229 sphere_decp->getCollisionSpheres()[j].radius_;
230 sphere_marker.id = id;
231 body_marker_array.markers.push_back(sphere_marker);
232 id++;
233 }
234 }
235}
236} // namespace collision_detection
Object defining bodies that can be attached to robot links.
const EigenSTL::vector_Isometry3d & getGlobalCollisionBodyTransforms() const
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guar...
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
const std::string & getName() const
The name of this link.
Definition link_model.h:86
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object &obj, double resolution)
void getBodySphereVisualizationMarkers(const GroupStateRepresentationPtr &gsr, const std::string &reference_frame, visualization_msgs::msg::MarkerArray &body_marker_array)
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const moveit::core::AttachedBody *att, double resolution)
BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr &shape, double resolution)
BodyDecompositionCache & getBodyDecompositionCache()
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const moveit::core::AttachedBody *att, double resolution)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::owner_less< shapes::ShapeConstWeakPtr > Comperator
std::map< shapes::ShapeConstWeakPtr, BodyDecompositionConstPtr, Comperator > Map
A representation of an object.
Definition world.h:79
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
Definition world.h:106
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Definition world.h:96