moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
shape_mask.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 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: Ioan Sucan */
36
37#pragma once
38
39#include <sensor_msgs/msg/point_cloud2.hpp>
40#include <geometric_shapes/bodies.h>
41#include <vector>
42#include <set>
43#include <map>
44#include <mutex>
45#include <functional>
46
48{
49typedef unsigned int ShapeHandle;
50
53{
54public:
56 enum
57 {
58 INSIDE = 0,
60 CLIP = 2
61 };
62
63 typedef std::function<bool(ShapeHandle, Eigen::Isometry3d&)> TransformCallback;
64
66 ShapeMask(const TransformCallback& transform_callback = TransformCallback());
67
69 virtual ~ShapeMask();
70
71 ShapeHandle addShape(const shapes::ShapeConstPtr& shape, double scale = 1.0, double padding = 0.0);
72 void removeShape(ShapeHandle handle);
73
74 void setTransformCallback(const TransformCallback& transform_callback);
75
80 void maskContainment(const sensor_msgs::msg::PointCloud2& data_in, const Eigen::Vector3d& sensor_pos,
81 const double min_sensor_dist, const double max_sensor_dist, std::vector<int>& mask);
82
85 int getMaskContainment(double x, double y, double z) const;
86
89 int getMaskContainment(const Eigen::Vector3d& pt) const;
90
91protected:
92 struct SeeShape
93 {
95 {
96 body = nullptr;
97 }
98
99 bodies::Body* body;
101 double volume;
102 };
103
105 {
106 bool operator()(const SeeShape& b1, const SeeShape& b2) const
107 {
108 if (b1.volume > b2.volume)
109 return true;
110 if (b1.volume < b2.volume)
111 return false;
112 return b1.handle < b2.handle;
113 }
114 };
115
117
119 mutable std::mutex shapes_lock_;
120 std::set<SeeShape, SortBodies> bodies_;
121 std::vector<bodies::BoundingSphere> bspheres_;
122
123private:
125 void freeMemory();
126
127 ShapeHandle next_handle_;
128 ShapeHandle min_handle_;
129 std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator> used_handles_;
130};
131} // namespace point_containment_filter
Computing a mask for a pointcloud that states which points are inside the robot.
Definition shape_mask.h:53
ShapeHandle addShape(const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
std::mutex shapes_lock_
Protects, bodies_ and bspheres_. All public methods acquire this mutex for their whole duration.
Definition shape_mask.h:119
std::vector< bodies::BoundingSphere > bspheres_
Definition shape_mask.h:121
std::set< SeeShape, SortBodies > bodies_
Definition shape_mask.h:120
std::function< bool(ShapeHandle, Eigen::Isometry3d &)> TransformCallback
Definition shape_mask.h:63
TransformCallback transform_callback_
Definition shape_mask.h:116
void removeShape(ShapeHandle handle)
void maskContainment(const sensor_msgs::msg::PointCloud2 &data_in, const Eigen::Vector3d &sensor_pos, const double min_sensor_dist, const double max_sensor_dist, std::vector< int > &mask)
Compute the containment mask (INSIDE or OUTSIDE) for a given pointcloud. If a mask element is INSIDE,...
int getMaskContainment(double x, double y, double z) const
Get the containment mask (INSIDE or OUTSIDE) value for an individual point. It is assumed the point i...
virtual ~ShapeMask()
Destructor to clean up.
void setTransformCallback(const TransformCallback &transform_callback)
unsigned int ShapeHandle
Definition shape_mask.h:49
bool operator()(const SeeShape &b1, const SeeShape &b2) const
Definition shape_mask.h:106