Go to the documentation of this file.
   38 #ifndef FCL_MATH_GEOMETRY_H 
   39 #define FCL_MATH_GEOMETRY_H 
   45 #include "fcl/config.h" 
   53 void normalize(Vector3<S>& v, 
bool* signal);
 
   55 template <
typename Derived>
 
   57 typename Derived::RealScalar 
triple(
const Eigen::MatrixBase<Derived>& x,
 
   58                                     const Eigen::MatrixBase<Derived>& y,
 
   59                                     const Eigen::MatrixBase<Derived>& z);
 
   61 template <
typename S, 
int M, 
int N>
 
   64     const VectorN<S, M>& v1, 
const VectorN<S, N>& v2);
 
   68 void hat(Matrix3<S>& mat, 
const Vector3<S>& vec);
 
   74 void eigen(
const Matrix3<S>& m, Vector3<S>& dout, Matrix3<S>& vout);
 
   80 void eigen_old(
const Matrix3<S>& m, Vector3<S>& dout, Matrix3<S>& vout);
 
   85                    const Vector3<S>& eigenS,
 
   91                    const Vector3<S>& eigenS,
 
  104 template <
typename S>
 
  108 template <
typename DerivedA, 
typename DerivedB, 
typename DerivedC, 
typename DerivedD>
 
  111     const Eigen::MatrixBase<DerivedA>& R1, 
const Eigen::MatrixBase<DerivedB>& t1,
 
  112     const Eigen::MatrixBase<DerivedA>& R2, 
const Eigen::MatrixBase<DerivedB>& t2,
 
  113     Eigen::MatrixBase<DerivedC>& R, Eigen::MatrixBase<DerivedD>& t);
 
  115 template <
typename S, 
typename DerivedA, 
typename DerivedB>
 
  118     const Eigen::Transform<S, 3, Eigen::Isometry>& T1,
 
  119     const Eigen::Transform<S, 3, Eigen::Isometry>& T2,
 
  120     Eigen::MatrixBase<DerivedA>& R, Eigen::MatrixBase<DerivedB>& t);
 
  124 template <
typename S>
 
  127     const Vector3<S>* 
const ps,
 
  128     const Vector3<S>* 
const ps2,
 
  130     unsigned int* indices,
 
  132     const Matrix3<S>& axis,
 
  139 template <
typename S>
 
  142     const Vector3<S>* 
const ps,
 
  143     const Vector3<S>* 
const ps2,
 
  145     unsigned int* indices,
 
  152 template <
typename S>
 
  162 template <
typename S>
 
  165     const Vector3<S>* 
const ps,
 
  166     const Vector3<S>* 
const ps2,
 
  168     unsigned int* indices,
 
  170     const Vector3<S>& query);
 
  174 template <
typename S>
 
  177     const Vector3<S>* 
const ps,
 
  178     const Vector3<S>* 
const ps2,
 
  180     unsigned int* indices,
 
  182     const Matrix3<S>& axis,
 
  188 template <
typename S>
 
  191     const Vector3<S>* 
const ps,
 
  192     const Vector3<S>* 
const ps2,
 
  194     unsigned int* indices,
 
  202 template <
typename S>
 
  205     const Vector3<S>* 
const ps,
 
  206     const Vector3<S>* 
const ps2,
 
  208     unsigned int* indices,
 
  
template void circumCircleComputation(const Vector3d &a, const Vector3d &b, const Vector3d &c, Vector3d ¢er, double &radius)
template void axisFromEigen(const Matrix3d &eigenV, const Vector3d &eigenS, Matrix3d &axis)
FCL_EXPORT VectorN< S, M+N > combine(const VectorN< S, M > &v1, const VectorN< S, N > &v2)
template void normalize(Vector3d &v, bool *signal)
template void getCovariance(const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3d &M)
template double maximumDistance(const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3d &query)
template void eigen_old(const Matrix3d &m, Vector3d &dout, Matrix3d &vout)
template Matrix3d generateCoordinateSystem(const Vector3d &x_axis)
template void getExtentAndCenter(const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d ¢er, Vector3d &extent)
template void getRadiusAndOriginAndRectangleSize(const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d &origin, double l[2], double &r)
template void hat(Matrix3d &mat, const Vector3d &vec)
template void eigen(const Matrix3d &m, Vector3d &dout, Matrix3d &vout)
FCL_EXPORT Derived::RealScalar triple(const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z)
FCL_EXPORT void relativeTransform(const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &t1, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &t2, Eigen::MatrixBase< DerivedC > &R, Eigen::MatrixBase< DerivedD > &t)
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:17