bodies.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 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 
37 #ifndef GEOMETRIC_SHAPES_POINT_INCLUSION_
38 #define GEOMETRIC_SHAPES_POINT_INCLUSION_
39 
42 #include <tf/LinearMath/Vector3.h>
43 // #include <BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h>
44 // #include <BulletCollision/CollisionShapes/btTriangleMesh.h>
45 #include <vector>
46 
56 {
57 namespace bodies
58 {
59 
62  {
64  double radius;
65  };
66 
70  class Body
71  {
72  public:
73 
74  Body(void)
75  {
76  m_scale = 1.0;
77  m_padding = 0.0;
78  m_pose.setIdentity();
79  m_type = shapes::UNKNOWN_SHAPE;
80  }
81 
82  virtual ~Body(void)
83  {
84  }
85 
88  {
89  return m_type;
90  }
91 
94  void setScale(double scale)
95  {
96  m_scale = scale;
97  updateInternalData();
98  }
99 
101  double getScale(void) const
102  {
103  return m_scale;
104  }
105 
108  void setPadding(double padd)
109  {
110  m_padding = padd;
111  updateInternalData();
112  }
113 
115  double getPadding(void) const
116  {
117  return m_padding;
118  }
119 
121  void setPose(const tf::Transform &pose)
122  {
123  m_pose = pose;
124  updateInternalData();
125  }
126 
128  const tf::Transform& getPose(void) const
129  {
130  return m_pose;
131  }
132 
134  void setDimensions(const shapes::Shape *shape)
135  {
136  useDimensions(shape);
137  updateInternalData();
138  }
139 
141  bool containsPoint(double x, double y, double z) const
142  {
143  return containsPoint(tf::Vector3(tfScalar(x), tfScalar(y), tfScalar(z)));
144  }
145 
150  virtual bool intersectsRay(const tf::Vector3& origin, const tf::Vector3 &dir, std::vector<tf::Vector3> *intersections = NULL, unsigned int count = 0) const = 0;
151 
153  virtual bool containsPoint(const tf::Vector3 &p, bool verbose = false) const = 0;
154 
157  virtual double computeVolume(void) const = 0;
158 
161  virtual void computeBoundingSphere(BoundingSphere &sphere) const = 0;
162 
163  protected:
164 
165  virtual void updateInternalData(void) = 0;
166  virtual void useDimensions(const shapes::Shape *shape) = 0;
167 
170  double m_scale;
171  double m_padding;
172  };
173 
175  class Sphere : public Body
176  {
177  public:
178  Sphere(void) : Body()
179  {
180  m_type = shapes::SPHERE;
181  }
182 
183  Sphere(const shapes::Shape *shape) : Body()
184  {
185  m_type = shapes::SPHERE;
186  setDimensions(shape);
187  }
188 
189  virtual ~Sphere(void)
190  {
191  }
192 
193  virtual bool containsPoint(const tf::Vector3 &p, bool verbose=false) const;
194  virtual double computeVolume(void) const;
195  virtual void computeBoundingSphere(BoundingSphere &sphere) const;
196  virtual bool intersectsRay(const tf::Vector3& origin, const tf::Vector3 &dir, std::vector<tf::Vector3> *intersections = NULL, unsigned int count = 0) const;
197 
198  protected:
199 
200  virtual void useDimensions(const shapes::Shape *shape);
201  virtual void updateInternalData(void);
202 
204  double m_radius;
205  double m_radiusU;
206  double m_radius2;
207  };
208 
210  class Cylinder : public Body
211  {
212  public:
213  Cylinder(void) : Body()
214  {
215  m_type = shapes::CYLINDER;
216  }
217 
218  Cylinder(const shapes::Shape *shape) : Body()
219  {
220  m_type = shapes::CYLINDER;
221  setDimensions(shape);
222  }
223 
224  virtual ~Cylinder(void)
225  {
226  }
227 
228  virtual bool containsPoint(const tf::Vector3 &p, bool verbose=false) const;
229  virtual double computeVolume(void) const;
230  virtual void computeBoundingSphere(BoundingSphere &sphere) const;
231  virtual bool intersectsRay(const tf::Vector3& origin, const tf::Vector3 &dir, std::vector<tf::Vector3> *intersections = NULL, unsigned int count = 0) const;
232 
233  protected:
234 
235  virtual void useDimensions(const shapes::Shape *shape);
236  virtual void updateInternalData(void);
237 
242 
243  double m_length;
244  double m_length2;
245  double m_radius;
246  double m_radiusU;
247  double m_radiusB;
248  double m_radiusBSqr;
249  double m_radius2;
250  double m_d1;
251  double m_d2;
252  };
253 
255  class Box : public Body
256  {
257  public:
258  Box(void) : Body()
259  {
260  m_type = shapes::BOX;
261  }
262 
263  Box(const shapes::Shape *shape) : Body()
264  {
265  m_type = shapes::BOX;
266  setDimensions(shape);
267  }
268 
269  virtual ~Box(void)
270  {
271  }
272 
273  virtual bool containsPoint(const tf::Vector3 &p, bool verbose = false) const;
274  virtual double computeVolume(void) const;
275  virtual void computeBoundingSphere(BoundingSphere &sphere) const;
276  virtual bool intersectsRay(const tf::Vector3& origin, const tf::Vector3 &dir, std::vector<tf::Vector3> *intersections = NULL, unsigned int count = 0) const;
277 
278  protected:
279 
280  virtual void useDimensions(const shapes::Shape *shape); // (x, y, z) = (length, width, height)
281  virtual void updateInternalData(void);
282 
287 
290 
291  double m_length;
292  double m_width;
293  double m_height;
294  double m_length2;
295  double m_width2;
296  double m_height2;
297  double m_radiusB;
298  double m_radius2;
299  };
300 
301  /*
302  class Mesh : public Body
303  {
304  public:
306  Mesh(void) : Body()
307  {
308  m_type = shapes::MESH;
309  m_btMeshShape = NULL;
310  m_btMesh = NULL;
311  }
312 
313  Mesh(const shapes::Shape *shape) : Body()
314  {
315  m_type = shapes::MESH;
316  m_btMeshShape = NULL;
317  m_btMesh = NULL;
318  setDimensions(shape);
319  }
320 
321  virtual ~Mesh(void)
322  {
323  if (m_btMeshShape)
324  delete m_btMeshShape;
325  if (m_btMesh)
326  delete m_btMesh;
327  }
328 
329  \\\ \brief The mesh is considered to be concave, so this function is implemented with raycasting. This is a bit slow and not so accurate for very small triangles.
330  virtual bool containsPoint(const tf::Vector3 &p) const;
331 
332  \\\ \brief This function is approximate. It returns the volume of the AABB enclosing the shape
333  virtual double computeVolume(void) const;
334  virtual void computeBoundingSphere(BoundingSphere &sphere) const;
335  virtual bool intersectsRay(const tf::Vector3& origin, const tf::Vector3 &dir, std::vector<tf::Vector3> *intersections = NULL, unsigned int count = 0) const;
336 
337  protected:
338 
339  virtual void useDimensions(const shapes::Shape *shape);
340  virtual void updateInternalData(void);
341 
342  btBvhTriangleMeshShape *m_btMeshShape;
343  btTriangleMesh *m_btMesh;
344  tf::Transform m_iPose;
345  tf::Vector3 m_center;
346  tf::Vector3 m_aabbMin;
347  tf::Vector3 m_aabbMax;
348  double m_radiusB;
349  double m_radiusBSqr;
350 
351  };
352  */
353 
355  class ConvexMesh : public Body
356  {
357  public:
358 
359  ConvexMesh(void) : Body()
360  {
361  m_type = shapes::MESH;
362  }
363 
364  ConvexMesh(const shapes::Shape *shape) : Body()
365  {
366  m_type = shapes::MESH;
367  setDimensions(shape);
368  }
369 
370  virtual ~ConvexMesh(void)
371  {
372  }
373 
374  virtual bool containsPoint(const tf::Vector3 &p, bool verbose = false) const;
375  virtual double computeVolume(void) const;
376 
377  virtual void computeBoundingSphere(BoundingSphere &sphere) const;
378  virtual bool intersectsRay(const tf::Vector3& origin, const tf::Vector3 &dir, std::vector<tf::Vector3> *intersections = NULL, unsigned int count = 0) const;
379 
380  protected:
381 
382  virtual void useDimensions(const shapes::Shape *shape);
383  virtual void updateInternalData(void);
384 
385  unsigned int countVerticesBehindPlane(const tf::tfVector4& planeNormal) const;
386  bool isPointInsidePlanes(const tf::Vector3& point) const;
387 
388  std::vector<tf::tfVector4> m_planes;
389  std::vector<tf::Vector3> m_vertices;
390  std::vector<tf::Vector3> m_scaledVertices;
391  std::vector<unsigned int> m_triangles;
393 
396  double m_radiusB;
397  double m_radiusBSqr;
399 
402  };
403 
404 
406  Body* createBodyFromShape(const shapes::Shape *shape);
407 
409  void mergeBoundingSpheres(const std::vector<BoundingSphere> &spheres, BoundingSphere &mergedSphere);
410 
411 }
412 }
413 #endif
Sphere(const shapes::Shape *shape)
Definition: bodies.h:183
shapes::ShapeType getType(void) const
Get the type of shape this body represents.
Definition: bodies.h:87
const tf::Transform & getPose(void) const
Retrieve the pose of the body.
Definition: bodies.h:128
double tfScalar
std::vector< tf::Vector3 > m_vertices
Definition: bodies.h:389
ShapeType
A list of known shape types.
Definition: shapes.h:53
Box(const shapes::Shape *shape)
Definition: bodies.h:263
Definition of a cylinder.
Definition: bodies.h:210
Definition of a sphere that bounds another object.
Definition: bodies.h:61
shapes::ShapeType m_type
Definition: bodies.h:168
Definition of a convex mesh. Convex hull is computed for a given shape::Mesh.
Definition: bodies.h:355
Body * createBodyFromShape(const shapes::Shape *shape)
Create a body from a given shape.
Definition: bodies.cpp:46
void mergeBoundingSpheres(const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere)
Compute a bounding sphere to enclose a set of bounding spheres.
Definition: bodies.cpp:73
bool containsPoint(double x, double y, double z) const
Check is a point is inside the body.
Definition: bodies.h:141
double getPadding(void) const
Retrieve the current padding.
Definition: bodies.h:115
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
Definition: bodies.h:70
void setPose(const tf::Transform &pose)
Set the pose of the body. Default is identity.
Definition: bodies.h:121
void setPadding(double padd)
If constant padding should be added to the body, this method sets the padding. Default is 0...
Definition: bodies.h:108
std::vector< unsigned int > m_triangles
Definition: bodies.h:391
void setScale(double scale)
If the dimension of the body should be scaled, this method sets the scale. Default is 1...
Definition: bodies.h:94
Definition of a box.
Definition: bodies.h:255
std::vector< tf::Vector3 > m_scaledVertices
Definition: bodies.h:390
std::vector< tf::tfVector4 > m_planes
Definition: bodies.h:388
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:59
double getScale(void) const
Retrieve the current scale.
Definition: bodies.h:101
Cylinder(const shapes::Shape *shape)
Definition: bodies.h:218
void setDimensions(const shapes::Shape *shape)
Set the dimensions of the body (from corresponding shape)
Definition: bodies.h:134
Definition of a sphere.
Definition: bodies.h:175
ConvexMesh(const shapes::Shape *shape)
Definition: bodies.h:364


robot_self_filter
Author(s): Eitan Marder-Eppstein
autogenerated on Thu Jun 6 2019 19:59:05