Public Member Functions | Public Attributes | List of all members
IceMaths::OBB Class Reference

#include <OPC_IceHook.h>

Public Member Functions

void ComputeLSS (LSS &lss) const
 
bool ComputePlanes (Plane *planes) const
 
bool ComputePoints (Point *pts) const
 
bool ComputeVertexNormals (Point *pts) const
 
void ComputeWorldEdgeNormal (udword edge_index, Point &world_normal) const
 
bool ContainsPoint (const Point &p) const
 
void Create (const AABB &aabb, const Matrix4x4 &mat)
 
inline_ const PointGetCenter () const
 
const udwordGetEdges () const
 
inline_ const PointGetExtents () const
 
const PointGetLocalEdgeNormals () const
 
inline_ const Matrix3x3GetRot () const
 
inline_ void GetRotatedExtents (Matrix3x3 &extents) const
 
BOOL IsInside (const OBB &box) const
 
inline_ BOOL IsValid () const
 
inline_ OBB ()
 Constructor. More...
 
inline_ OBB (const Point &center, const Point &extents, const Matrix3x3 &rot)
 Constructor. More...
 
inline_ void Rotate (const Matrix4x4 &mtx, OBB &obb) const
 
void SetEmpty ()
 
inline_ ~OBB ()
 Destructor. More...
 

Public Attributes

Point mCenter
 B for Box. More...
 
Point mExtents
 B for Bounding. More...
 
Matrix3x3 mRot
 O for Oriented. More...
 

Detailed Description

Definition at line 19 of file OPC_IceHook.h.

Constructor & Destructor Documentation

inline_ IceMaths::OBB::OBB ( )
inline

Constructor.

Definition at line 23 of file OPC_IceHook.h.

inline_ IceMaths::OBB::OBB ( const Point center,
const Point extents,
const Matrix3x3 rot 
)
inline

Constructor.

Definition at line 25 of file OPC_IceHook.h.

inline_ IceMaths::OBB::~OBB ( )
inline

Destructor.

Definition at line 27 of file OPC_IceHook.h.

Member Function Documentation

void OBB::ComputeLSS ( LSS lss) const

Computes an LSS surrounding the OBB.

Parameters
lss[out] the LSS

Definition at line 255 of file IceOBB.cpp.

bool OBB::ComputePlanes ( Plane planes) const

Computes the obb planes.

Parameters
planes[out] 6 box planes
Returns
true if success

Definition at line 82 of file IceOBB.cpp.

bool OBB::ComputePoints ( Point pts) const

Computes the obb points.

Parameters
pts[out] 8 box points
Returns
true if success

Definition at line 125 of file IceOBB.cpp.

bool OBB::ComputeVertexNormals ( Point pts) const

Computes vertex normals.

Parameters
pts[out] 8 box points
Returns
true if success

Definition at line 166 of file IceOBB.cpp.

void OBB::ComputeWorldEdgeNormal ( udword  edge_index,
Point world_normal 
) const

Returns world edge normal

Parameters
edge_index[in] 0 <= edge index < 12
world_normal[out] edge normal in world space

Definition at line 243 of file IceOBB.cpp.

bool OBB::ContainsPoint ( const Point p) const

Tests if a point is contained within the OBB.

Parameters
p[in] the world point to test
Returns
true if inside the OBB

Definition at line 32 of file IceOBB.cpp.

void OBB::Create ( const AABB aabb,
const Matrix4x4 mat 
)

Builds an OBB from an AABB and a world transform.

Parameters
aabb[in] the aabb
mat[in] the world transform

Definition at line 60 of file IceOBB.cpp.

inline_ const Point& IceMaths::OBB::GetCenter ( ) const
inline

Definition at line 160 of file OPC_IceHook.h.

const udword * OBB::GetEdges ( ) const

Returns edges.

Returns
24 indices (12 edges) indexing the list returned by ComputePoints()

Definition at line 197 of file IceOBB.cpp.

inline_ const Point& IceMaths::OBB::GetExtents ( ) const
inline

Definition at line 161 of file OPC_IceHook.h.

const Point * OBB::GetLocalEdgeNormals ( ) const

Returns local edge normals.

Returns
edge normals in local space

Definition at line 214 of file IceOBB.cpp.

inline_ const Matrix3x3& IceMaths::OBB::GetRot ( ) const
inline

Definition at line 162 of file OPC_IceHook.h.

inline_ void IceMaths::OBB::GetRotatedExtents ( Matrix3x3 extents) const
inline

Definition at line 164 of file OPC_IceHook.h.

BOOL OBB::IsInside ( const OBB box) const

Checks the OBB is inside another OBB.

Parameters
box[in] the other OBB
Returns
TRUE if we're inside the other box

Definition at line 288 of file IceOBB.cpp.

inline_ BOOL IceMaths::OBB::IsValid ( ) const
inline

Checks the OBB is valid.

Returns
true if the box is valid

Definition at line 82 of file OPC_IceHook.h.

inline_ void IceMaths::OBB::Rotate ( const Matrix4x4 mtx,
OBB obb 
) const
inline

Recomputes the OBB after an arbitrary transform by a 4x4 matrix.

Parameters
mtx[in] the transform matrix
obb[out] the transformed OBB

Definition at line 66 of file OPC_IceHook.h.

void IceMaths::OBB::SetEmpty ( )
inline

Setups an empty OBB.

Definition at line 34 of file OPC_IceHook.h.

Member Data Documentation

Point IceMaths::OBB::mCenter

B for Box.

Definition at line 170 of file OPC_IceHook.h.

Point IceMaths::OBB::mExtents

B for Bounding.

Definition at line 171 of file OPC_IceHook.h.

Matrix3x3 IceMaths::OBB::mRot

O for Oriented.

Definition at line 172 of file OPC_IceHook.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 May 8 2021 02:42:45