|
33 | 33 |
|
34 | 34 | #define _USE_MATH_DEFINES
|
35 | 35 | #include "geometric_shapes/aabb.h"
|
| 36 | +#include "geometric_shapes/obb.h" |
36 | 37 | #include "geometric_shapes/shapes.h"
|
37 | 38 | #include <eigen_stl_containers/eigen_stl_containers.h>
|
38 | 39 | #include <random_numbers/random_numbers.h>
|
@@ -240,6 +241,10 @@ class Body
|
240 | 241 | pose. Scaling and padding are accounted for. */
|
241 | 242 | virtual void computeBoundingBox(AABB& bbox) const = 0;
|
242 | 243 |
|
| 244 | + /** \brief Compute the oriented bounding box for the body, in its current |
| 245 | + pose. Scaling and padding are accounted for. */ |
| 246 | + virtual void computeBoundingBox(OBB& bbox) const = 0; |
| 247 | + |
243 | 248 | /** \brief Get a clone of this body, but one that is located at the pose \e pose */
|
244 | 249 | inline BodyPtr cloneAt(const Eigen::Isometry3d& pose) const
|
245 | 250 | {
|
@@ -307,6 +312,7 @@ class Sphere : public Body
|
307 | 312 | void computeBoundingSphere(BoundingSphere& sphere) const override;
|
308 | 313 | void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
|
309 | 314 | void computeBoundingBox(AABB& bbox) const override;
|
| 315 | + void computeBoundingBox(OBB& bbox) const override; |
310 | 316 | bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
|
311 | 317 | EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
|
312 | 318 |
|
@@ -359,6 +365,7 @@ class Cylinder : public Body
|
359 | 365 | void computeBoundingSphere(BoundingSphere& sphere) const override;
|
360 | 366 | void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
|
361 | 367 | void computeBoundingBox(AABB& bbox) const override;
|
| 368 | + void computeBoundingBox(OBB& bbox) const override; |
362 | 369 | bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
|
363 | 370 | EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
|
364 | 371 |
|
@@ -421,6 +428,7 @@ class Box : public Body
|
421 | 428 | void computeBoundingSphere(BoundingSphere& sphere) const override;
|
422 | 429 | void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
|
423 | 430 | void computeBoundingBox(AABB& bbox) const override;
|
| 431 | + void computeBoundingBox(OBB& bbox) const override; |
424 | 432 | bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
|
425 | 433 | EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
|
426 | 434 |
|
@@ -483,6 +491,7 @@ class ConvexMesh : public Body
|
483 | 491 | void computeBoundingSphere(BoundingSphere& sphere) const override;
|
484 | 492 | void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
|
485 | 493 | void computeBoundingBox(AABB& bbox) const override;
|
| 494 | + void computeBoundingBox(OBB& bbox) const override; |
486 | 495 | bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
|
487 | 496 | EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
|
488 | 497 |
|
|
0 commit comments