Skip to content

Commit

Permalink
Apply inline pattern to primitive shapes
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Aug 15, 2016
1 parent 4b1840f commit abec43c
Show file tree
Hide file tree
Showing 51 changed files with 2,750 additions and 1,521 deletions.
Expand Up @@ -41,7 +41,16 @@
#include <ccd/ccd.h>
#include <ccd/quat.h>
#include <ccd/vec3.h>
#include "fcl/object/geometry/shape/geometric_shapes.h"
#include "fcl/object/geometry/shape/box.h"
#include "fcl/object/geometry/shape/capsule.h"
#include "fcl/object/geometry/shape/cone.h"
#include "fcl/object/geometry/shape/convex.h"
#include "fcl/object/geometry/shape/cylinder.h"
#include "fcl/object/geometry/shape/ellipsoid.h"
#include "fcl/object/geometry/shape/halfspace.h"
#include "fcl/object/geometry/shape/plane.h"
#include "fcl/object/geometry/shape/sphere.h"
#include "fcl/object/geometry/shape/triangle_p.h"
#include "fcl/narrowphase/detail/convexity_based_algorithm/simplex.h"
#include "fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h"

Expand Down
Expand Up @@ -37,6 +37,17 @@

#include "fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff.h"

#include "fcl/object/geometry/shape/box.h"
#include "fcl/object/geometry/shape/capsule.h"
#include "fcl/object/geometry/shape/cone.h"
#include "fcl/object/geometry/shape/convex.h"
#include "fcl/object/geometry/shape/cylinder.h"
#include "fcl/object/geometry/shape/ellipsoid.h"
#include "fcl/object/geometry/shape/halfspace.h"
#include "fcl/object/geometry/shape/plane.h"
#include "fcl/object/geometry/shape/sphere.h"
#include "fcl/object/geometry/shape/triangle_p.h"

namespace fcl
{

Expand Down
Expand Up @@ -39,7 +39,7 @@
#define FCL_NARROWPHASE_DETAIL_MINKOWSKIDIFF_H

#include "fcl/math/detail/project.h"
#include "fcl/object/geometry/shape/geometric_shapes.h"
#include "fcl/object/geometry/shape/shape_base.h"

namespace fcl
{
Expand Down
Expand Up @@ -58,6 +58,12 @@ namespace detail
template <typename S>
S halfspaceIntersectTolerance();

template <>
float halfspaceIntersectTolerance();

template <>
double halfspaceIntersectTolerance();

template <typename S>
bool sphereHalfspaceIntersect(const Sphere<S>& s1, const Transform3<S>& tf1,
const Halfspace<S>& s2, const Transform3<S>& tf2,
Expand Down
Expand Up @@ -58,6 +58,12 @@ namespace detail
template <typename S>
S planeIntersectTolerance();

template <>
double planeIntersectTolerance();

template <>
float planeIntersectTolerance();

template <typename S>
bool spherePlaneIntersect(const Sphere<S>& s1, const Transform3<S>& tf1,
const Plane<S>& s2, const Transform3<S>& tf2,
Expand Down
128 changes: 128 additions & 0 deletions include/fcl/object/geometry/shape/box-inl.h
@@ -0,0 +1,128 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011-2014, Willow Garage, Inc.
* Copyright (c) 2014-2016, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

/** @author Jia Pan */

#include "fcl/object/geometry/shape/box.h"

namespace fcl
{

//==============================================================================
template <typename S>
Box<S>::Box(S x, S y, S z)
: ShapeBase<S>(), side(x, y, z)
{
// Do nothing
}

//==============================================================================
template <typename S>
Box<S>::Box(const Vector3<S>& side_)
: ShapeBase<S>(), side(side_)
{
// Do nothing
}

//==============================================================================
template <typename S>
Box<S>::Box()
: ShapeBase<S>(), side(Vector3<S>::Zero())
{
// Do nothing
}

//==============================================================================
template <typename S>
void Box<S>::computeLocalAABB()
{
computeBV(*this, Transform3<S>::Identity(), this->aabb_local);
this->aabb_center = this->aabb_local.center();
this->aabb_radius = (this->aabb_local.min_ - this->aabb_center).norm();
}

//==============================================================================
template <typename S>
NODE_TYPE Box<S>::getNodeType() const
{
return GEOM_BOX;
}

//==============================================================================
template <typename S>
S Box<S>::computeVolume() const
{
return side.prod();
}

//==============================================================================
template <typename S>
Matrix3<S> Box<S>::computeMomentofInertia() const
{
S V = computeVolume();

S a2 = side[0] * side[0] * V;
S b2 = side[1] * side[1] * V;
S c2 = side[2] * side[2] * V;

Vector3<S> I((b2 + c2) / 12, (a2 + c2) / 12, (a2 + b2) / 12);

return I.asDiagonal();
}

//==============================================================================
template <typename S>
std::vector<Vector3<S>> Box<S>::getBoundVertices(
const Transform3<S>& tf) const
{
std::vector<Vector3<S>> result(8);
auto a = side[0] / 2;
auto b = side[1] / 2;
auto c = side[2] / 2;
result[0] = tf * Vector3<S>(a, b, c);
result[1] = tf * Vector3<S>(a, b, -c);
result[2] = tf * Vector3<S>(a, -b, c);
result[3] = tf * Vector3<S>(a, -b, -c);
result[4] = tf * Vector3<S>(-a, b, c);
result[5] = tf * Vector3<S>(-a, b, -c);
result[6] = tf * Vector3<S>(-a, -b, c);
result[7] = tf * Vector3<S>(-a, -b, -c);

return result;
}

} // namespace fcl

#include "fcl/object/geometry/shape/detail/bv_computer_box.h"
148 changes: 148 additions & 0 deletions include/fcl/object/geometry/shape/capsule-inl.h
@@ -0,0 +1,148 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011-2014, Willow Garage, Inc.
* Copyright (c) 2014-2016, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

/** @author Jia Pan */

#include "fcl/object/geometry/shape/capsule.h"

namespace fcl
{

//==============================================================================
template <typename S>
Capsule<S>::Capsule(S radius, S lz)
: ShapeBase<S>(), radius(radius), lz(lz)
{
// Do nothing
}

//==============================================================================
template <typename S>
void Capsule<S>::computeLocalAABB()
{
computeBV(*this, Transform3<S>::Identity(), this->aabb_local);
this->aabb_center = this->aabb_local.center();
this->aabb_radius = (this->aabb_local.min_ - this->aabb_center).norm();
}

//==============================================================================
template <typename S>
NODE_TYPE Capsule<S>::getNodeType() const
{
return GEOM_CAPSULE;
}

//==============================================================================
template <typename S>
S Capsule<S>::computeVolume() const
{
return constants<S>::pi() * radius * radius *(lz + radius * 4/3.0);
}

//==============================================================================
template <typename S>
Matrix3<S> Capsule<S>::computeMomentofInertia() const
{
S v_cyl = radius * radius * lz * constants<S>::pi();
S v_sph = radius * radius * radius * constants<S>::pi() * 4 / 3.0;

S ix = v_cyl * lz * lz / 12.0 + 0.25 * v_cyl * radius + 0.4 * v_sph * radius * radius + 0.25 * v_sph * lz * lz;
S iz = (0.5 * v_cyl + 0.4 * v_sph) * radius * radius;

return Vector3<S>(ix, ix, iz).asDiagonal();
}

//==============================================================================
template <typename S>
std::vector<Vector3<S>> Capsule<S>::getBoundVertices(
const Transform3<S>& tf) const
{
std::vector<Vector3<S>> result(36);
const auto m = (1 + std::sqrt(5.0)) / 2.0;

auto hl = lz * 0.5;
auto edge_size = radius * 6 / (std::sqrt(27.0) + std::sqrt(15.0));
auto a = edge_size;
auto b = m * edge_size;
auto r2 = radius * 2 / std::sqrt(3.0);

result[0] = tf * Vector3<S>(0, a, b + hl);
result[1] = tf * Vector3<S>(0, -a, b + hl);
result[2] = tf * Vector3<S>(0, a, -b + hl);
result[3] = tf * Vector3<S>(0, -a, -b + hl);
result[4] = tf * Vector3<S>(a, b, hl);
result[5] = tf * Vector3<S>(-a, b, hl);
result[6] = tf * Vector3<S>(a, -b, hl);
result[7] = tf * Vector3<S>(-a, -b, hl);
result[8] = tf * Vector3<S>(b, 0, a + hl);
result[9] = tf * Vector3<S>(b, 0, -a + hl);
result[10] = tf * Vector3<S>(-b, 0, a + hl);
result[11] = tf * Vector3<S>(-b, 0, -a + hl);

result[12] = tf * Vector3<S>(0, a, b - hl);
result[13] = tf * Vector3<S>(0, -a, b - hl);
result[14] = tf * Vector3<S>(0, a, -b - hl);
result[15] = tf * Vector3<S>(0, -a, -b - hl);
result[16] = tf * Vector3<S>(a, b, -hl);
result[17] = tf * Vector3<S>(-a, b, -hl);
result[18] = tf * Vector3<S>(a, -b, -hl);
result[19] = tf * Vector3<S>(-a, -b, -hl);
result[20] = tf * Vector3<S>(b, 0, a - hl);
result[21] = tf * Vector3<S>(b, 0, -a - hl);
result[22] = tf * Vector3<S>(-b, 0, a - hl);
result[23] = tf * Vector3<S>(-b, 0, -a - hl);

auto c = 0.5 * r2;
auto d = radius;
result[24] = tf * Vector3<S>(r2, 0, hl);
result[25] = tf * Vector3<S>(c, d, hl);
result[26] = tf * Vector3<S>(-c, d, hl);
result[27] = tf * Vector3<S>(-r2, 0, hl);
result[28] = tf * Vector3<S>(-c, -d, hl);
result[29] = tf * Vector3<S>(c, -d, hl);

result[30] = tf * Vector3<S>(r2, 0, -hl);
result[31] = tf * Vector3<S>(c, d, -hl);
result[32] = tf * Vector3<S>(-c, d, -hl);
result[33] = tf * Vector3<S>(-r2, 0, -hl);
result[34] = tf * Vector3<S>(-c, -d, -hl);
result[35] = tf * Vector3<S>(c, -d, -hl);

return result;
}

} // namespace fcl

#include "fcl/object/geometry/shape/detail/bv_computer_capsule.h"

0 comments on commit abec43c

Please sign in to comment.