Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
fcl::detail::OcTreeSolver< NarrowPhaseSolver > Class Template Reference

Algorithms for collision related with octree. More...

#include <octree_solver.h>

Public Member Functions

template<typename BV >
void MeshOcTreeDistance (const BVHModel< BV > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
 distance between mesh and octree More...
 
template<typename BV >
void MeshOcTreeIntersect (const BVHModel< BV > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
 collision between mesh and octree More...
 
void OcTreeDistance (const OcTree< S > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
 distance between two octrees More...
 
void OcTreeIntersect (const OcTree< S > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
 collision between two octrees More...
 
template<typename BV >
void OcTreeMeshDistance (const OcTree< S > *tree1, const BVHModel< BV > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
 distance between octree and mesh More...
 
template<typename BV >
void OcTreeMeshIntersect (const OcTree< S > *tree1, const BVHModel< BV > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
 collision between octree and mesh More...
 
template<typename Shape >
void OcTreeShapeDistance (const OcTree< S > *tree, const Shape &s, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
 distance between octree and shape More...
 
template<typename Shape >
void OcTreeShapeIntersect (const OcTree< S > *tree, const Shape &s, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
 collision between octree and shape More...
 
 OcTreeSolver (const NarrowPhaseSolver *solver_)
 
template<typename Shape >
void ShapeOcTreeDistance (const Shape &s, const OcTree< S > *tree, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
 distance between shape and octree More...
 
template<typename Shape >
void ShapeOcTreeIntersect (const Shape &s, const OcTree< S > *tree, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
 collision between shape and octree More...
 

Private Types

using S = typename NarrowPhaseSolver::S
 

Private Member Functions

bool OcTreeDistanceRecurse (const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const OcTree< S > *tree2, const typename OcTree< S >::OcTreeNode *root2, const AABB< S > &bv2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
 
bool OcTreeIntersectRecurse (const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const OcTree< S > *tree2, const typename OcTree< S >::OcTreeNode *root2, const AABB< S > &bv2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
 
template<typename BV >
bool OcTreeMeshDistanceRecurse (const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const BVHModel< BV > *tree2, int root2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
 
template<typename BV >
bool OcTreeMeshIntersectRecurse (const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const BVHModel< BV > *tree2, int root2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
 
template<typename Shape >
bool OcTreeShapeDistanceRecurse (const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const Shape &s, const AABB< S > &aabb2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
 
template<typename Shape >
bool OcTreeShapeIntersectRecurse (const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const Shape &s, const OBB< S > &obb2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
 

Private Attributes

const CollisionRequest< S > * crequest
 
CollisionResult< S > * cresult
 
const DistanceRequest< S > * drequest
 
DistanceResult< S > * dresult
 
const NarrowPhaseSolver * solver
 

Detailed Description

template<typename NarrowPhaseSolver>
class fcl::detail::OcTreeSolver< NarrowPhaseSolver >

Algorithms for collision related with octree.

Definition at line 59 of file octree_solver.h.

Member Typedef Documentation

◆ S

template<typename NarrowPhaseSolver >
using fcl::detail::OcTreeSolver< NarrowPhaseSolver >::S = typename NarrowPhaseSolver::S
private

Definition at line 63 of file octree_solver.h.

Constructor & Destructor Documentation

◆ OcTreeSolver()

template<typename NarrowPhaseSolver >
fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeSolver ( const NarrowPhaseSolver *  solver_)

Definition at line 53 of file octree_solver-inl.h.

Member Function Documentation

◆ MeshOcTreeDistance()

template<typename NarrowPhaseSolver >
template<typename BV >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::MeshOcTreeDistance ( const BVHModel< BV > *  tree1,
const OcTree< S > *  tree2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const DistanceRequest< S > &  request_,
DistanceResult< S > &  result_ 
) const

distance between mesh and octree

Definition at line 162 of file octree_solver-inl.h.

◆ MeshOcTreeIntersect()

template<typename NarrowPhaseSolver >
template<typename BV >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::MeshOcTreeIntersect ( const BVHModel< BV > *  tree1,
const OcTree< S > *  tree2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const CollisionRequest< S > &  request_,
CollisionResult< S > &  result_ 
) const

collision between mesh and octree

Definition at line 141 of file octree_solver-inl.h.

◆ OcTreeDistance()

template<typename NarrowPhaseSolver >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeDistance ( const OcTree< S > *  tree1,
const OcTree< S > *  tree2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const DistanceRequest< S > &  request_,
DistanceResult< S > &  result_ 
) const

distance between two octrees

Definition at line 84 of file octree_solver-inl.h.

◆ OcTreeDistanceRecurse()

template<typename NarrowPhaseSolver >
bool fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeDistanceRecurse ( const OcTree< S > *  tree1,
const typename OcTree< S >::OcTreeNode *  root1,
const AABB< S > &  bv1,
const OcTree< S > *  tree2,
const typename OcTree< S >::OcTreeNode *  root2,
const AABB< S > &  bv2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2 
) const
private

Definition at line 765 of file octree_solver-inl.h.

◆ OcTreeIntersect()

template<typename NarrowPhaseSolver >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeIntersect ( const OcTree< S > *  tree1,
const OcTree< S > *  tree2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const CollisionRequest< S > &  request_,
CollisionResult< S > &  result_ 
) const

collision between two octrees

Definition at line 66 of file octree_solver-inl.h.

◆ OcTreeIntersectRecurse()

template<typename NarrowPhaseSolver >
bool fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeIntersectRecurse ( const OcTree< S > *  tree1,
const typename OcTree< S >::OcTreeNode *  root1,
const AABB< S > &  bv1,
const OcTree< S > *  tree2,
const typename OcTree< S >::OcTreeNode *  root2,
const AABB< S > &  bv2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2 
) const
private

stop when 1) bounding boxes of two objects not overlap; OR 2) at least one of the nodes is free; OR 2) (two uncertain nodes OR one node occupied and one node uncertain) AND cost not required

Definition at line 852 of file octree_solver-inl.h.

◆ OcTreeMeshDistance()

template<typename NarrowPhaseSolver >
template<typename BV >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeMeshDistance ( const OcTree< S > *  tree1,
const BVHModel< BV > *  tree2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const DistanceRequest< S > &  request_,
DistanceResult< S > &  result_ 
) const

distance between octree and mesh

Definition at line 122 of file octree_solver-inl.h.

◆ OcTreeMeshDistanceRecurse()

template<typename NarrowPhaseSolver >
template<typename BV >
bool fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeMeshDistanceRecurse ( const OcTree< S > *  tree1,
const typename OcTree< S >::OcTreeNode *  root1,
const AABB< S > &  bv1,
const BVHModel< BV > *  tree2,
int  root2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2 
) const
private

Definition at line 487 of file octree_solver-inl.h.

◆ OcTreeMeshIntersect()

template<typename NarrowPhaseSolver >
template<typename BV >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeMeshIntersect ( const OcTree< S > *  tree1,
const BVHModel< BV > *  tree2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const CollisionRequest< S > &  request_,
CollisionResult< S > &  result_ 
) const

collision between octree and mesh

Definition at line 103 of file octree_solver-inl.h.

◆ OcTreeMeshIntersectRecurse()

template<typename NarrowPhaseSolver >
template<typename BV >
bool fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeMeshIntersectRecurse ( const OcTree< S > *  tree1,
const typename OcTree< S >::OcTreeNode *  root1,
const AABB< S > &  bv1,
const BVHModel< BV > *  tree2,
int  root2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2 
) const
private

stop when 1) bounding boxes of two objects not overlap; OR 2) at least one of the nodes is free; OR 2) (two uncertain nodes OR one node occupied and one node uncertain) AND cost not required

Definition at line 575 of file octree_solver-inl.h.

◆ OcTreeShapeDistance()

template<typename NarrowPhaseSolver >
template<typename Shape >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeShapeDistance ( const OcTree< S > *  tree,
const Shape &  s,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const DistanceRequest< S > &  request_,
DistanceResult< S > &  result_ 
) const

distance between octree and shape

Definition at line 231 of file octree_solver-inl.h.

◆ OcTreeShapeDistanceRecurse()

template<typename NarrowPhaseSolver >
template<typename Shape >
bool fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeShapeDistanceRecurse ( const OcTree< S > *  tree1,
const typename OcTree< S >::OcTreeNode *  root1,
const AABB< S > &  bv1,
const Shape &  s,
const AABB< S > &  aabb2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2 
) const
private

Definition at line 274 of file octree_solver-inl.h.

◆ OcTreeShapeIntersect()

template<typename NarrowPhaseSolver >
template<typename Shape >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeShapeIntersect ( const OcTree< S > *  tree,
const Shape &  s,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const CollisionRequest< S > &  request_,
CollisionResult< S > &  result_ 
) const

collision between octree and shape

Definition at line 182 of file octree_solver-inl.h.

◆ OcTreeShapeIntersectRecurse()

template<typename NarrowPhaseSolver >
template<typename Shape >
bool fcl::detail::OcTreeSolver< NarrowPhaseSolver >::OcTreeShapeIntersectRecurse ( const OcTree< S > *  tree1,
const typename OcTree< S >::OcTreeNode *  root1,
const AABB< S > &  bv1,
const Shape &  s,
const OBB< S > &  obb2,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2 
) const
private

stop when 1) bounding boxes of two objects not overlap; OR 2) at least of one the nodes is free; OR 2) (two uncertain nodes or one node occupied and one node uncertain) AND cost not required

Definition at line 332 of file octree_solver-inl.h.

◆ ShapeOcTreeDistance()

template<typename NarrowPhaseSolver >
template<typename Shape >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::ShapeOcTreeDistance ( const Shape &  s,
const OcTree< S > *  tree,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const DistanceRequest< S > &  request_,
DistanceResult< S > &  result_ 
) const

distance between shape and octree

Definition at line 253 of file octree_solver-inl.h.

◆ ShapeOcTreeIntersect()

template<typename NarrowPhaseSolver >
template<typename Shape >
void fcl::detail::OcTreeSolver< NarrowPhaseSolver >::ShapeOcTreeIntersect ( const Shape &  s,
const OcTree< S > *  tree,
const Transform3< S > &  tf1,
const Transform3< S > &  tf2,
const CollisionRequest< S > &  request_,
CollisionResult< S > &  result_ 
) const

collision between shape and octree

Definition at line 207 of file octree_solver-inl.h.

Member Data Documentation

◆ crequest

template<typename NarrowPhaseSolver >
const CollisionRequest<S>* fcl::detail::OcTreeSolver< NarrowPhaseSolver >::crequest
mutableprivate

Definition at line 67 of file octree_solver.h.

◆ cresult

template<typename NarrowPhaseSolver >
CollisionResult<S>* fcl::detail::OcTreeSolver< NarrowPhaseSolver >::cresult
mutableprivate

Definition at line 70 of file octree_solver.h.

◆ drequest

template<typename NarrowPhaseSolver >
const DistanceRequest<S>* fcl::detail::OcTreeSolver< NarrowPhaseSolver >::drequest
mutableprivate

Definition at line 68 of file octree_solver.h.

◆ dresult

template<typename NarrowPhaseSolver >
DistanceResult<S>* fcl::detail::OcTreeSolver< NarrowPhaseSolver >::dresult
mutableprivate

Definition at line 71 of file octree_solver.h.

◆ solver

template<typename NarrowPhaseSolver >
const NarrowPhaseSolver* fcl::detail::OcTreeSolver< NarrowPhaseSolver >::solver
private

Definition at line 65 of file octree_solver.h.


The documentation for this class was generated from the following files:


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:51