81 shapes::ShapeConstWeakPtr wptr(shape);
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())
87 return cache_it->second;
91 BodyDecompositionConstPtr bdcp = std::make_shared<const BodyDecomposition>(shape, resolution);
93 std::scoped_lock slock(cache.
lock_);
94 cache.
map_[wptr] = bdcp;
144 visualization_msgs::msg::MarkerArray& body_marker_array)
147 std::string robot_ns = gsr->dfce_->group_name_ +
"_sphere_decomposition";
148 std::string attached_ns =
"attached_sphere_decomposition";
151 std_msgs::msg::ColorRGBA robot_color;
153 robot_color.b = 0.8f;
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;
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);
179 unsigned int id{ 0 };
180 for (
unsigned int i{ 0 }; i < gsr->dfce_->link_names_.size(); ++i)
183 if (gsr->dfce_->link_has_geometry_[i])
187 collision_detection::PosedBodySphereDecompositionConstPtr sphere_representation =
188 gsr->link_body_decompositions_[i];
189 for (
unsigned int j = 0; j < sphere_representation->getCollisionSpheres().size(); ++j)
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;
197 body_marker_array.markers.push_back(sphere_marker);
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)
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());
216 if (gsr->attached_body_decompositions_[i]->getSize() != att->
getShapes().size())
218 RCLCPP_WARN(getLogger(),
"Attached body size discrepancy");
222 for (
unsigned int j{ 0 }; j < att->
getShapes().size(); ++j)
224 PosedBodySphereDecompositionVectorPtr sphere_decp = gsr->attached_body_decompositions_[i];
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);
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.
std::owner_less< shapes::ShapeConstWeakPtr > Comperator
std::map< shapes::ShapeConstWeakPtr, BodyDecompositionConstPtr, Comperator > Map