Skip to content

Commit

Permalink
Revert OBB additions
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Nov 26, 2024
1 parent 3d3b942 commit ad23c24
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 24 deletions.
10 changes: 5 additions & 5 deletions include/geometric_shapes/bodies.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ class Body

/** \brief Compute the oriented bounding box for the body, in its current
pose. Scaling and padding are accounted for. */
virtual void computeBoundingBox(OBB& bbox) const = 0;
// virtual void computeBoundingBox(OBB& bbox) const = 0;

/** \brief Get a clone of this body, but one that is located at the pose \e pose */
inline BodyPtr cloneAt(const Eigen::Isometry3d& pose) const
Expand Down Expand Up @@ -312,7 +312,7 @@ class Sphere : public Body
void computeBoundingSphere(BoundingSphere& sphere) const override;
void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
void computeBoundingBox(AABB& bbox) const override;
void computeBoundingBox(OBB& bbox) const override;
// void computeBoundingBox(OBB& bbox) const override;
bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;

Expand Down Expand Up @@ -365,7 +365,7 @@ class Cylinder : public Body
void computeBoundingSphere(BoundingSphere& sphere) const override;
void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
void computeBoundingBox(AABB& bbox) const override;
void computeBoundingBox(OBB& bbox) const override;
// void computeBoundingBox(OBB& bbox) const override;
bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;

Expand Down Expand Up @@ -428,7 +428,7 @@ class Box : public Body
void computeBoundingSphere(BoundingSphere& sphere) const override;
void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
void computeBoundingBox(AABB& bbox) const override;
void computeBoundingBox(OBB& bbox) const override;
// void computeBoundingBox(OBB& bbox) const override;
bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;

Expand Down Expand Up @@ -491,7 +491,7 @@ class ConvexMesh : public Body
void computeBoundingSphere(BoundingSphere& sphere) const override;
void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
void computeBoundingBox(AABB& bbox) const override;
void computeBoundingBox(OBB& bbox) const override;
// void computeBoundingBox(OBB& bbox) const override;
bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;

Expand Down
38 changes: 19 additions & 19 deletions src/bodies.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,14 +206,14 @@ void bodies::Sphere::computeBoundingBox(bodies::AABB& bbox) const
bbox.extendWithTransformedBox(transform, Eigen::Vector3d(2 * radiusU_, 2 * radiusU_, 2 * radiusU_));
}

void bodies::Sphere::computeBoundingBox(bodies::OBB& bbox) const
{
// it's a sphere, so we do not rotate the bounding box
Eigen::Isometry3d transform = Eigen::Isometry3d::Identity();
transform.translation() = getPose().translation();
// void bodies::Sphere::computeBoundingBox(bodies::OBB& bbox) const
// {
// // it's a sphere, so we do not rotate the bounding box
// Eigen::Isometry3d transform = Eigen::Isometry3d::Identity();
// transform.translation() = getPose().translation();

bbox.setPoseAndExtents(transform, 2 * Eigen::Vector3d(radiusU_, radiusU_, radiusU_));
}
// bbox.setPoseAndExtents(transform, 2 * Eigen::Vector3d(radiusU_, radiusU_, radiusU_));
// }

bool bodies::Sphere::samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
Eigen::Vector3d& result) const
Expand Down Expand Up @@ -436,10 +436,10 @@ void bodies::Cylinder::computeBoundingBox(bodies::AABB& bbox) const
bbox.extend(pb + e);
}

void bodies::Cylinder::computeBoundingBox(bodies::OBB& bbox) const
{
bbox.setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(radiusU_, radiusU_, length2_));
}
// void bodies::Cylinder::computeBoundingBox(bodies::OBB& bbox) const
// {
// bbox.setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(radiusU_, radiusU_, length2_));
// }

bool bodies::Cylinder::intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections, unsigned int count) const
Expand Down Expand Up @@ -677,10 +677,10 @@ void bodies::Box::computeBoundingBox(bodies::AABB& bbox) const
bbox.extendWithTransformedBox(getPose(), 2 * Eigen::Vector3d(length2_, width2_, height2_));
}

void bodies::Box::computeBoundingBox(bodies::OBB& bbox) const
{
bbox.setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(length2_, width2_, height2_));
}
// void bodies::Box::computeBoundingBox(bodies::OBB& bbox) const
// {
// bbox.setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(length2_, width2_, height2_));
// }

bool bodies::Box::intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections, unsigned int count) const
Expand Down Expand Up @@ -1174,10 +1174,10 @@ void bodies::ConvexMesh::computeBoundingBox(bodies::AABB& bbox) const
bounding_box_.computeBoundingBox(bbox);
}

void bodies::ConvexMesh::computeBoundingBox(bodies::OBB& bbox) const
{
bounding_box_.computeBoundingBox(bbox);
}
// void bodies::ConvexMesh::computeBoundingBox(bodies::OBB& bbox) const
// {
// bounding_box_.computeBoundingBox(bbox);
// }

bool bodies::ConvexMesh::isPointInsidePlanes(const Eigen::Vector3d& point) const
{
Expand Down

0 comments on commit ad23c24

Please sign in to comment.