FCL  0.6.0
Flexible Collision Library
fcl::OBBRSS< S_ > Class Template Reference

Class merging the OBB and RSS, can handle collision and distance simultaneously. More...

#include <OBBRSS.h>

Public Types

using S = S_
 

Public Member Functions

bool overlap (const OBBRSS< S > &other) const
 Check collision between two OBBRSS.
 
bool overlap (const OBBRSS< S > &other, OBBRSS< S > &overlap_part) const
 Check collision between two OBBRSS and return the overlap part.
 
bool contain (const Vector3< S > &p) const
 Check whether the OBBRSS contains a point.
 
OBBRSS< S > & operator+= (const Vector3< S > &p)
 Merge the OBBRSS and a point.
 
OBBRSS< S > & operator+= (const OBBRSS< S > &other)
 Merge two OBBRSS.
 
OBBRSS< S > operator+ (const OBBRSS< S > &other) const
 Merge two OBBRSS.
 
width () const
 Width of the OBRSS.
 
height () const
 Height of the OBBRSS.
 
depth () const
 Depth of the OBBRSS.
 
volume () const
 Volume of the OBBRSS.
 
size () const
 Size of the OBBRSS (used in BV_Splitter to order two OBBRSS)
 
const Vector3< S > center () const
 Center of the OBBRSS.
 
distance (const OBBRSS< S > &other, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) const
 Distance between two OBBRSS; P and Q , is not nullptr, returns the nearest points.
 

Public Attributes

OBB< S > obb
 OBB member, for rotation.
 
RSS< S > rss
 RSS member, for distance.
 

Detailed Description

template<typename S_>
class fcl::OBBRSS< S_ >

Class merging the OBB and RSS, can handle collision and distance simultaneously.


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