Blender V2.61 - r43446
|
#include <math.h>
#include <stdlib.h>
#include <cstdlib>
#include <cfloat>
#include <float.h>
#include <assert.h>
Go to the source code of this file.
Classes | |
struct | btTypedObject |
rudimentary class to provide type info More... | |
Defines | |
#define | BT_BULLET_VERSION 278 |
#define | SIMD_FORCE_INLINE inline |
#define | ATTRIBUTE_ALIGNED16(a) a |
#define | ATTRIBUTE_ALIGNED64(a) a |
#define | ATTRIBUTE_ALIGNED128(a) a |
#define | btAssert(x) |
#define | btFullAssert(x) |
#define | btLikely(_c) _c |
#define | btUnlikely(_c) _c |
#define | BT_LARGE_FLOAT 1e18f |
#define | BT_DECLARE_ALIGNED_ALLOCATOR() |
#define | SIMD_2_PI btScalar(6.283185307179586232) |
#define | SIMD_PI (SIMD_2_PI * btScalar(0.5)) |
#define | SIMD_HALF_PI (SIMD_2_PI * btScalar(0.25)) |
#define | SIMD_RADS_PER_DEG (SIMD_2_PI / btScalar(360.0)) |
#define | SIMD_DEGS_PER_RAD (btScalar(360.0) / SIMD_2_PI) |
#define | SIMDSQRT12 btScalar(0.7071067811865475244008443621048490) |
#define | btRecipSqrt(x) ((btScalar)(btScalar(1.0)/btSqrt(btScalar(x)))) |
#define | SIMD_EPSILON FLT_EPSILON |
#define | SIMD_INFINITY FLT_MAX |
#define | BT_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name |
#define | btFsels(a, b, c) (btScalar)btFsel(a,b,c) |
Typedefs | |
typedef float | btScalar |
The btScalar type abstracts floating point numbers, to easily switch between double and single floating point precision. | |
Functions | |
int | btGetVersion () |
SIMD_FORCE_INLINE btScalar | btSqrt (btScalar y) |
SIMD_FORCE_INLINE btScalar | btFabs (btScalar x) |
SIMD_FORCE_INLINE btScalar | btCos (btScalar x) |
SIMD_FORCE_INLINE btScalar | btSin (btScalar x) |
SIMD_FORCE_INLINE btScalar | btTan (btScalar x) |
SIMD_FORCE_INLINE btScalar | btAcos (btScalar x) |
SIMD_FORCE_INLINE btScalar | btAsin (btScalar x) |
SIMD_FORCE_INLINE btScalar | btAtan (btScalar x) |
SIMD_FORCE_INLINE btScalar | btAtan2 (btScalar x, btScalar y) |
SIMD_FORCE_INLINE btScalar | btExp (btScalar x) |
SIMD_FORCE_INLINE btScalar | btLog (btScalar x) |
SIMD_FORCE_INLINE btScalar | btPow (btScalar x, btScalar y) |
SIMD_FORCE_INLINE btScalar | btFmod (btScalar x, btScalar y) |
SIMD_FORCE_INLINE btScalar | btAtan2Fast (btScalar y, btScalar x) |
SIMD_FORCE_INLINE bool | btFuzzyZero (btScalar x) |
SIMD_FORCE_INLINE bool | btEqual (btScalar a, btScalar eps) |
SIMD_FORCE_INLINE bool | btGreaterEqual (btScalar a, btScalar eps) |
SIMD_FORCE_INLINE int | btIsNegative (btScalar x) |
SIMD_FORCE_INLINE btScalar | btRadians (btScalar x) |
SIMD_FORCE_INLINE btScalar | btDegrees (btScalar x) |
SIMD_FORCE_INLINE btScalar | btFsel (btScalar a, btScalar b, btScalar c) |
SIMD_FORCE_INLINE bool | btMachineIsLittleEndian () |
SIMD_FORCE_INLINE unsigned | btSelect (unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) |
SIMD_FORCE_INLINE int | btSelect (unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero) |
SIMD_FORCE_INLINE float | btSelect (unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero) |
template<typename T > | |
SIMD_FORCE_INLINE void | btSwap (T &a, T &b) |
SIMD_FORCE_INLINE unsigned | btSwapEndian (unsigned val) |
SIMD_FORCE_INLINE unsigned short | btSwapEndian (unsigned short val) |
SIMD_FORCE_INLINE unsigned | btSwapEndian (int val) |
SIMD_FORCE_INLINE unsigned short | btSwapEndian (short val) |
SIMD_FORCE_INLINE unsigned int | btSwapEndianFloat (float d) |
btSwapFloat uses using char pointers to swap the endianness | |
SIMD_FORCE_INLINE float | btUnswapEndianFloat (unsigned int a) |
SIMD_FORCE_INLINE void | btSwapEndianDouble (double d, unsigned char *dst) |
SIMD_FORCE_INLINE double | btUnswapEndianDouble (const unsigned char *src) |
SIMD_FORCE_INLINE btScalar | btNormalizeAngle (btScalar angleInRadians) |
#define ATTRIBUTE_ALIGNED128 | ( | a | ) | a |
Definition at line 181 of file btScalar.h.
#define ATTRIBUTE_ALIGNED16 | ( | a | ) | a |
Definition at line 179 of file btScalar.h.
Referenced by btDbvtBroadphase::aabbTest(), bounds(), btDbvtBroadphase::collide(), btDbvt::collideTV(), btSoftBody::defaultCollisionHandler(), btDbvtBroadphase::getBroadphaseAabb(), merge(), btSoftBody::predictMotion(), btSoftColliders::CollideCL_RS::Process(), btCompoundCollisionAlgorithm::processCollision(), btSoftBody::scale(), Select(), btDbvtBroadphase::setAabb(), btDbvtBroadphase::setAabbForceUpdate(), btSoftBody::transform(), and btSoftBody::updateClusters().
#define ATTRIBUTE_ALIGNED64 | ( | a | ) | a |
Definition at line 180 of file btScalar.h.
#define BT_BULLET_VERSION 278 |
Definition at line 33 of file btScalar.h.
Referenced by btGetVersion().
#define BT_DECLARE_ALIGNED_ALLOCATOR | ( | ) |
SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes,16); } \ SIMD_FORCE_INLINE void operator delete(void* ptr) { btAlignedFree(ptr); } \ SIMD_FORCE_INLINE void* operator new(size_t, void* ptr) { return ptr; } \ SIMD_FORCE_INLINE void operator delete(void*, void*) { } \ SIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes,16); } \ SIMD_FORCE_INLINE void operator delete[](void* ptr) { btAlignedFree(ptr); } \ SIMD_FORCE_INLINE void* operator new[](size_t, void* ptr) { return ptr; } \ SIMD_FORCE_INLINE void operator delete[](void*, void*) { } \
Definition at line 217 of file btScalar.h.
Referenced by ATTRIBUTE_ALIGNED128(), ATTRIBUTE_ALIGNED16(), and ATTRIBUTE_ALIGNED64().
#define BT_DECLARE_HANDLE | ( | name | ) | typedef struct name##__ { int unused; } *name |
Definition at line 345 of file btScalar.h.
#define BT_LARGE_FLOAT 1e18f |
Definition at line 212 of file btScalar.h.
Referenced by btMultiSphereShape::batchedUnitVectorGetSupportingVertexWithoutMargin(), btCapsuleShape::batchedUnitVectorGetSupportingVertexWithoutMargin(), btConvexTriangleMeshShape::batchedUnitVectorGetSupportingVertexWithoutMargin(), btPolyhedralConvexShape::batchedUnitVectorGetSupportingVertexWithoutMargin(), btGenerateInternalEdgeInfo(), btSingleRayCallback::btSingleRayCallback(), btSingleSweepCallback::btSingleSweepCallback(), btMinkowskiPenetrationDepthSolver::calcPenDepth(), btStridingMeshInterface::calculateAabbBruteForce(), btConvexTriangleMeshShape::calculatePrincipalAxisTransform(), convexHullSupport(), cullPoints2(), btCollisionWorld::debugDrawObject(), EdgeSeparation(), FindIncidentEdge(), FindMaxSeparation(), btBU_Simplex1to4::getAabb(), btMultiSapBroadphase::getBroadphaseAabb(), btSimpleBroadphase::getBroadphaseAabb(), btGjkPairDetector::getClosestPointsNonVirtual(), btConeTwistConstraint::init(), btSoftBody::initializeClusters(), btTriangleMeshShape::localGetSupportingVertex(), btConvexTriangleMeshShape::localGetSupportingVertexWithoutMargin(), btMultiSphereShape::localGetSupportingVertexWithoutMargin(), btPolyhedralConvexShape::localGetSupportingVertexWithoutMargin(), btCapsuleShape::localGetSupportingVertexWithoutMargin(), btVector4::maxAxis4(), btVector4::minAxis4(), btConvexConvexAlgorithm::processCollision(), btBoxBoxCollisionAlgorithm::processCollision(), btSphereTriangleCollisionAlgorithm::processCollision(), btDbvt::rayTest(), btVoronoiSimplexSolver::reset(), CcdPhysicsEnvironment::setConstraintParam(), btRotationalLimitMotor::solveAngularLimits(), and btTranslationalLimitMotor::solveLinearAxis().
#define btAssert | ( | x | ) |
Definition at line 189 of file btScalar.h.
Referenced by gim_hash_table< T >::_assign_hash_table_cell(), GIM_BOX_TREE::_build_sub_tree(), btQuantizedBvhTree::_build_sub_tree(), btBvhTree::_build_sub_tree(), gim_hash_table< T >::_erase_by_index_hash_table(), gim_hash_table< T >::_erase_unsorted(), gim_hash_table< T >::_rehash(), btBvhTree::_sort_and_calc_splitting_index(), GIM_BOX_TREE::_sort_and_calc_splitting_index(), btQuantizedBvhTree::_sort_and_calc_splitting_index(), btGImpactCompoundShape::addChildShape(), btCollisionWorld::addCollisionObject(), btManifoldResult::addContactPoint(), btPairCachingGhostObject::addOverlappingObjectInternal(), btSortedOverlappingPairCache::addOverlappingPair(), btCollisionWorld::ClosestRayResultCallback::addSingleResult(), btCollisionWorld::ClosestConvexResultCallback::addSingleResult(), btPoolAllocator::allocate(), btStackAlloc::allocate(), btAxisSweep3Internal< BP_FP_INT_TYPE >::allocHandle(), btSimpleBroadphase::allocHandle(), btQuaternion::angle(), btSoftBody::appendFace(), btRaycastVehicle::applyEngineForce(), ATTRIBUTE_ALIGNED128(), ATTRIBUTE_ALIGNED16(), bt32BitAxisSweep3::bt32BitAxisSweep3(), btAxisSweep3::btAxisSweep3(), btCollisionDispatcher::btCollisionDispatcher(), btCompoundCollisionAlgorithm::btCompoundCollisionAlgorithm(), btDefaultSerializer::btDefaultSerializer(), btTransformAabb(), btSimulationIslandManager::buildIslands(), btMinkowskiSumShape::calculateLocalInertia(), btSoftBodyCollisionShape::calculateLocalInertia(), btEmptyShape::calculateLocalInertia(), btTriangleMeshShape::calculateLocalInertia(), btMultiSapBroadphase::calculateOverlappingPairs(), btAxisSweep3Internal< BP_FP_INT_TYPE >::calculateOverlappingPairs(), btSimpleBroadphase::calculateOverlappingPairs(), btCompoundCollisionAlgorithm::calculateTimeOfImpact(), btGImpactMeshShape::childrenHasTransform(), btSoftBodyTriangleCallback::clearCache(), btDbvt::collideKDOP(), btDbvt::collideOCL(), convexHullSupport(), btSimpleBroadphase::createProxy(), cullPoints2(), btStackAlloc::destroy(), btMultiSapBroadphase::destroyProxy(), EdgeSeparation(), btGeneric6DofSpringConstraint::enableSpring(), btStackAlloc::endBlock(), btDefaultSerializer::finalizeChunk(), FindIncidentEdge(), btHashedOverlappingPairCache::findPair(), btSimpleBroadphase::freeHandle(), btAxisSweep3Internal< BP_FP_INT_TYPE >::freeHandle(), btPoolAllocator::freeMemory(), btSoftBody::generateBendingConstraints(), btGImpactCompoundShape::CompoundPrimitiveManager::get_primitive_triangle(), btTypedConstraint::getAppliedImpulse(), btHashMap< btHashPtr, btPointerUid >::getAtIndex(), btGImpactMeshShape::getBulletTetrahedron(), btGImpactCompoundShape::getBulletTetrahedron(), btGImpactMeshShapePart::getBulletTetrahedron(), btGImpactCompoundShape::getBulletTriangle(), btGImpactMeshShape::getBulletTriangle(), btConvexInternalAabbCachingShape::getCachedLocalAabb(), btPolyhedralConvexAabbCachingShape::getCachedLocalAabb(), btGImpactMeshShape::getChildAabb(), btGImpactMeshShape::getChildShape(), btGImpactMeshShapePart::getChildShape(), btGImpactMeshShape::getChildTransform(), btGImpactMeshShapePart::getChildTransform(), btGImpactCompoundShape::getChildTransform(), btGjkPairDetector::getClosestPointsNonVirtual(), btBox2dShape::getEdge(), btBoxShape::getEdge(), btConvexTriangleMeshShape::getEdge(), btGeneric6DofConstraint::getInfo2(), btConeTwistConstraint::getInfo2NonVirtual(), btSliderConstraint::getInfo2NonVirtual(), btGeneric6DofConstraint::getInfo2NonVirtual(), btConvexInternalAabbCachingShape::getNonvirtualAabb(), btPolyhedralConvexAabbCachingShape::getNonvirtualAabb(), btGImpactMeshShape::getNumChildShapes(), btConvexTriangleMeshShape::getPlane(), btBox2dShape::getPlaneEquation(), btBoxShape::getPlaneEquation(), btConvexInternalShape::getPreferredPenetrationDirection(), btBoxShape::getPreferredPenetrationDirection(), btBox2dShape::getPreferredPenetrationDirection(), btGImpactMeshShape::getPrimitiveManager(), btHeightfieldTerrainShape::getRawHeightFieldValue(), btConvexTriangleMeshShape::getVertex(), btHeightfieldTerrainShape::getVertex(), btRaycastVehicle::getWheelInfo(), btRaycastVehicle::getWheelTransformWS(), btSymMatrix< T >::index(), btHeightfieldTerrainShape::initialize(), btDefaultSerializer::internalAlloc(), btStridingMeshInterface::InternalProcessAllTriangles(), btSoftRigidDynamicsWorld::internalSingleStepSimulation(), btConvexTriangleMeshShape::isInside(), btConvexInternalShape::localGetSupportingVertex(), btTriangleMeshShape::localGetSupportingVertexWithoutMargin(), btGImpactMeshShape::lockChildShapes(), maxdirfiltered(), maxdirsterid(), btCollisionDispatcher::needsCollision(), btGImpactMeshShape::needsRetrieveTetrahedrons(), btGImpactMeshShape::needsRetrieveTriangles(), btHullTriangle::neib(), btQuaternion::operator/(), btQuaternion::operator/=(), btGeneric6DofConstraint::operator=(), btDbvtBroadphase::performDeferredRemoval(), plAddChildShape(), plAddRigidBody(), plAddVertex(), plCreateRigidBody(), plDeleteRigidBody(), plDeleteShape(), plGetOpenGLMatrix(), plGetOrientation(), plGetPosition(), plRemoveRigidBody(), plSetOpenGLMatrix(), plSetOrientation(), plSetPosition(), plSetScaling(), plStepSimulation(), btSoftBodyCollisionShape::processAllTriangles(), btHeightfieldTerrainShape::processAllTriangles(), btCompoundLeafCallback::ProcessChildShape(), btConvexConvexAlgorithm::processCollision(), btCompoundCollisionAlgorithm::processCollision(), RemovingOverlapCallback::processOverlap(), btSoftBodyTriangleCallback::processTriangle(), btRaycastVehicle::rayCast(), btDbvt::rayTest(), btManifoldResult::refreshContactPoints(), btCollisionDispatcher::releaseManifold(), btHashMap< btHashPtr, btPointerUid >::remove(), btPairCachingGhostObject::removeOverlappingObjectInternal(), btHashedOverlappingPairCache::removeOverlappingPair(), btGhostPairCallback::removeOverlappingPairsContainingProxy(), btVoronoiSimplexSolver::removeVertex(), btSolve2LinearConstraint::resolveBilateralPairConstraint(), btSolve2LinearConstraint::resolveUnilateralPairConstraint(), btSoftBody::serialize(), btStridingMeshInterface::serialize(), btRaycastVehicle::setBrake(), btGImpactCompoundShape::setChildTransform(), btGImpactMeshShapePart::setChildTransform(), btGImpactMeshShape::setChildTransform(), btConeShape::setConeUpIndex(), btGeneric6DofSpringConstraint::setDamping(), btGeneric6DofSpringConstraint::setEquilibriumPoint(), btQuaternion::setRotation(), btRaycastVehicle::setSteeringValue(), btGeneric6DofSpringConstraint::setStiffness(), btConeTwistConstraint::solveConstraintObsolete(), btDiscreteDynamicsWorld::solveConstraints(), btSequentialImpulseConstraintSolver::solveGroup(), btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinish(), btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(), sort(), btDiscreteDynamicsWorld::synchronizeSingleMotionState(), ThreePlaneIntersection(), btGImpactMeshShape::unlockChildShapes(), btSimpleBroadphase::validate(), and btRigidBody::~btRigidBody().
#define btFsels | ( | a, | |
b, | |||
c | |||
) | (btScalar)btFsel(a,b,c) |
Definition at line 353 of file btScalar.h.
Referenced by btBoxShape::batchedUnitVectorGetSupportingVertexWithoutMargin(), btBox2dShape::batchedUnitVectorGetSupportingVertexWithoutMargin(), btBox2dShape::localGetSupportingVertex(), btBoxShape::localGetSupportingVertex(), btBoxShape::localGetSupportingVertexWithoutMargin(), and btBox2dShape::localGetSupportingVertexWithoutMargin().
#define btFullAssert | ( | x | ) |
Definition at line 193 of file btScalar.h.
Referenced by ATTRIBUTE_ALIGNED16(), btMatrix3x3::getRow(), btMatrix3x3::inverse(), operator/(), btMatrix3x3::operator[](), and btMatrix3x3::setRotation().
#define btLikely | ( | _c | ) | _c |
Definition at line 194 of file btScalar.h.
Definition at line 301 of file btScalar.h.
Referenced by btPlaneSpace1(), and capsuleCapsuleDistance().
#define btUnlikely | ( | _c | ) | _c |
Definition at line 195 of file btScalar.h.
#define SIMD_2_PI btScalar(6.283185307179586232) |
Definition at line 294 of file btScalar.h.
Referenced by btAdjustAngleToLimits(), btAdjustInternalEdgeContacts(), btNormalizeAngle(), btTriangleInfo::btTriangleInfo(), btDiscreteDynamicsWorld::debugDrawConstraint(), btIDebugDraw::drawCone(), btIDebugDraw::drawCylinder(), btConvexConvexAlgorithm::processCollision(), and btConvexPlaneCollisionAlgorithm::processCollision().
#define SIMD_DEGS_PER_RAD (btScalar(360.0) / SIMD_2_PI) |
Definition at line 298 of file btScalar.h.
Referenced by btDegrees().
#define SIMD_EPSILON FLT_EPSILON |
Definition at line 308 of file btScalar.h.
Referenced by btConeTwistConstraint::adjustSwingAxisToUseEllipseNormal(), CcdPhysicsController::ApplyForce(), btSoftBody::applyForces(), CcdPhysicsController::applyImpulse(), CcdPhysicsController::ApplyTorque(), ATTRIBUTE_ALIGNED16(), bt_plane_clip_polygon(), bt_plane_clip_polygon_collect(), bt_plane_clip_triangle(), bt_segment_collision(), btFuzzyZero(), btConeTwistConstraint::buildJacobian(), btConeTwistConstraint::calcAngleInfo2(), btContinuousConvexCollision::calcTimeOfImpact(), btSubsimplexConvexCast::calcTimeOfImpact(), btTransformUtil::calculateDiffAxisAngle(), btTransformUtil::calculateDiffAxisAngleQuaternion(), btGeneric6DofConstraint::calculateTransforms(), capsuleCapsuleDistance(), SphereTriangleDetector::collide(), btConeTwistConstraint::computeConeLimitInfo(), btConeTwistConstraint::computeTwistLimitInfo(), btSequentialImpulseConstraintSolver::convertContact(), cullPoints2(), btMatrix3x3::diagonalize(), CProfileManager::dumpRecursive(), btSoftBody::generateClusters(), btQuaternion::getAxis(), btGjkPairDetector::getClosestPointsNonVirtual(), btSliderConstraint::getInfo2NonVirtual(), getNormalizedVector(), btConeTwistConstraint::GetPointForAngle(), btSphereBoxCollisionAlgorithm::getSphereDistance(), btCylinderShape::localGetSupportingVertex(), btConvexInternalShape::localGetSupportingVertex(), btConvexTriangleMeshShape::localGetSupportingVertex(), btConeShape::localGetSupportingVertex(), btMultiSphereShape::localGetSupportingVertexWithoutMargin(), GIM_TRIANGLE_CONTACT::merge_points(), NormalizeAny(), btConvexConvexAlgorithm::processCollision(), btSphereBoxCollisionAlgorithm::processCollision(), btSphereSphereCollisionAlgorithm::processCollision(), CcdPhysicsEnvironment::processFhSprings(), ProjectOrigin(), btSoftBody::PSolve_Links(), btSoftBody::PSolve_RContacts(), btSoftBody::RayFromToCaster::rayFromToTriangle(), CcdPhysicsEnvironment::rayTest(), btSolve2LinearConstraint::resolveBilateralPairConstraint(), btSolve2LinearConstraint::resolveUnilateralPairConstraint(), CcdPhysicsController::SetAngularVelocity(), btConeTwistConstraint::setMotorTargetInConstraintSpace(), shortestArcQuat(), btGjkEpaSolver2::SignedDistance(), btRotationalLimitMotor::solveAngularLimits(), btConeTwistConstraint::solveConstraintObsolete(), btKinematicCharacterController::stepForwardAndStrafe(), btSoftBody::updateClusters(), btSoftBody::updateNormals(), btSoftBody::updatePose(), and btKinematicCharacterController::updateTargetPositionBasedOnCollision().
#define SIMD_FORCE_INLINE inline |
Definition at line 174 of file btScalar.h.
Referenced by ATTRIBUTE_ALIGNED128(), ATTRIBUTE_ALIGNED16(), and ATTRIBUTE_ALIGNED64().
#define SIMD_HALF_PI (SIMD_2_PI * btScalar(0.25)) |
Definition at line 296 of file btScalar.h.
Referenced by btHinge2Constraint::btHinge2Constraint(), btUniversalConstraint::btUniversalConstraint(), btIDebugDraw::drawSpherePatch(), btMatrix3x3::getEulerYPR(), and matrixToEulerXYZ().
#define SIMD_INFINITY FLT_MAX |
Definition at line 309 of file btScalar.h.
Referenced by bottomup(), btGeneric6DofConstraint::get_limit_motor_info2(), btConeTwistConstraint::getInfo2NonVirtual(), btSliderConstraint::getInfo2NonVirtual(), btSliderConstraint::getParam(), btSoftColliders::CollideVF_SS::Process(), and btGjkEpaSolver2::SignedDistance().
#define SIMD_PI (SIMD_2_PI * btScalar(0.5)) |
Definition at line 295 of file btScalar.h.
Referenced by btAtan2Fast(), btHinge2Constraint::btHinge2Constraint(), btNormalizeAngle(), btUniversalConstraint::btUniversalConstraint(), btConeTwistConstraint::computeTwistLimitInfo(), btSoftBodyHelpers::CreateEllipsoid(), btDiscreteDynamicsWorld::debugDrawConstraint(), btIDebugDraw::drawSpherePatch(), btMatrix3x3::getEulerYPR(), btMatrix3x3::getEulerZYX(), btSoftBody::AJoint::Prepare(), btConvexConvexAlgorithm::processCollision(), btConvexPlaneCollisionAlgorithm::processCollision(), and btConnectivityProcessor::processTriangle().
#define SIMD_RADS_PER_DEG (SIMD_2_PI / btScalar(360.0)) |
Definition at line 297 of file btScalar.h.
Referenced by btRadians(), btIDebugDraw::drawArc(), btIDebugDraw::drawSpherePatch(), and maxdirsterid().
#define SIMDSQRT12 btScalar(0.7071067811865475244008443621048490) |
Definition at line 299 of file btScalar.h.
Referenced by btPlaneSpace1().
typedef float btScalar |
The btScalar type abstracts floating point numbers, to easily switch between double and single floating point precision.
Definition at line 210 of file btScalar.h.
Definition at line 271 of file btScalar.h.
References acosf.
Referenced by btQuaternion::angle(), ATTRIBUTE_ALIGNED16(), btQuaternion::getAngle(), and btSoftBody::AJoint::Prepare().
Definition at line 278 of file btScalar.h.
References asinf.
Referenced by btMatrix3x3::getEulerYPR(), btMatrix3x3::getEulerZYX(), and matrixToEulerXYZ().
Definition at line 285 of file btScalar.h.
References atanf.
Definition at line 286 of file btScalar.h.
References atan2f.
Referenced by btGetAngle(), btConeTwistConstraint::calcAngleInfo2(), cullPoints2(), btMatrix3x3::getEulerYPR(), btMatrix3x3::getEulerZYX(), matrixToEulerXYZ(), and btSliderConstraint::testAngLimits().
Definition at line 312 of file btScalar.h.
References angle(), btFabs(), and SIMD_PI.
Referenced by btConeTwistConstraint::calcAngleInfo().
Definition at line 268 of file btScalar.h.
References cosf.
Referenced by btConeTwistConstraint::calcAngleInfo2(), btSoftBodyHelpers::CreateEllipsoid(), btDiscreteDynamicsWorld::debugDrawConstraint(), btIDebugDraw::drawArc(), btIDebugDraw::drawSpherePatch(), btMatrix3x3::getEulerZYX(), btConeTwistConstraint::GetPointForAngle(), btTransformUtil::integrateTransform(), maxdirsterid(), btQuaternion::setEuler(), btQuaternion::setEulerZYX(), btMatrix3x3::setEulerZYX(), btKinematicCharacterController::setMaxSlope(), and btQuaternion::setRotation().
Definition at line 343 of file btScalar.h.
References SIMD_DEGS_PER_RAD.
Definition at line 330 of file btScalar.h.
Referenced by btAngularLimit::fit().
Definition at line 287 of file btScalar.h.
References expf.
Definition at line 267 of file btScalar.h.
References fabsf.
Referenced by btMatrix3x3::absolute(), btVector4::absolute4(), btSoftBody::applyForces(), ATTRIBUTE_ALIGNED16(), bt_line_plane_collision(), btAdjustAngleToLimits(), btAtan2Fast(), btFuzzyZero(), btPlaneSpace1(), btConeTwistConstraint::calcAngleInfo(), btConvexTriangleMeshShape::calculatePrincipalAxisTransform(), ClusterMetric(), GIM_AABB::collide_ray(), cullPoints2(), dBoxBox2(), btMatrix3x3::diagonalize(), btSoftColliders::CollideSDF_RS::DoNode(), OcclusionBuffer::draw(), gjkepa2_impl::GJK::EncloseOrigin(), GIM_TRIANGLE::get_uv_parameters(), btMatrix3x3::getEulerYPR(), btMatrix3x3::getEulerZYX(), btSliderConstraint::getInfo2NonVirtual(), btGeometryUtil::getVerticesFromPlaneEquations(), ImplicitSolve(), btGeneric6DofSpringConstraint::internalUpdateSprings(), LINE_PLANE_COLLISION(), gim_contact_array::merge_contacts(), btContactArray::merge_contacts(), btKinematicCharacterController::playerStep(), gjkepa2_impl::GJK::projectorigin(), Proximity(), btSoftBody::refine(), btSolve2LinearConstraint::resolveBilateralPairConstraint(), resolveSingleBilateral(), btSolve2LinearConstraint::resolveUnilateralPairConstraint(), btSoftBody::setVolumeDensity(), btSoftBody::setVolumeMass(), btEigen::system(), ThreePlaneIntersection(), topdown(), btSoftBody::updateClusters(), and btSoftBody::updateConstants().
Definition at line 348 of file btScalar.h.
Referenced by btSelect().
SIMD_FORCE_INLINE bool btFuzzyZero | ( | btScalar | x | ) |
Definition at line 328 of file btScalar.h.
References btFabs(), and SIMD_EPSILON.
Referenced by btConeTwistConstraint::calcAngleInfo2(), PolarDecompose(), btSoftBody::RayFromToCaster::rayFromToTriangle(), CcdPhysicsController::setScaling(), btDiscreteDynamicsWorld::stepSimulation(), and CcdPhysicsController::SynchronizeMotionStates().
int btGetVersion | ( | ) | [inline] |
Definition at line 35 of file btScalar.h.
References BT_BULLET_VERSION.
Definition at line 333 of file btScalar.h.
SIMD_FORCE_INLINE int btIsNegative | ( | btScalar | x | ) |
Definition at line 338 of file btScalar.h.
Definition at line 288 of file btScalar.h.
References logf.
SIMD_FORCE_INLINE bool btMachineIsLittleEndian | ( | ) |
Definition at line 356 of file btScalar.h.
Definition at line 494 of file btScalar.h.
References btFmod(), SIMD_2_PI, and SIMD_PI.
Referenced by ATTRIBUTE_ALIGNED16(), btAdjustAngleToLimits(), btAngularLimit::fit(), btAngularLimit::getHigh(), btAngularLimit::getLow(), btAngularLimit::set(), btGeneric6DofConstraint::setAngularLowerLimit(), btGeneric6DofConstraint::setAngularUpperLimit(), btGeneric6DofConstraint::setLimit(), btSliderConstraint::setLowerAngLimit(), btSliderConstraint::setUpperAngLimit(), and btAngularLimit::test().
Definition at line 289 of file btScalar.h.
References powf.
Referenced by btRigidBody::applyDamping(), and btQuaternion::getAxis().
Definition at line 342 of file btScalar.h.
References SIMD_RADS_PER_DEG.
Referenced by btKinematicCharacterController::btKinematicCharacterController().
SIMD_FORCE_INLINE int btSelect | ( | unsigned | condition, |
int | valueIfConditionNonZero, | ||
int | valueIfConditionZero | ||
) |
Definition at line 380 of file btScalar.h.
SIMD_FORCE_INLINE float btSelect | ( | unsigned | condition, |
float | valueIfConditionNonZero, | ||
float | valueIfConditionZero | ||
) |
Definition at line 386 of file btScalar.h.
References btFsel().
SIMD_FORCE_INLINE unsigned btSelect | ( | unsigned | condition, |
unsigned | valueIfConditionNonZero, | ||
unsigned | valueIfConditionZero | ||
) |
btSelect avoids branches, which makes performance much better for consoles like Playstation 3 and XBox 360 Thanks Phil Knight. See also http://www.cellperformance.com/articles/2006/04/more_techniques_for_eliminatin_1.html
Definition at line 370 of file btScalar.h.
Referenced by testQuantizedAabbAgainstQuantizedAabb().
Definition at line 269 of file btScalar.h.
References sinf.
Referenced by btConeTwistConstraint::calcAngleInfo2(), btSoftBodyHelpers::CreateEllipsoid(), btDiscreteDynamicsWorld::debugDrawConstraint(), btIDebugDraw::drawArc(), btIDebugDraw::drawSpherePatch(), btConeTwistConstraint::GetPointForAngle(), btTransformUtil::integrateTransform(), maxdirsterid(), btQuaternion::setEuler(), btQuaternion::setEulerZYX(), btMatrix3x3::setEulerZYX(), btQuaternion::setRotation(), and btQuaternion::slerp().
Definition at line 247 of file btScalar.h.
References sqrtf.
Referenced by btQuaternion::angle(), ATTRIBUTE_ALIGNED16(), btConeShape::btConeShape(), btTransformUtil::calculateDiffAxisAngle(), btTransformUtil::calculateDiffAxisAngleQuaternion(), Clamp(), SphereTriangleDetector::collide(), btSequentialImpulseConstraintSolver::convertContact(), btSoftBodyHelpers::CreateEllipsoid(), CylinderLocalSupportX(), CylinderLocalSupportY(), CylinderLocalSupportZ(), btMatrix3x3::diagonalize(), btQuaternion::getAxis(), btGjkPairDetector::getClosestPointsNonVirtual(), btSliderConstraint::getInfo2NonVirtual(), btMatrix3x3::getRotation(), btSphereBoxCollisionAlgorithm::getSphereDistance(), GIM_CONTACT::interpolate_normals(), btQuaternion::length(), btConvexTriangleMeshShape::localGetSupportingVertexWithoutMargin(), btMultiSphereShape::localGetSupportingVertexWithoutMargin(), btPolyhedralConvexShape::localGetSupportingVertexWithoutMargin(), btCapsuleShape::localGetSupportingVertexWithoutMargin(), btSoftColliders::CollideVF_SS::Process(), gjkepa2_impl::GJK::projectorigin(), ProjectOrigin(), btConeShape::setLocalScaling(), shortestArcQuat(), btEigen::system(), and btRaycastVehicle::updateFriction().
SIMD_FORCE_INLINE void btSwap | ( | T & | a, |
T & | b | ||
) |
Definition at line 395 of file btScalar.h.
References T.
Referenced by btDbvtBroadphase::collide(), gjkepa2_impl::EPA::Evaluate(), btHashedOverlappingPairCache::findPair(), btSoftBody::generateClusters(), ImplicitSolve(), btSymMatrix< T >::index(), btDbvtTreeCollider::Process(), btSoftBody::randomizeConstraints(), btSoftBody::refine(), btHashedOverlappingPairCache::removeOverlappingPair(), and sort().
SIMD_FORCE_INLINE unsigned short btSwapEndian | ( | unsigned short | val | ) |
Definition at line 409 of file btScalar.h.
SIMD_FORCE_INLINE unsigned btSwapEndian | ( | int | val | ) |
Definition at line 414 of file btScalar.h.
References btSwapEndian().
SIMD_FORCE_INLINE unsigned short btSwapEndian | ( | short | val | ) |
Definition at line 419 of file btScalar.h.
References btSwapEndian().
SIMD_FORCE_INLINE unsigned btSwapEndian | ( | unsigned | val | ) |
Definition at line 404 of file btScalar.h.
Referenced by btSwapEndian(), and btDefaultSerializer::initDNA().
SIMD_FORCE_INLINE void btSwapEndianDouble | ( | double | d, |
unsigned char * | dst | ||
) |
Definition at line 460 of file btScalar.h.
SIMD_FORCE_INLINE unsigned int btSwapEndianFloat | ( | float | d | ) |
btSwapFloat uses using char pointers to swap the endianness
btSwapFloat/btSwapDouble will NOT return a float, because the machine might 'correct' invalid floating point values Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. so instead of returning a float/double, we return integer/long long integer
Definition at line 430 of file btScalar.h.
Definition at line 270 of file btScalar.h.
References tanf.
SIMD_FORCE_INLINE double btUnswapEndianDouble | ( | const unsigned char * | src | ) |
Definition at line 476 of file btScalar.h.
References simple_enum_gen::d.
SIMD_FORCE_INLINE float btUnswapEndianFloat | ( | unsigned int | a | ) |
Definition at line 444 of file btScalar.h.
References simple_enum_gen::d.