mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-18 21:10:05 +00:00
Merge pull request #2162 from erwincoumans/cl_237962826
Qualify calls to certain functions from the cmath library.
This commit is contained in:
commit
ced17be7f3
@ -41,36 +41,36 @@ struct btBlockSolverInternalData
|
||||
|
||||
btBlockSolver::btBlockSolver()
|
||||
{
|
||||
m_data = new btBlockSolverInternalData;
|
||||
m_data2 = new btBlockSolverInternalData;
|
||||
}
|
||||
|
||||
btBlockSolver::~btBlockSolver()
|
||||
{
|
||||
delete m_data;
|
||||
delete m_data2;
|
||||
}
|
||||
|
||||
|
||||
btScalar btBlockSolver::solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher)
|
||||
{
|
||||
|
||||
btSISolverSingleIterationData siData(m_data->m_tmpSolverBodyPool,
|
||||
m_data->m_tmpSolverContactConstraintPool,
|
||||
m_data->m_tmpSolverNonContactConstraintPool,
|
||||
m_data->m_tmpSolverContactFrictionConstraintPool,
|
||||
m_data->m_tmpSolverContactRollingFrictionConstraintPool,
|
||||
m_data->m_orderTmpConstraintPool,
|
||||
m_data->m_orderNonContactConstraintPool,
|
||||
m_data->m_orderFrictionConstraintPool,
|
||||
m_data->m_tmpConstraintSizesPool,
|
||||
m_data->m_resolveSingleConstraintRowGeneric,
|
||||
m_data->m_resolveSingleConstraintRowLowerLimit,
|
||||
m_data->m_resolveSplitPenetrationImpulse,
|
||||
m_data->m_kinematicBodyUniqueIdToSolverBodyTable,
|
||||
m_data->m_btSeed2,
|
||||
m_data->m_fixedBodyId,
|
||||
m_data->m_maxOverrideNumSolverIterations);
|
||||
btSISolverSingleIterationData siData(m_data2->m_tmpSolverBodyPool,
|
||||
m_data2->m_tmpSolverContactConstraintPool,
|
||||
m_data2->m_tmpSolverNonContactConstraintPool,
|
||||
m_data2->m_tmpSolverContactFrictionConstraintPool,
|
||||
m_data2->m_tmpSolverContactRollingFrictionConstraintPool,
|
||||
m_data2->m_orderTmpConstraintPool,
|
||||
m_data2->m_orderNonContactConstraintPool,
|
||||
m_data2->m_orderFrictionConstraintPool,
|
||||
m_data2->m_tmpConstraintSizesPool,
|
||||
m_data2->m_resolveSingleConstraintRowGeneric,
|
||||
m_data2->m_resolveSingleConstraintRowLowerLimit,
|
||||
m_data2->m_resolveSplitPenetrationImpulse,
|
||||
m_data2->m_kinematicBodyUniqueIdToSolverBodyTable,
|
||||
m_data2->m_btSeed2,
|
||||
m_data2->m_fixedBodyId,
|
||||
m_data2->m_maxOverrideNumSolverIterations);
|
||||
|
||||
m_data->m_fixedBodyId = -1;
|
||||
m_data2->m_fixedBodyId = -1;
|
||||
//todo: setup sse2/4 constraint row methods
|
||||
|
||||
btSequentialImpulseConstraintSolver::convertBodiesInternal(siData, bodies, numBodies, info);
|
||||
@ -154,7 +154,7 @@ void btBlockSolver::solveMultiBodyGroup(btCollisionObject * *bodies, int numBodi
|
||||
|
||||
void btBlockSolver::reset()
|
||||
{
|
||||
//or just set m_data->m_btSeed2=0?
|
||||
delete m_data;
|
||||
m_data = new btBlockSolverInternalData;
|
||||
}
|
||||
//or just set m_data2->m_btSeed2=0?
|
||||
delete m_data2;
|
||||
m_data2 = new btBlockSolverInternalData;
|
||||
}
|
||||
|
@ -5,7 +5,7 @@
|
||||
|
||||
class btBlockSolver : public btMultiBodyConstraintSolver
|
||||
{
|
||||
struct btBlockSolverInternalData* m_data;
|
||||
struct btBlockSolverInternalData* m_data2;
|
||||
|
||||
public:
|
||||
btBlockSolver();
|
||||
@ -26,4 +26,4 @@ public:
|
||||
}
|
||||
};
|
||||
|
||||
#endif //BT_BLOCK_SOLVER_H
|
||||
#endif //BT_BLOCK_SOLVER_H
|
||||
|
@ -18,6 +18,8 @@ subject to the following restrictions:
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
#include "MotorDemo.h"
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
class btBroadphaseInterface;
|
||||
class btCollisionShape;
|
||||
@ -158,8 +160,8 @@ public:
|
||||
for (i = 0; i < NUM_LEGS; i++)
|
||||
{
|
||||
float fAngle = 2 * M_PI * i / NUM_LEGS;
|
||||
float fSin = sin(fAngle);
|
||||
float fCos = cos(fAngle);
|
||||
float fSin = std::sin(fAngle);
|
||||
float fCos = std::cos(fAngle);
|
||||
|
||||
transform.setIdentity();
|
||||
btVector3 vBoneOrigin = btVector3(btScalar(fCos * (fBodySize + 0.5 * fLegLength)), btScalar(fHeight), btScalar(fSin * (fBodySize + 0.5 * fLegLength)));
|
||||
@ -197,8 +199,8 @@ public:
|
||||
for (i = 0; i < NUM_LEGS; i++)
|
||||
{
|
||||
float fAngle = 2 * M_PI * i / NUM_LEGS;
|
||||
float fSin = sin(fAngle);
|
||||
float fCos = cos(fAngle);
|
||||
float fSin = std::sin(fAngle);
|
||||
float fCos = std::cos(fAngle);
|
||||
|
||||
// hip joints
|
||||
localA.setIdentity();
|
||||
|
@ -15,6 +15,8 @@ subject to the following restrictions:
|
||||
|
||||
#include "NN3DWalkers.h"
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
@ -282,8 +284,8 @@ public:
|
||||
for (i = 0; i < NUM_LEGS; i++)
|
||||
{
|
||||
float footAngle = 2 * SIMD_PI * i / NUM_LEGS; // legs are uniformly distributed around the root body
|
||||
float footYUnitPosition = sin(footAngle); // y position of the leg on the unit circle
|
||||
float footXUnitPosition = cos(footAngle); // x position of the leg on the unit circle
|
||||
float footYUnitPosition = std::sin(footAngle); // y position of the leg on the unit circle
|
||||
float footXUnitPosition = std::cos(footAngle); // x position of the leg on the unit circle
|
||||
|
||||
transform.setIdentity();
|
||||
btVector3 legCOM = btVector3(btScalar(footXUnitPosition * (gRootBodyRadius + 0.5 * gLegLength)), btScalar(rootAboveGroundHeight), btScalar(footYUnitPosition * (gRootBodyRadius + 0.5 * gLegLength)));
|
||||
@ -1017,7 +1019,7 @@ void NN3DWalkersExample::updateEvaluations(const btScalar timeSinceLastTick)
|
||||
}
|
||||
|
||||
// apply the activation function
|
||||
targetAngle = (tanh(targetAngle) + 1.0f) * 0.5f;
|
||||
targetAngle = (std::tanh(targetAngle) + 1.0f) * 0.5f;
|
||||
}
|
||||
btScalar targetLimitAngle = hingeC->getLowerLimit() + targetAngle * (hingeC->getUpperLimit() - hingeC->getLowerLimit());
|
||||
btScalar currentAngle = hingeC->getHingeAngle();
|
||||
|
@ -48,6 +48,8 @@ subject to the following restrictions:
|
||||
|
||||
#include <stdio.h> //printf debugging
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#if defined(BT_USE_DOUBLE_PRECISION)
|
||||
#define btglLoadMatrix glLoadMatrixd
|
||||
#define btglMultMatrix glMultMatrixd
|
||||
@ -149,19 +151,19 @@ void GL_ShapeDrawer::drawSphere(btScalar radius, int lats, int longs)
|
||||
for (i = 0; i <= lats; i++)
|
||||
{
|
||||
btScalar lat0 = SIMD_PI * (-btScalar(0.5) + (btScalar)(i - 1) / lats);
|
||||
btScalar z0 = radius * sin(lat0);
|
||||
btScalar zr0 = radius * cos(lat0);
|
||||
btScalar z0 = radius * std::sin(lat0);
|
||||
btScalar zr0 = radius * std::cos(lat0);
|
||||
|
||||
btScalar lat1 = SIMD_PI * (-btScalar(0.5) + (btScalar)i / lats);
|
||||
btScalar z1 = radius * sin(lat1);
|
||||
btScalar zr1 = radius * cos(lat1);
|
||||
btScalar z1 = radius * std::sin(lat1);
|
||||
btScalar zr1 = radius * std::cos(lat1);
|
||||
|
||||
glBegin(GL_QUAD_STRIP);
|
||||
for (j = 0; j <= longs; j++)
|
||||
{
|
||||
btScalar lng = 2 * SIMD_PI * (btScalar)(j - 1) / longs;
|
||||
btScalar x = cos(lng);
|
||||
btScalar y = sin(lng);
|
||||
btScalar x = std::cos(lng);
|
||||
btScalar y = std::sin(lng);
|
||||
glNormal3f(x * zr1, y * zr1, z1);
|
||||
glVertex3f(x * zr1, y * zr1, z1);
|
||||
glNormal3f(x * zr0, y * zr0, z0);
|
||||
@ -906,4 +908,4 @@ void GL_ShapeDrawer::drawScene(const btDiscreteDynamicsWorld* dynamicsWorld, boo
|
||||
glDisable(GL_CULL_FACE);
|
||||
drawSceneInternal(dynamicsWorld, 0, cameraUpAxis);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -15,8 +15,9 @@
|
||||
|
||||
#include "MultiPendulum.h"
|
||||
|
||||
#include <vector> // TODO: Should I use another data structure?
|
||||
#include <cmath>
|
||||
#include <iterator>
|
||||
#include <vector> // TODO: Should I use another data structure?
|
||||
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/btVector3.h"
|
||||
@ -159,7 +160,7 @@ void MultiPendulumExample::initPhysics()
|
||||
m_collisionShapes.push_back(pendulumShape);
|
||||
|
||||
// create multi-pendulum
|
||||
createMultiPendulum(pendulumShape, floor(gPendulaQty), position,
|
||||
createMultiPendulum(pendulumShape, std::floor(gPendulaQty), position,
|
||||
gInitialPendulumLength, pendulumMass);
|
||||
}
|
||||
|
||||
|
@ -15,8 +15,9 @@
|
||||
|
||||
#include "NewtonsCradle.h"
|
||||
|
||||
#include <vector> // TODO: Should I use another data structure?
|
||||
#include <cmath>
|
||||
#include <iterator>
|
||||
#include <vector> // TODO: Should I use another data structure?
|
||||
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/btVector3.h"
|
||||
@ -158,7 +159,7 @@ void NewtonsCradleExample::initPhysics()
|
||||
btSphereShape* pendulumShape = new btSphereShape(gSphereRadius);
|
||||
m_collisionShapes.push_back(pendulumShape);
|
||||
|
||||
for (int i = 0; i < floor(gPendulaQty); i++)
|
||||
for (int i = 0; i < std::floor(gPendulaQty); i++)
|
||||
{
|
||||
// create pendulum
|
||||
createPendulum(pendulumShape, position, gInitialPendulumLength, pendulumMass);
|
||||
|
@ -15,8 +15,9 @@
|
||||
|
||||
#include "NewtonsRopeCradle.h"
|
||||
|
||||
#include <vector> // TODO: Should I use another data structure?
|
||||
#include <cmath>
|
||||
#include <iterator>
|
||||
#include <vector> // TODO: Should I use another data structure?
|
||||
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/btVector3.h"
|
||||
@ -204,7 +205,7 @@ void NewtonsRopeCradleExample::initPhysics()
|
||||
btSphereShape* pendulumShape = new btSphereShape(gSphereRadius);
|
||||
m_collisionShapes.push_back(pendulumShape);
|
||||
|
||||
for (int i = 0; i < floor(gPendulaQty); i++)
|
||||
for (int i = 0; i < std::floor(gPendulaQty); i++)
|
||||
{
|
||||
// create pendulum
|
||||
createRopePendulum(pendulumShape, position, orientation, gInitialPendulumWidth,
|
||||
|
@ -22,6 +22,7 @@ subject to the following restrictions:
|
||||
|
||||
#include <stdio.h> //printf debugging
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
|
||||
static btScalar gSliderStackRows = 1.0f;
|
||||
static btScalar gSliderStackColumns = 1.0f;
|
||||
@ -107,7 +108,7 @@ public:
|
||||
// update ground
|
||||
const float cyclesPerSecond = 1.0f;
|
||||
m_groundMovePhase += cyclesPerSecond * deltaTime;
|
||||
m_groundMovePhase -= floor(m_groundMovePhase); // keep phase between 0 and 1
|
||||
m_groundMovePhase -= std::floor(m_groundMovePhase); // keep phase between 0 and 1
|
||||
btTransform xf = m_groundStartXf;
|
||||
float gndHOffset = btSin(m_groundMovePhase * SIMD_2_PI) * gSliderGroundHorizontalAmplitude;
|
||||
float gndHVel = btCos(m_groundMovePhase * SIMD_2_PI) * gSliderGroundHorizontalAmplitude * cyclesPerSecond * SIMD_2_PI; // d(gndHOffset)/dt
|
||||
|
@ -21,6 +21,8 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#include <cmath>
|
||||
#include "LinearR3.h"
|
||||
|
||||
#if 0
|
||||
@ -121,7 +123,7 @@ float unit(float vin[3], float vout[3])
|
||||
|
||||
if (dist > 0.0)
|
||||
{
|
||||
dist = sqrt(dist);
|
||||
dist = std::sqrt(dist);
|
||||
f = 1. / dist;
|
||||
vout[0] = f * vin[0];
|
||||
vout[1] = f * vin[1];
|
||||
|
@ -11,6 +11,8 @@
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#include <cmath>
|
||||
|
||||
namespace Gwen
|
||||
{
|
||||
namespace Renderer
|
||||
@ -87,16 +89,16 @@ void Base::Translate(int& x, int& y)
|
||||
x += m_RenderOffset.x;
|
||||
y += m_RenderOffset.y;
|
||||
|
||||
x = ceil(((float)x) * m_fScale);
|
||||
y = ceil(((float)y) * m_fScale);
|
||||
x = std::ceil(((float)x) * m_fScale);
|
||||
y = std::ceil(((float)y) * m_fScale);
|
||||
}
|
||||
|
||||
void Base::Translate(Gwen::Rect& rect)
|
||||
{
|
||||
Translate(rect.x, rect.y);
|
||||
|
||||
rect.w = ceil(((float)rect.w) * m_fScale);
|
||||
rect.h = ceil(((float)rect.h) * m_fScale);
|
||||
rect.w = std::ceil(((float)rect.w) * m_fScale);
|
||||
rect.h = std::ceil(((float)rect.h) * m_fScale);
|
||||
}
|
||||
|
||||
void Gwen::Renderer::Base::SetClipRegion(Gwen::Rect rect)
|
||||
@ -214,4 +216,4 @@ Gwen::Point Base::MeasureText(Gwen::Font* pFont, const Gwen::UnicodeString& text
|
||||
return p;
|
||||
}
|
||||
} // namespace Renderer
|
||||
} // namespace Gwen
|
||||
} // namespace Gwen
|
||||
|
@ -5,6 +5,7 @@
|
||||
*/
|
||||
|
||||
#include <math.h>
|
||||
#include <cmath>
|
||||
#include "Gwen/Controls/Slider.h"
|
||||
|
||||
using namespace Gwen;
|
||||
@ -68,7 +69,7 @@ void Slider::SetValueInternal(float val)
|
||||
{
|
||||
if (m_bClampToNotches)
|
||||
{
|
||||
val = floor((val * (float)m_iNumNotches) + 0.5f);
|
||||
val = std::floor((val * (float)m_iNumNotches) + 0.5f);
|
||||
val /= (float)m_iNumNotches;
|
||||
}
|
||||
|
||||
@ -98,4 +99,4 @@ void Slider::RenderFocus(Gwen::Skin::Base* skin)
|
||||
if (!IsTabable()) return;
|
||||
|
||||
skin->DrawKeyboardHighlight(this, GetRenderBounds(), 0);
|
||||
}
|
||||
}
|
||||
|
@ -22,6 +22,8 @@ subject to the following restrictions:
|
||||
|
||||
#include <string.h> //for memset
|
||||
|
||||
#include <cmath>
|
||||
|
||||
const int kNoMerge = -1;
|
||||
|
||||
bool btBatchedConstraints::s_debugDrawBatches = false;
|
||||
@ -520,7 +522,7 @@ static void writeGrainSizes(btBatchedConstraints* bc)
|
||||
{
|
||||
const Range& phase = bc->m_phases[iPhase];
|
||||
int numBatches = phase.end - phase.begin;
|
||||
float grainSize = floor((0.25f * numBatches / float(numThreads)) + 0.0f);
|
||||
float grainSize = std::floor((0.25f * numBatches / float(numThreads)) + 0.0f);
|
||||
bc->m_phaseGrainSize[iPhase] = btMax(1, int(grainSize));
|
||||
}
|
||||
}
|
||||
|
@ -19,6 +19,7 @@ Written by: Marcus Hennix
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
#include "LinearMath/btMinMax.h"
|
||||
#include <cmath>
|
||||
#include <new>
|
||||
|
||||
//#define CONETWIST_USE_OBSOLETE_SOLVER true
|
||||
@ -842,7 +843,7 @@ void btConeTwistConstraint::computeConeLimitInfo(const btQuaternion& qCone,
|
||||
btScalar norm = 1 / (m_swingSpan2 * m_swingSpan2);
|
||||
norm += surfaceSlope2 / (m_swingSpan1 * m_swingSpan1);
|
||||
btScalar swingLimit2 = (1 + surfaceSlope2) / norm;
|
||||
swingLimit = sqrt(swingLimit2);
|
||||
swingLimit = std::sqrt(swingLimit2);
|
||||
}
|
||||
|
||||
// test!
|
||||
@ -887,7 +888,7 @@ btVector3 btConeTwistConstraint::GetPointForAngle(btScalar fAngleInRadians, btSc
|
||||
btScalar norm = 1 / (m_swingSpan2 * m_swingSpan2);
|
||||
norm += surfaceSlope2 / (m_swingSpan1 * m_swingSpan1);
|
||||
btScalar swingLimit2 = (1 + surfaceSlope2) / norm;
|
||||
swingLimit = sqrt(swingLimit2);
|
||||
swingLimit = std::sqrt(swingLimit2);
|
||||
}
|
||||
|
||||
// convert into point in constraint space:
|
||||
|
@ -40,6 +40,7 @@ http://gimpact.sf.net
|
||||
#include "btGeneric6DofSpring2Constraint.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
#include <cmath>
|
||||
#include <new>
|
||||
|
||||
btGeneric6DofSpring2Constraint::btGeneric6DofSpring2Constraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, RotateOrder rotOrder)
|
||||
@ -845,7 +846,7 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2(
|
||||
if (m_rbA.getInvMass() == 0) m = mB; else
|
||||
if (m_rbB.getInvMass() == 0) m = mA; else
|
||||
m = mA*mB / (mA + mB);
|
||||
btScalar angularfreq = sqrt(ks / m);
|
||||
btScalar angularfreq = btSqrt(ks / m);
|
||||
|
||||
//limit stiffness (the spring should not be sampled faster that the quarter of its angular frequency)
|
||||
if (limot->m_springStiffnessLimited && 0.25 < angularfreq * dt)
|
||||
@ -1085,7 +1086,7 @@ void btGeneric6DofSpring2Constraint::setServoTarget(int index, btScalar targetOr
|
||||
btScalar target = targetOrg + SIMD_PI;
|
||||
if (1)
|
||||
{
|
||||
btScalar m = target - SIMD_2_PI * floor(target / SIMD_2_PI);
|
||||
btScalar m = target - SIMD_2_PI * std::floor(target / SIMD_2_PI);
|
||||
// handle boundary cases resulted from floating-point cut off:
|
||||
{
|
||||
if (m >= SIMD_2_PI)
|
||||
|
Loading…
Reference in New Issue
Block a user