Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
RayCollider Class Reference

#include <OPC_RayCollider.h>

Inheritance diagram for RayCollider:
Inheritance graph
[legend]

Public Member Functions

bool Collide (const Ray &world_ray, const Model &model, const Matrix4x4 *world=null, udword *cache=null)
 
bool Collide (const Ray &world_ray, const AABBTree *tree, Container &box_indices)
 
inline_ udword GetNbIntersections () const
 
inline_ udword GetNbRayBVTests () const
 
inline_ udword GetNbRayPrimTests () const
 
 override (Collider) const char *ValidateSettings()
 
 RayCollider ()
 
inline_ void SetClosestHit (bool flag)
 
inline_ void SetCulling (bool flag)
 
inline_ void SetDestination (CollisionFaces *cf)
 
inline_ void SetMaxDist (float max_dist=MAX_FLOAT)
 
virtual ~RayCollider ()
 
- Public Member Functions inherited from Collider
 Collider ()
 
inline_ BOOL ContactFound () const
 
inline_ BOOL FirstContactEnabled () const
 
inline_ BOOL GetContactStatus () const
 
inline_ void SetFirstContact (bool flag)
 
inline_ void SetPrimitiveTests (bool flag)
 
inline_ void SetTemporalCoherence (bool flag)
 
inline_ BOOL SkipPrimitiveTests () const
 
inline_ BOOL TemporalCoherenceEnabled () const
 
inline_ BOOL TemporalHit () const
 
virtual const char * ValidateSettings ()=0
 
virtual ~Collider ()
 

Protected Member Functions

void _RayStab (const AABBCollisionNode *node)
 
void _RayStab (const AABBNoLeafNode *node)
 
void _RayStab (const AABBQuantizedNode *node)
 
void _RayStab (const AABBQuantizedNoLeafNode *node)
 
void _RayStab (const AABBTreeNode *node, Container &box_indices)
 
void _SegmentStab (const AABBCollisionNode *node)
 
void _SegmentStab (const AABBNoLeafNode *node)
 
void _SegmentStab (const AABBQuantizedNode *node)
 
void _SegmentStab (const AABBQuantizedNoLeafNode *node)
 
void _SegmentStab (const AABBTreeNode *node, Container &box_indices)
 
BOOL InitQuery (const Ray &world_ray, const Matrix4x4 *world=null, udword *face_id=null)
 
inline_ BOOL RayAABBOverlap (const Point &center, const Point &extents)
 
inline_ BOOL RayTriOverlap (const Point &vert0, const Point &vert1, const Point &vert2)
 
inline_ BOOL SegmentAABBOverlap (const Point &center, const Point &extents)
 
- Protected Member Functions inherited from Collider
virtual inline_ void InitQuery ()
 
inline_ BOOL Setup (const BaseModel *model)
 

Protected Attributes

Point mCenterCoeff
 
bool mClosestHit
 Report closest hit only. More...
 
bool mCulling
 Stab culled faces or not. More...
 
Point mData
 
Point mData2
 
Point mDir
 Ray direction (normalized) More...
 
Point mExtentsCoeff
 
Point mFDir
 fabsf(mDir) More...
 
float mMaxDist
 Valid segment on the ray. More...
 
udword mNbIntersections
 Number of valid intersections. More...
 
udword mNbRayBVTests
 Number of Ray-BV tests. More...
 
udword mNbRayPrimTests
 Number of Ray-Primitive tests. More...
 
Point mOrigin
 Ray origin. More...
 
CollisionFace mStabbedFace
 Current stabbed face. More...
 
CollisionFacesmStabbedFaces
 List of stabbed faces. More...
 
- Protected Attributes inherited from Collider
const BaseModelmCurrentModel
 Current model for collision query (owner of touched faces) More...
 
udword mFlags
 Bit flags. More...
 
const MeshInterfacemIMesh
 User-defined mesh interface. More...
 

Detailed Description

Contains a ray-vs-tree collider. This class performs a stabbing query on an AABB tree, i.e. does a ray-mesh collision.

HIGHER DISTANCE BOUND:

    If P0 and P1 are two 3D points, let's define:
    - d = distance between P0 and P1
    - Origin        = P0
    - Direction     = (P1 - P0) / d = normalized direction vector
    - A parameter t such as a point P on the line (P0,P1) is P = Origin + t * Direction
    - t = 0  -->  P = P0
    - t = d  -->  P = P1

    Then we can define a general "ray" as:

            struct Ray
            {
                    Point   Origin;
                    Point   Direction;
            };

    But it actually maps three different things:
    - a segment,   when 0 <= t <= d
    - a half-line, when 0 <= t < +infinity, or -infinity < t <= d
    - a line,      when -infinity < t < +infinity

    In Opcode, we support segment queries, which yield half-line queries by setting d = +infinity.
    We don't support line-queries. If you need them, shift the origin along the ray by an appropriate margin.

    In short, the lower bound is always 0, and you can setup the higher bound "d" with RayCollider::SetMaxDist().

    Query   |segment                        |half-line              |line
    --------|-------------------|---------------|----------------
    Usages  |-shadow feelers        |-raytracing    |-
                    |-sweep tests           |-in/out tests  |

FIRST CONTACT:

    - You can setup "first contact" mode or "all contacts" mode with RayCollider::SetFirstContact().
    - In "first contact" mode we return as soon as the ray hits one face. If can be useful e.g. for shadow feelers, where
    you want to know whether the path to the light is free or not (a boolean answer is enough).
    - In "all contacts" mode we return all faces hit by the ray.

TEMPORAL COHERENCE:

    - You can enable or disable temporal coherence with RayCollider::SetTemporalCoherence().
    - It currently only works in "first contact" mode.
    - If temporal coherence is enabled, the previously hit triangle is cached during the first query. Then, next queries
    start by colliding the ray against the cached triangle. If they still collide, we return immediately.

CLOSEST HIT:

    - You can enable or disable "closest hit" with RayCollider::SetClosestHit().
    - It currently only works in "all contacts" mode.
    - If closest hit is enabled, faces are sorted by distance on-the-fly and the closest one only is reported.

BACKFACE CULLING:

    - You can enable or disable backface culling with RayCollider::SetCulling().
    - If culling is enabled, ray will not hit back faces (only front faces).
Author
Pierre Terdiman
Version
1.3
Date
June, 2, 2001

Definition at line 63 of file OPC_RayCollider.h.

Constructor & Destructor Documentation

RayCollider::RayCollider ( )
virtual RayCollider::~RayCollider ( )
virtual

Member Function Documentation

void RayCollider::_RayStab ( const AABBCollisionNode node)
protected
void RayCollider::_RayStab ( const AABBNoLeafNode node)
protected
void RayCollider::_RayStab ( const AABBQuantizedNode node)
protected
void RayCollider::_RayStab ( const AABBQuantizedNoLeafNode node)
protected
void RayCollider::_RayStab ( const AABBTreeNode node,
Container box_indices 
)
protected
void RayCollider::_SegmentStab ( const AABBCollisionNode node)
protected
void RayCollider::_SegmentStab ( const AABBNoLeafNode node)
protected
void RayCollider::_SegmentStab ( const AABBQuantizedNode node)
protected
void RayCollider::_SegmentStab ( const AABBQuantizedNoLeafNode node)
protected
void RayCollider::_SegmentStab ( const AABBTreeNode node,
Container box_indices 
)
protected
bool RayCollider::Collide ( const Ray world_ray,
const Model model,
const Matrix4x4 world = null,
udword cache = null 
)

Generic stabbing query for generic OPCODE models. After the call, access the results:

Parameters
world_ray[in] stabbing ray in world space
model[in] Opcode model to collide with
world[in] model's world matrix, or null
cache[in] a possibly cached face index, or null
Returns
true if success
Warning
SCALE NOT SUPPORTED. The matrices must contain rotation & translation parts only.
bool RayCollider::Collide ( const Ray world_ray,
const AABBTree tree,
Container box_indices 
)
inline_ udword RayCollider::GetNbIntersections ( ) const
inline

Stats: gets the number of intersection found after a collision query. Can be used for in/out tests.

See also
GetNbRayBVTests()
GetNbRayPrimTests()
Returns
the number of valid intersections during last query

Definition at line 168 of file OPC_RayCollider.h.

inline_ udword RayCollider::GetNbRayBVTests ( ) const
inline

Stats: gets the number of Ray-BV overlap tests after a collision query.

See also
GetNbRayPrimTests()
GetNbIntersections()
Returns
the number of Ray-BV tests performed during last query

Definition at line 147 of file OPC_RayCollider.h.

inline_ udword RayCollider::GetNbRayPrimTests ( ) const
inline

Stats: gets the number of Ray-Triangle overlap tests after a collision query.

See also
GetNbRayBVTests()
GetNbIntersections()
Returns
the number of Ray-Triangle tests performed during last query

Definition at line 157 of file OPC_RayCollider.h.

BOOL RayCollider::InitQuery ( const Ray world_ray,
const Matrix4x4 world = null,
udword face_id = null 
)
protected
RayCollider::override ( Collider  ) const

Validates current settings. You should call this method after all the settings and callbacks have been defined for a collider.

Returns
null if everything is ok, else a string describing the problem
inline_ BOOL RayCollider::RayAABBOverlap ( const Point center,
const Point extents 
)
protected

Computes a ray-AABB overlap test using the separating axis theorem. Ray is cached within the class.

Parameters
center[in] AABB center
extents[in] AABB extents
Returns
true on overlap

Definition at line 40 of file OPC_RayAABBOverlap.h.

inline_ BOOL RayCollider::RayTriOverlap ( const Point vert0,
const Point vert1,
const Point vert2 
)
protected

Computes a ray-triangle intersection test. Original code from Tomas Möller's "Fast Minimum Storage Ray-Triangle Intersection". It's been optimized a bit with integer code, and modified to return a non-intersection if distance from ray origin to triangle is negative.

Parameters
vert0[in] triangle vertex
vert1[in] triangle vertex
vert2[in] triangle vertex
Returns
true on overlap. mStabbedFace is filled with relevant info.

Definition at line 16 of file OPC_RayTriOverlap.h.

inline_ BOOL RayCollider::SegmentAABBOverlap ( const Point center,
const Point extents 
)
protected

Computes a segment-AABB overlap test using the separating axis theorem. Segment is cached within the class.

Parameters
center[in] AABB center
extents[in] AABB extents
Returns
true on overlap

Definition at line 15 of file OPC_RayAABBOverlap.h.

inline_ void RayCollider::SetClosestHit ( bool  flag)
inline

Settings: enable or disable "closest hit" mode.

Parameters
flag[in] true to report closest hit only
See also
SetCulling(bool flag)
SetMaxDist(float max_dist)
SetDestination(StabbedFaces* sf)

Definition at line 99 of file OPC_RayCollider.h.

inline_ void RayCollider::SetCulling ( bool  flag)
inline

Settings: enable or disable backface culling.

Parameters
flag[in] true to enable backface culling
See also
SetClosestHit(bool flag)
SetMaxDist(float max_dist)
SetDestination(StabbedFaces* sf)

Definition at line 110 of file OPC_RayCollider.h.

inline_ void RayCollider::SetDestination ( CollisionFaces cf)
inline

Settings: sets the destination array for stabbed faces.

Parameters
cf[in] destination array, filled during queries
See also
SetClosestHit(bool flag)
SetCulling(bool flag)
SetMaxDist(float max_dist)

Definition at line 136 of file OPC_RayCollider.h.

inline_ void RayCollider::SetMaxDist ( float  max_dist = MAX_FLOAT)
inline

Settings: sets the higher distance bound.

Parameters
max_dist[in] higher distance bound. Default = maximal value, for ray queries (else segment)
See also
SetClosestHit(bool flag)
SetCulling(bool flag)
SetDestination(StabbedFaces* sf)

Definition at line 121 of file OPC_RayCollider.h.

Member Data Documentation

Point RayCollider::mCenterCoeff
protected

Definition at line 198 of file OPC_RayCollider.h.

bool RayCollider::mClosestHit
protected

Report closest hit only.

Definition at line 203 of file OPC_RayCollider.h.

bool RayCollider::mCulling
protected

Stab culled faces or not.

Definition at line 205 of file OPC_RayCollider.h.

Point RayCollider::mData
protected

Definition at line 183 of file OPC_RayCollider.h.

Point RayCollider::mData2
protected

Definition at line 183 of file OPC_RayCollider.h.

Point RayCollider::mDir
protected

Ray direction (normalized)

Definition at line 181 of file OPC_RayCollider.h.

Point RayCollider::mExtentsCoeff
protected

Definition at line 199 of file OPC_RayCollider.h.

Point RayCollider::mFDir
protected

fabsf(mDir)

Definition at line 182 of file OPC_RayCollider.h.

float RayCollider::mMaxDist
protected

Valid segment on the ray.

Definition at line 201 of file OPC_RayCollider.h.

udword RayCollider::mNbIntersections
protected

Number of valid intersections.

Definition at line 196 of file OPC_RayCollider.h.

udword RayCollider::mNbRayBVTests
protected

Number of Ray-BV tests.

Definition at line 193 of file OPC_RayCollider.h.

udword RayCollider::mNbRayPrimTests
protected

Number of Ray-Primitive tests.

Definition at line 194 of file OPC_RayCollider.h.

Point RayCollider::mOrigin
protected

Ray origin.

Definition at line 180 of file OPC_RayCollider.h.

CollisionFace RayCollider::mStabbedFace
protected

Current stabbed face.

Definition at line 185 of file OPC_RayCollider.h.

CollisionFaces* RayCollider::mStabbedFaces
protected

List of stabbed faces.

Definition at line 190 of file OPC_RayCollider.h.


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


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat Apr 13 2019 02:14:29