Skip to content

Commit

Permalink
Created Vec3::sOne as an alias for Vec3::sReplicate(1.0f)
Browse files Browse the repository at this point in the history
Replaced all occurrences in code with this shorthand
  • Loading branch information
jrouwe committed Jan 17, 2025
1 parent 41532dd commit 193857e
Show file tree
Hide file tree
Showing 60 changed files with 222 additions and 198 deletions.
2 changes: 1 addition & 1 deletion Jolt/Geometry/RayAABox.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ class RayInvDirection
mIsParallel = Vec3::sLessOrEqual(inDirection.Abs(), Vec3::sReplicate(1.0e-20f));

// Calculate 1 / direction while avoiding division by zero
mInvDirection = Vec3::sSelect(inDirection, Vec3::sReplicate(1.0f), mIsParallel).Reciprocal();
mInvDirection = Vec3::sSelect(inDirection, Vec3::sOne(), mIsParallel).Reciprocal();
}

Vec3 mInvDirection; ///< 1 / ray direction
Expand Down
6 changes: 3 additions & 3 deletions Jolt/Geometry/RayTriangle.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ JPH_INLINE float RayTriangle(Vec3Arg inOrigin, Vec3Arg inDirection, Vec3Arg inV0

// Zero & one
Vec3 zero = Vec3::sZero();
Vec3 one = Vec3::sReplicate(1.0f);
Vec3 one = Vec3::sOne();

// Find vectors for two edges sharing inV0
Vec3 e1 = inV1 - inV0;
Expand All @@ -31,7 +31,7 @@ JPH_INLINE float RayTriangle(Vec3Arg inOrigin, Vec3Arg inDirection, Vec3Arg inV0
UVec4 det_near_zero = Vec3::sLess(det.Abs(), epsilon);

// When the determinant is near zero, set it to one to avoid dividing by zero
det = Vec3::sSelect(det, Vec3::sReplicate(1.0f), det_near_zero);
det = Vec3::sSelect(det, Vec3::sOne(), det_near_zero);

// Calculate distance from inV0 to ray origin
Vec3 s = inOrigin - inV0;
Expand Down Expand Up @@ -110,7 +110,7 @@ JPH_INLINE Vec4 RayTriangle4(Vec3Arg inOrigin, Vec3Arg inDirection, Vec4Arg inV0
UVec4 det_near_zero = Vec4::sLess(det, epsilon);

// Set components of the determinant to 1 that are near zero to avoid dividing by zero
det = Vec4::sSelect(det, Vec4::sReplicate(1.0f), det_near_zero);
det = Vec4::sSelect(det, Vec4::sOne(), det_near_zero);

// Calculate distance from inV0 to ray origin
Vec4 sx = inOrigin.SplatX() - inV0X;
Expand Down
3 changes: 3 additions & 0 deletions Jolt/Math/DVec3.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,9 @@ class [[nodiscard]] alignas(JPH_DVECTOR_ALIGNMENT) DVec3
/// Vector with all zeros
static JPH_INLINE DVec3 sZero();

/// Vector with all ones
static JPH_INLINE DVec3 sOne();

/// Vectors with the principal axis
static JPH_INLINE DVec3 sAxisX() { return DVec3(1, 0, 0); }
static JPH_INLINE DVec3 sAxisY() { return DVec3(0, 1, 0); }
Expand Down
7 changes: 6 additions & 1 deletion Jolt/Math/DVec3.inl
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,11 @@ DVec3 DVec3::sReplicate(double inV)
#endif
}

DVec3 DVec3::sOne()
{
return sReplicate(1.0);
}

DVec3 DVec3::sNaN()
{
return sReplicate(numeric_limits<double>::quiet_NaN());
Expand Down Expand Up @@ -727,7 +732,7 @@ DVec3 DVec3::Abs() const

DVec3 DVec3::Reciprocal() const
{
return sReplicate(1.0) / mValue;
return sOne() / mValue;
}

DVec3 DVec3::Cross(DVec3Arg inV2) const
Expand Down
3 changes: 3 additions & 0 deletions Jolt/Math/Vec3.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,9 @@ class [[nodiscard]] alignas(JPH_VECTOR_ALIGNMENT) Vec3
/// Vector with all zeros
static JPH_INLINE Vec3 sZero();

/// Vector with all ones
static JPH_INLINE Vec3 sOne();

/// Vector with all NaN's
static JPH_INLINE Vec3 sNaN();

Expand Down
7 changes: 6 additions & 1 deletion Jolt/Math/Vec3.inl
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,11 @@ Vec3 Vec3::sReplicate(float inV)
#endif
}

Vec3 Vec3::sOne()
{
return sReplicate(1.0f);
}

Vec3 Vec3::sNaN()
{
return sReplicate(numeric_limits<float>::quiet_NaN());
Expand Down Expand Up @@ -584,7 +589,7 @@ Vec3 Vec3::Abs() const

Vec3 Vec3::Reciprocal() const
{
return sReplicate(1.0f) / mValue;
return sOne() / mValue;
}

Vec3 Vec3::Cross(Vec3Arg inV2) const
Expand Down
3 changes: 3 additions & 0 deletions Jolt/Math/Vec4.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@ class [[nodiscard]] alignas(JPH_VECTOR_ALIGNMENT) Vec4
/// Vector with all zeros
static JPH_INLINE Vec4 sZero();

/// Vector with all ones
static JPH_INLINE Vec4 sOne();

/// Vector with all NaN's
static JPH_INLINE Vec4 sNaN();

Expand Down
15 changes: 10 additions & 5 deletions Jolt/Math/Vec4.inl
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,11 @@ Vec4 Vec4::sReplicate(float inV)
#endif
}

Vec4 Vec4::sOne()
{
return sReplicate(1.0f);
}

Vec4 Vec4::sNaN()
{
return sReplicate(numeric_limits<float>::quiet_NaN());
Expand Down Expand Up @@ -614,7 +619,7 @@ Vec4 Vec4::Abs() const

Vec4 Vec4::Reciprocal() const
{
return sReplicate(1.0f) / mValue;
return sOne() / mValue;
}

Vec4 Vec4::DotV(Vec4Arg inV2) const
Expand Down Expand Up @@ -805,7 +810,7 @@ void Vec4::SinCos(Vec4 &outSin, Vec4 &outCos) const

// Taylor expansion:
// Cos(x) = 1 - x^2/2! + x^4/4! - x^6/6! + x^8/8! + ... = (((x2/8!- 1/6!) * x2 + 1/4!) * x2 - 1/2!) * x2 + 1
Vec4 taylor_cos = ((2.443315711809948e-5f * x2 - Vec4::sReplicate(1.388731625493765e-3f)) * x2 + Vec4::sReplicate(4.166664568298827e-2f)) * x2 * x2 - 0.5f * x2 + Vec4::sReplicate(1.0f);
Vec4 taylor_cos = ((2.443315711809948e-5f * x2 - Vec4::sReplicate(1.388731625493765e-3f)) * x2 + Vec4::sReplicate(4.166664568298827e-2f)) * x2 * x2 - 0.5f * x2 + Vec4::sOne();
// Sin(x) = x - x^3/3! + x^5/5! - x^7/7! + ... = ((-x2/7! + 1/5!) * x2 - 1/3!) * x2 * x + x
Vec4 taylor_sin = ((-1.9515295891e-4f * x2 + Vec4::sReplicate(8.3321608736e-3f)) * x2 - Vec4::sReplicate(1.6666654611e-1f)) * x2 * x + x;

Expand Down Expand Up @@ -880,14 +885,14 @@ Vec4 Vec4::ASin() const
Vec4 a = Vec4::sXor(*this, asin_sign.ReinterpretAsFloat());

// ASin is not defined outside the range [-1, 1] but it often happens that a value is slightly above 1 so we just clamp here
a = Vec4::sMin(a, Vec4::sReplicate(1.0f));
a = Vec4::sMin(a, Vec4::sOne());

// When |x| <= 0.5 we use the asin approximation as is
Vec4 z1 = a * a;
Vec4 x1 = a;

// When |x| > 0.5 we use the identity asin(x) = PI / 2 - 2 * asin(sqrt((1 - x) / 2))
Vec4 z2 = 0.5f * (Vec4::sReplicate(1.0f) - a);
Vec4 z2 = 0.5f * (Vec4::sOne() - a);
Vec4 x2 = z2.Sqrt();

// Select which of the two situations we have
Expand Down Expand Up @@ -923,7 +928,7 @@ Vec4 Vec4::ATan() const

// If x > Tan(PI / 8)
UVec4 greater1 = Vec4::sGreater(x, Vec4::sReplicate(0.4142135623730950f));
Vec4 x1 = (x - Vec4::sReplicate(1.0f)) / (x + Vec4::sReplicate(1.0f));
Vec4 x1 = (x - Vec4::sOne()) / (x + Vec4::sOne());

// If x > Tan(3 * PI / 8)
UVec4 greater2 = Vec4::sGreater(x, Vec4::sReplicate(2.414213562373095f));
Expand Down
4 changes: 2 additions & 2 deletions Jolt/Physics/Body/Body.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void Body::MoveKinematic(RVec3Arg inTargetPosition, QuatArg inTargetRotation, fl

void Body::CalculateWorldSpaceBoundsInternal()
{
mBounds = mShape->GetWorldSpaceBounds(GetCenterOfMassTransform(), Vec3::sReplicate(1.0f));
mBounds = mShape->GetWorldSpaceBounds(GetCenterOfMassTransform(), Vec3::sOne());
}

void Body::SetPositionAndRotationInternal(RVec3Arg inPosition, QuatArg inRotation, bool inResetSleepTimer)
Expand Down Expand Up @@ -190,7 +190,7 @@ void Body::GetSubmergedVolume(RVec3Arg inSurfacePosition, Vec3Arg inSurfaceNorma
Plane surface_relative_to_body = Plane::sFromPointAndNormal(inSurfacePosition - mPosition, inSurfaceNormal);

// Calculate amount of volume that is submerged and what the center of buoyancy is
mShape->GetSubmergedVolume(rotation, Vec3::sReplicate(1.0f), surface_relative_to_body, outTotalVolume, outSubmergedVolume, outRelativeCenterOfBuoyancy JPH_IF_DEBUG_RENDERER(, mPosition));
mShape->GetSubmergedVolume(rotation, Vec3::sOne(), surface_relative_to_body, outTotalVolume, outSubmergedVolume, outRelativeCenterOfBuoyancy JPH_IF_DEBUG_RENDERER(, mPosition));
}

bool Body::ApplyBuoyancyImpulse(float inTotalVolume, float inSubmergedVolume, Vec3Arg inRelativeCenterOfBuoyancy, float inBuoyancy, float inLinearDrag, float inAngularDrag, Vec3Arg inFluidVelocity, Vec3Arg inGravity, float inDeltaTime)
Expand Down
8 changes: 4 additions & 4 deletions Jolt/Physics/Body/BodyManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1014,15 +1014,15 @@ void BodyManager::Draw(const DrawSettings &inDrawSettings, const PhysicsSettings

// Draw the results of GetSupportFunction
if (inDrawSettings.mDrawGetSupportFunction)
body->mShape->DrawGetSupportFunction(inRenderer, body->GetCenterOfMassTransform(), Vec3::sReplicate(1.0f), color, inDrawSettings.mDrawSupportDirection);
body->mShape->DrawGetSupportFunction(inRenderer, body->GetCenterOfMassTransform(), Vec3::sOne(), color, inDrawSettings.mDrawSupportDirection);

// Draw the results of GetSupportingFace
if (inDrawSettings.mDrawGetSupportingFace)
body->mShape->DrawGetSupportingFace(inRenderer, body->GetCenterOfMassTransform(), Vec3::sReplicate(1.0f));
body->mShape->DrawGetSupportingFace(inRenderer, body->GetCenterOfMassTransform(), Vec3::sOne());

// Draw the shape
if (inDrawSettings.mDrawShape)
body->mShape->Draw(inRenderer, body->GetCenterOfMassTransform(), Vec3::sReplicate(1.0f), color, inDrawSettings.mDrawShapeColor == EShapeColor::MaterialColor, inDrawSettings.mDrawShapeWireframe || is_sensor);
body->mShape->Draw(inRenderer, body->GetCenterOfMassTransform(), Vec3::sOne(), color, inDrawSettings.mDrawShapeColor == EShapeColor::MaterialColor, inDrawSettings.mDrawShapeWireframe || is_sensor);

// Draw bounding box
if (inDrawSettings.mDrawBoundingBox)
Expand Down Expand Up @@ -1147,7 +1147,7 @@ void BodyManager::ValidateActiveBodyBounds()
{
const Body *body = mBodies[id->GetIndex()];
AABox cached = body->GetWorldSpaceBounds();
AABox calculated = body->GetShape()->GetWorldSpaceBounds(body->GetCenterOfMassTransform(), Vec3::sReplicate(1.0f));
AABox calculated = body->GetShape()->GetWorldSpaceBounds(body->GetCenterOfMassTransform(), Vec3::sOne());
JPH_ASSERT(cached == calculated);
}
}
Expand Down
4 changes: 2 additions & 2 deletions Jolt/Physics/Body/MotionProperties.inl
Original file line number Diff line number Diff line change
Expand Up @@ -107,8 +107,8 @@ void MotionProperties::ApplyGyroscopicForceInternal(QuatArg inBodyRotation, floa

// Calculate local space inertia tensor (a diagonal in local space)
UVec4 is_zero = Vec3::sEquals(mInvInertiaDiagonal, Vec3::sZero());
Vec3 denominator = Vec3::sSelect(mInvInertiaDiagonal, Vec3::sReplicate(1.0f), is_zero);
Vec3 nominator = Vec3::sSelect(Vec3::sReplicate(1.0f), Vec3::sZero(), is_zero);
Vec3 denominator = Vec3::sSelect(mInvInertiaDiagonal, Vec3::sOne(), is_zero);
Vec3 nominator = Vec3::sSelect(Vec3::sOne(), Vec3::sZero(), is_zero);
Vec3 local_inertia = nominator / denominator; // Avoid dividing by zero, inertia in this axis will be zero

// Calculate local space angular momentum
Expand Down
2 changes: 1 addition & 1 deletion Jolt/Physics/Character/Character.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ void Character::CheckCollision(RMat44Arg inCenterOfMassTransform, Vec3Arg inMove
settings.mActiveEdgeMovementDirection = inMovementDirection;
settings.mBackFaceMode = EBackFaceMode::IgnoreBackFaces;

sGetNarrowPhaseQuery(mSystem, inLockBodies).CollideShape(inShape, Vec3::sReplicate(1.0f), inCenterOfMassTransform, settings, inBaseOffset, ioCollector, broadphase_layer_filter, object_layer_filter, body_filter);
sGetNarrowPhaseQuery(mSystem, inLockBodies).CollideShape(inShape, Vec3::sOne(), inCenterOfMassTransform, settings, inBaseOffset, ioCollector, broadphase_layer_filter, object_layer_filter, body_filter);
}

void Character::CheckCollision(RVec3Arg inPosition, QuatArg inRotation, Vec3Arg inMovementDirection, float inMaxSeparationDistance, const Shape *inShape, RVec3Arg inBaseOffset, CollideShapeCollector &ioCollector, bool inLockBodies) const
Expand Down
18 changes: 9 additions & 9 deletions Jolt/Physics/Character/CharacterVirtual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void CharacterVsCharacterCollisionSimple::CollideCharacter(const CharacterVirtua
settings.mMaxSeparationDistance = inCollideShapeSettings.mMaxSeparationDistance + c->GetCharacterPadding();

// Note that this collides against the character's shape without padding, this will be corrected for in CharacterVirtual::GetContactsAtPosition
CollisionDispatch::sCollideShapeVsShape(shape, c->GetShape(), Vec3::sReplicate(1.0f), Vec3::sReplicate(1.0f), transform1, transform2, SubShapeIDCreator(), SubShapeIDCreator(), settings, ioCollector);
CollisionDispatch::sCollideShapeVsShape(shape, c->GetShape(), Vec3::sOne(), Vec3::sOne(), transform1, transform2, SubShapeIDCreator(), SubShapeIDCreator(), settings, ioCollector);
}

// Reset the user data
Expand All @@ -64,7 +64,7 @@ void CharacterVsCharacterCollisionSimple::CastCharacter(const CharacterVirtual *
{
// Convert shape cast relative to inBaseOffset
Mat44 transform1 = inCenterOfMassTransform.PostTranslated(-inBaseOffset).ToMat44();
ShapeCast shape_cast(inCharacter->GetShape(), Vec3::sReplicate(1.0f), transform1, inDirection);
ShapeCast shape_cast(inCharacter->GetShape(), Vec3::sOne(), transform1, inDirection);

// Iterate over all characters
for (const CharacterVirtual *c : mCharacters)
Expand All @@ -78,7 +78,7 @@ void CharacterVsCharacterCollisionSimple::CastCharacter(const CharacterVirtual *
Mat44 transform2 = c->GetCenterOfMassTransform().PostTranslated(-inBaseOffset).ToMat44();

// Note that this collides against the character's shape without padding, this will be corrected for in CharacterVirtual::GetFirstContactForSweep
CollisionDispatch::sCastShapeVsShapeWorldSpace(shape_cast, inShapeCastSettings, c->GetShape(), Vec3::sReplicate(1.0f), { }, transform2, SubShapeIDCreator(), SubShapeIDCreator(), ioCollector);
CollisionDispatch::sCastShapeVsShapeWorldSpace(shape_cast, inShapeCastSettings, c->GetShape(), Vec3::sOne(), { }, transform2, SubShapeIDCreator(), SubShapeIDCreator(), ioCollector);
}

// Reset the user data
Expand Down Expand Up @@ -371,7 +371,7 @@ void CharacterVirtual::CheckCollision(RVec3Arg inPosition, QuatArg inRotation, V
auto collide_shape_function = mEnhancedInternalEdgeRemoval? &NarrowPhaseQuery::CollideShapeWithInternalEdgeRemoval : &NarrowPhaseQuery::CollideShape;

// Collide shape
(mSystem->GetNarrowPhaseQuery().*collide_shape_function)(inShape, Vec3::sReplicate(1.0f), transform, settings, inBaseOffset, ioCollector, inBroadPhaseLayerFilter, inObjectLayerFilter, body_filter, inShapeFilter);
(mSystem->GetNarrowPhaseQuery().*collide_shape_function)(inShape, Vec3::sOne(), transform, settings, inBaseOffset, ioCollector, inBroadPhaseLayerFilter, inObjectLayerFilter, body_filter, inShapeFilter);

// Also collide with other characters
if (mCharacterVsCharacterCollision != nullptr)
Expand Down Expand Up @@ -557,7 +557,7 @@ bool CharacterVirtual::GetFirstContactForSweep(RVec3Arg inPosition, Vec3Arg inDi
RVec3 base_offset = start.GetTranslation();
ContactCastCollector collector(mSystem, this, inDisplacement, mUp, inIgnoredContacts, base_offset, contact);
collector.ResetEarlyOutFraction(contact.mFraction);
RShapeCast shape_cast(mShape, Vec3::sReplicate(1.0f), start, inDisplacement);
RShapeCast shape_cast(mShape, Vec3::sOne(), start, inDisplacement);
mSystem->GetNarrowPhaseQuery().CastShape(shape_cast, settings, base_offset, collector, inBroadPhaseLayerFilter, inObjectLayerFilter, body_filter, inShapeFilter);

// Also collide with other characters
Expand Down Expand Up @@ -602,7 +602,7 @@ bool CharacterVirtual::GetFirstContactForSweep(RVec3Arg inPosition, Vec3Arg inDi
AddConvexRadius add_cvx(polygon, character_padding);

// Correct fraction to hit this inflated face instead of the inner shape
corrected = sCorrectFractionForCharacterPadding(mShape, start.GetRotation(), inDisplacement, Vec3::sReplicate(1.0f), add_cvx, outContact.mFraction);
corrected = sCorrectFractionForCharacterPadding(mShape, start.GetRotation(), inDisplacement, Vec3::sOne(), add_cvx, outContact.mFraction);
}
if (!corrected)
{
Expand Down Expand Up @@ -1602,7 +1602,7 @@ bool CharacterVirtual::WalkStairs(float inDeltaTime, Vec3Arg inStepUp, Vec3Arg i
RVec3 debug_pos = new_position + contact.mFraction * down;
DebugRenderer::sInstance->DrawArrow(new_position, debug_pos, Color::sWhite, 0.01f);
DebugRenderer::sInstance->DrawArrow(contact.mPosition, contact.mPosition + contact.mSurfaceNormal, Color::sWhite, 0.01f);
mShape->Draw(DebugRenderer::sInstance, GetCenterOfMassTransform(debug_pos, mRotation, mShape), Vec3::sReplicate(1.0f), Color::sWhite, false, true);
mShape->Draw(DebugRenderer::sInstance, GetCenterOfMassTransform(debug_pos, mRotation, mShape), Vec3::sOne(), Color::sWhite, false, true);
}
#endif // JPH_DEBUG_RENDERER

Expand Down Expand Up @@ -1640,7 +1640,7 @@ bool CharacterVirtual::WalkStairs(float inDeltaTime, Vec3Arg inStepUp, Vec3Arg i
RVec3 debug_pos = test_position + test_contact.mFraction * down;
DebugRenderer::sInstance->DrawArrow(test_position, debug_pos, Color::sCyan, 0.01f);
DebugRenderer::sInstance->DrawArrow(test_contact.mPosition, test_contact.mPosition + test_contact.mSurfaceNormal, Color::sCyan, 0.01f);
mShape->Draw(DebugRenderer::sInstance, GetCenterOfMassTransform(debug_pos, mRotation, mShape), Vec3::sReplicate(1.0f), Color::sCyan, false, true);
mShape->Draw(DebugRenderer::sInstance, GetCenterOfMassTransform(debug_pos, mRotation, mShape), Vec3::sOne(), Color::sCyan, false, true);
}
#endif // JPH_DEBUG_RENDERER

Expand Down Expand Up @@ -1680,7 +1680,7 @@ bool CharacterVirtual::StickToFloor(Vec3Arg inStepDown, const BroadPhaseLayerFil
if (sDrawStickToFloor)
{
DebugRenderer::sInstance->DrawArrow(mPosition, new_position, Color::sOrange, 0.01f);
mShape->Draw(DebugRenderer::sInstance, GetCenterOfMassTransform(new_position, mRotation, mShape), Vec3::sReplicate(1.0f), Color::sOrange, false, true);
mShape->Draw(DebugRenderer::sInstance, GetCenterOfMassTransform(new_position, mRotation, mShape), Vec3::sOne(), Color::sOrange, false, true);
}
#endif // JPH_DEBUG_RENDERER

Expand Down
2 changes: 1 addition & 1 deletion Jolt/Physics/Collision/BroadPhase/QuadTree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1534,7 +1534,7 @@ void QuadTree::ValidateTree(const BodyVector &inBodies, const TrackingVector &in
node.GetChildBounds(i, body_bounds);
const Body *body = inBodies[child_node_id.GetBodyID().GetIndex()];
AABox cached_body_bounds = body->GetWorldSpaceBounds();
AABox real_body_bounds = body->GetShape()->GetWorldSpaceBounds(body->GetCenterOfMassTransform(), Vec3::sReplicate(1.0f));
AABox real_body_bounds = body->GetShape()->GetWorldSpaceBounds(body->GetCenterOfMassTransform(), Vec3::sOne());
JPH_ASSERT(cached_body_bounds == real_body_bounds); // Check that cached body bounds are up to date
JPH_ASSERT(body_bounds.Contains(real_body_bounds));
}
Expand Down
6 changes: 3 additions & 3 deletions Jolt/Physics/Collision/Shape/ConvexShape.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ bool ConvexShape::CastRay(const RayCast &inRay, const SubShapeIDCreator &inSubSh

// Create support function
SupportBuffer buffer;
const Support *support = GetSupportFunction(ConvexShape::ESupportMode::IncludeConvexRadius, buffer, Vec3::sReplicate(1.0f));
const Support *support = GetSupportFunction(ConvexShape::ESupportMode::IncludeConvexRadius, buffer, Vec3::sOne());

// Cast ray
GJKClosestPoint gjk;
Expand Down Expand Up @@ -241,7 +241,7 @@ void ConvexShape::CollidePoint(Vec3Arg inPoint, const SubShapeIDCreator &inSubSh
{
// Create support function
SupportBuffer buffer;
const Support *support = GetSupportFunction(ConvexShape::ESupportMode::IncludeConvexRadius, buffer, Vec3::sReplicate(1.0f));
const Support *support = GetSupportFunction(ConvexShape::ESupportMode::IncludeConvexRadius, buffer, Vec3::sOne());

// Create support function for point
PointConvexSupport point { inPoint };
Expand Down Expand Up @@ -319,7 +319,7 @@ class ConvexShape::CSGetTrianglesContext
mLocalToWorld(Mat44::sRotationTranslation(inRotation, inPositionCOM) * Mat44::sScale(inScale)),
mIsInsideOut(ScaleHelpers::IsInsideOut(inScale))
{
mSupport = inShape->GetSupportFunction(ESupportMode::IncludeConvexRadius, mSupportBuffer, Vec3::sReplicate(1.0f));
mSupport = inShape->GetSupportFunction(ESupportMode::IncludeConvexRadius, mSupportBuffer, Vec3::sOne());
}

SupportBuffer mSupportBuffer;
Expand Down
4 changes: 2 additions & 2 deletions Jolt/Physics/Collision/Shape/HeightFieldShape.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class JPH_EXPORT HeightFieldShapeSettings final : public ShapeSettings
/// The height field is a surface defined by: mOffset + mScale * (x, mHeightSamples[y * mSampleCount + x], y).
/// where x and y are integers in the range x and y e [0, mSampleCount - 1].
Vec3 mOffset = Vec3::sZero();
Vec3 mScale = Vec3::sReplicate(1.0f);
Vec3 mScale = Vec3::sOne();
uint32 mSampleCount = 0;

/// Artificial minimal value of mHeightSamples, used for compression and can be used to update the terrain after creating with lower height values. If there are any lower values in mHeightSamples, this value will be ignored.
Expand Down Expand Up @@ -349,7 +349,7 @@ class JPH_EXPORT HeightFieldShape final : public Shape
/// The height field is a surface defined by: mOffset + mScale * (x, mHeightSamples[y * mSampleCount + x], y).
/// where x and y are integers in the range x and y e [0, mSampleCount - 1].
Vec3 mOffset = Vec3::sZero();
Vec3 mScale = Vec3::sReplicate(1.0f);
Vec3 mScale = Vec3::sOne();

/// Height data
uint32 mSampleCount = 0; ///< See HeightFieldShapeSettings::mSampleCount
Expand Down
2 changes: 1 addition & 1 deletion Jolt/Physics/Collision/Shape/MeshShape.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -349,7 +349,7 @@ MassProperties MeshShape::GetMassProperties() const
// creating a Body:
//
// BodyCreationSettings::mOverrideMassProperties = EOverrideMassProperties::MassAndInertiaProvided;
// BodyCreationSettings::mMassPropertiesOverride.SetMassAndInertiaOfSolidBox(Vec3::sReplicate(1.0f), 1000.0f);
// BodyCreationSettings::mMassPropertiesOverride.SetMassAndInertiaOfSolidBox(Vec3::sOne(), 1000.0f);
//
// Note that for a mesh shape to simulate properly, it is best if the mesh is manifold
// (i.e. closed, all edges shared by only two triangles, consistent winding order).
Expand Down
Loading

0 comments on commit 193857e

Please sign in to comment.