Program Listing for File intersect.h
↰ Return to documentation for file (include/coal/internal/intersect.h
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011-2014, Willow Garage, Inc.
* Copyright (c) 2014-2015, 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.
*/
#ifndef COAL_INTERSECT_H
#define COAL_INTERSECT_H
#include "coal/math/transform.h"
namespace coal {
class COAL_DLLAPI Intersect {
public:
static bool buildTrianglePlane(const Vec3s& v1, const Vec3s& v2,
const Vec3s& v3, Vec3s* n, CoalScalar* t);
}; // class Intersect
class COAL_DLLAPI Project {
public:
struct COAL_DLLAPI ProjectResult {
CoalScalar parameterization[4];
CoalScalar sqr_distance;
unsigned int encode;
ProjectResult() : sqr_distance(-1), encode(0) {}
};
static ProjectResult projectLine(const Vec3s& a, const Vec3s& b,
const Vec3s& p);
static ProjectResult projectTriangle(const Vec3s& a, const Vec3s& b,
const Vec3s& c, const Vec3s& p);
static ProjectResult projectTetrahedra(const Vec3s& a, const Vec3s& b,
const Vec3s& c, const Vec3s& d,
const Vec3s& p);
static ProjectResult projectLineOrigin(const Vec3s& a, const Vec3s& b);
static ProjectResult projectTriangleOrigin(const Vec3s& a, const Vec3s& b,
const Vec3s& c);
static ProjectResult projectTetrahedraOrigin(const Vec3s& a, const Vec3s& b,
const Vec3s& c, const Vec3s& d);
};
class COAL_DLLAPI TriangleDistance {
public:
static void segPoints(const Vec3s& P, const Vec3s& A, const Vec3s& Q,
const Vec3s& B, Vec3s& VEC, Vec3s& X, Vec3s& Y);
static CoalScalar sqrTriDistance(const Vec3s S[3], const Vec3s T[3], Vec3s& P,
Vec3s& Q);
static CoalScalar sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
const Vec3s& S3, const Vec3s& T1,
const Vec3s& T2, const Vec3s& T3, Vec3s& P,
Vec3s& Q);
static CoalScalar sqrTriDistance(const Vec3s S[3], const Vec3s T[3],
const Matrix3s& R, const Vec3s& Tl, Vec3s& P,
Vec3s& Q);
static CoalScalar sqrTriDistance(const Vec3s S[3], const Vec3s T[3],
const Transform3s& tf, Vec3s& P, Vec3s& Q);
static CoalScalar sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
const Vec3s& S3, const Vec3s& T1,
const Vec3s& T2, const Vec3s& T3,
const Matrix3s& R, const Vec3s& Tl, Vec3s& P,
Vec3s& Q);
static CoalScalar sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
const Vec3s& S3, const Vec3s& T1,
const Vec3s& T2, const Vec3s& T3,
const Transform3s& tf, Vec3s& P, Vec3s& Q);
};
} // namespace coal
#endif