feat: modules moved and engine moved to submodule

This commit is contained in:
Jan van der Weide 2025-04-12 18:40:44 +02:00
parent dfb5e645cd
commit c33d2130cc
5136 changed files with 225275 additions and 64485 deletions

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_BODY_ACCESSOR_3D_H
#define JOLT_BODY_ACCESSOR_3D_H
#pragma once
#include "../objects/jolt_object_3d.h"
@ -210,5 +209,3 @@ typedef JoltAccessibleBody3D<JoltScopedBodyWriter3D, JPH::Body> JoltWritableBody
typedef JoltAccessibleBodies3D<JoltScopedBodyReader3D, const JPH::Body> JoltReadableBodies3D;
typedef JoltAccessibleBodies3D<JoltScopedBodyWriter3D, JPH::Body> JoltWritableBodies3D;
#endif // JOLT_BODY_ACCESSOR_3D_H

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_BROAD_PHASE_LAYER_H
#define JOLT_BROAD_PHASE_LAYER_H
#pragma once
#include "Jolt/Jolt.h"
@ -48,5 +47,3 @@ constexpr JPH::BroadPhaseLayer AREA_UNDETECTABLE(4);
constexpr uint32_t COUNT = 5;
} // namespace JoltBroadPhaseLayer
#endif // JOLT_BROAD_PHASE_LAYER_H

View file

@ -200,7 +200,7 @@ bool JoltContactListener3D::_try_add_contacts(const JPH::Body &p_jolt_body1, con
manifold.depth = p_manifold.mPenetrationDepth;
JPH::CollisionEstimationResult collision;
JPH::EstimateCollisionResponse(p_jolt_body1, p_jolt_body2, p_manifold, collision, p_settings.mCombinedFriction, p_settings.mCombinedRestitution, JoltProjectSettings::get_bounce_velocity_threshold(), 5);
JPH::EstimateCollisionResponse(p_jolt_body1, p_jolt_body2, p_manifold, collision, p_settings.mCombinedFriction, p_settings.mCombinedRestitution, JoltProjectSettings::bounce_velocity_threshold, 5);
for (JPH::uint i = 0; i < contact_count; ++i) {
const JPH::RVec3 relative_point1 = JPH::RVec3(p_manifold.mRelativeContactPointsOn1[i]);

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_CONTACT_LISTENER_3D_H
#define JOLT_CONTACT_LISTENER_3D_H
#pragma once
#include "core/templates/hash_map.h"
#include "core/templates/hash_set.h"
@ -44,7 +43,6 @@
#include "Jolt/Physics/Collision/ContactListener.h"
#include "Jolt/Physics/SoftBody/SoftBodyContactListener.h"
#include <stdint.h>
#include <new>
class JoltShapedObject3D;
@ -138,5 +136,3 @@ public:
void set_max_debug_contacts(int p_count) { debug_contacts.resize(p_count); }
#endif
};
#endif // JOLT_CONTACT_LISTENER_3D_H

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_JOB_SYSTEM_H
#define JOLT_JOB_SYSTEM_H
#pragma once
#include "core/os/spin_lock.h"
#include "core/templates/hash_map.h"
@ -39,7 +38,6 @@
#include "Jolt/Core/FixedSizeFreeList.h"
#include "Jolt/Core/JobSystemWithBarrier.h"
#include <stdint.h>
#include <atomic>
class JoltJobSystem final : public JPH::JobSystemWithBarrier {
@ -103,5 +101,3 @@ public:
void flush_timings();
#endif
};
#endif // JOLT_JOB_SYSTEM_H

View file

@ -64,7 +64,7 @@ public:
allow_collision(AREA_UNDETECTABLE, BODY_DYNAMIC);
allow_collision(AREA_UNDETECTABLE, AREA_DETECTABLE);
if (JoltProjectSettings::areas_detect_static_bodies()) {
if (JoltProjectSettings::areas_detect_static_bodies) {
allow_collision(BODY_STATIC, AREA_DETECTABLE);
allow_collision(BODY_STATIC, AREA_UNDETECTABLE);
allow_collision(BODY_STATIC_BIG, AREA_DETECTABLE);

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_LAYERS_H
#define JOLT_LAYERS_H
#pragma once
#include "core/templates/hash_map.h"
#include "core/templates/local_vector.h"
@ -39,8 +38,6 @@
#include "Jolt/Physics/Collision/BroadPhase/BroadPhaseLayer.h"
#include "Jolt/Physics/Collision/ObjectLayer.h"
#include <stdint.h>
class JoltLayers final
: public JPH::BroadPhaseLayerInterface,
public JPH::ObjectLayerPairFilter,
@ -68,5 +65,3 @@ public:
JPH::ObjectLayer to_object_layer(JPH::BroadPhaseLayer p_broad_phase_layer, uint32_t p_collision_layer, uint32_t p_collision_mask);
void from_object_layer(JPH::ObjectLayer p_encoded_layer, JPH::BroadPhaseLayer &r_broad_phase_layer, uint32_t &r_collision_layer, uint32_t &r_collision_mask) const;
};
#endif // JOLT_LAYERS_H

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_MOTION_FILTER_3D_H
#define JOLT_MOTION_FILTER_3D_H
#pragma once
#include "core/object/object_id.h"
#include "core/templates/hash_set.h"
@ -68,5 +67,3 @@ public:
virtual bool ShouldCollide(const JPH::Shape *p_jolt_shape, const JPH::SubShapeID &p_jolt_shape_id) const override;
virtual bool ShouldCollide(const JPH::Shape *p_jolt_shape_self, const JPH::SubShapeID &p_jolt_shape_id_self, const JPH::Shape *p_jolt_shape_other, const JPH::SubShapeID &p_jolt_shape_id_other) const override;
};
#endif // JOLT_MOTION_FILTER_3D_H

View file

@ -32,6 +32,7 @@
#include "../jolt_physics_server_3d.h"
#include "../jolt_project_settings.h"
#include "../misc/jolt_math_funcs.h"
#include "../misc/jolt_type_conversions.h"
#include "../objects/jolt_area_3d.h"
#include "../objects/jolt_body_3d.h"
@ -110,7 +111,7 @@ bool JoltPhysicsDirectSpaceState3D::_cast_motion_impl(const JPH::Shape &p_jolt_s
};
// Figure out the number of steps we need in our binary search in order to achieve millimeter precision, within reason.
const int step_count = CLAMP(int(logf(1000.0f * motion_length) / (float)Math_LN2), 4, 16);
const int step_count = CLAMP(int(logf(1000.0f * motion_length) / (float)Math::LN2), 4, 16);
bool collided = false;
@ -171,9 +172,6 @@ bool JoltPhysicsDirectSpaceState3D::_cast_motion_impl(const JPH::Shape &p_jolt_s
}
bool JoltPhysicsDirectSpaceState3D::_body_motion_recover(const JoltBody3D &p_body, const Transform3D &p_transform, float p_margin, const HashSet<RID> &p_excluded_bodies, const HashSet<ObjectID> &p_excluded_objects, Vector3 &r_recovery) const {
const int recovery_iterations = JoltProjectSettings::get_motion_query_recovery_iterations();
const float recovery_amount = JoltProjectSettings::get_motion_query_recovery_amount();
const JPH::Shape *jolt_shape = p_body.get_jolt_shape();
const Vector3 com_scaled = to_godot(jolt_shape->GetCenterOfMass());
@ -189,10 +187,10 @@ bool JoltPhysicsDirectSpaceState3D::_body_motion_recover(const JoltBody3D &p_bod
bool recovered = false;
for (int i = 0; i < recovery_iterations; ++i) {
for (int i = 0; i < JoltProjectSettings::motion_query_recovery_iterations; ++i) {
collector.reset();
_collide_shape_kinematics(jolt_shape, JPH::Vec3::sReplicate(1.0f), to_jolt_r(transform_com), settings, to_jolt_r(base_offset), collector, motion_filter, motion_filter, motion_filter, motion_filter);
_collide_shape_kinematics(jolt_shape, JPH::Vec3::sOne(), to_jolt_r(transform_com), settings, to_jolt_r(base_offset), collector, motion_filter, motion_filter, motion_filter, motion_filter);
if (!collector.had_hit()) {
break;
@ -240,7 +238,7 @@ bool JoltPhysicsDirectSpaceState3D::_body_motion_recover(const JoltBody3D &p_bod
const JoltBody3D *other_body = other_jolt_body.as_body();
ERR_CONTINUE(other_body == nullptr);
const float recovery_distance = penetration_depth * recovery_amount;
const float recovery_distance = penetration_depth * JoltProjectSettings::motion_query_recovery_amount;
const float other_priority = other_body->get_collision_priority();
const float other_priority_normalized = other_priority / average_priority;
const float scaled_recovery_distance = recovery_distance * other_priority_normalized;
@ -288,15 +286,14 @@ bool JoltPhysicsDirectSpaceState3D::_body_motion_cast(const JoltBody3D &p_body,
const Transform3D transform_com_local = transform_local.translated_local(com_scaled);
Transform3D transform_com = body_transform * transform_com_local;
Vector3 scale = transform_com.basis.get_scale();
Vector3 scale;
JoltMath::decompose(transform_com, scale);
JOLT_ENSURE_SCALE_VALID(jolt_shape, scale, "body_test_motion was passed an invalid transform along with body '%s'. This results in invalid scaling for shape at index %d.");
transform_com.basis.orthonormalize();
real_t shape_safe_fraction = 1.0;
real_t shape_unsafe_fraction = 1.0;
collided |= _cast_motion_impl(*jolt_shape, transform_com, scale, p_motion, JoltProjectSettings::use_enhanced_internal_edge_removal_for_motion_queries(), false, settings, motion_filter, motion_filter, motion_filter, motion_filter, shape_safe_fraction, shape_unsafe_fraction);
collided |= _cast_motion_impl(*jolt_shape, transform_com, scale, p_motion, JoltProjectSettings::use_enhanced_internal_edge_removal_for_motion_queries, false, settings, motion_filter, motion_filter, motion_filter, motion_filter, shape_safe_fraction, shape_unsafe_fraction);
r_safe_fraction = MIN(r_safe_fraction, shape_safe_fraction);
r_unsafe_fraction = MIN(r_unsafe_fraction, shape_unsafe_fraction);
@ -323,7 +320,7 @@ bool JoltPhysicsDirectSpaceState3D::_body_motion_collide(const JoltBody3D &p_bod
const JoltMotionFilter3D motion_filter(p_body, p_excluded_bodies, p_excluded_objects);
JoltQueryCollectorClosestMulti<JPH::CollideShapeCollector, 32> collector(p_max_collisions);
_collide_shape_kinematics(jolt_shape, JPH::Vec3::sReplicate(1.0f), to_jolt_r(transform_com), settings, to_jolt_r(base_offset), collector, motion_filter, motion_filter, motion_filter, motion_filter);
_collide_shape_kinematics(jolt_shape, JPH::Vec3::sOne(), to_jolt_r(transform_com), settings, to_jolt_r(base_offset), collector, motion_filter, motion_filter, motion_filter, motion_filter);
if (!collector.had_hit() || p_result == nullptr) {
return collector.had_hit();
@ -400,7 +397,7 @@ bool JoltPhysicsDirectSpaceState3D::_body_motion_collide(const JoltBody3D &p_bod
}
int JoltPhysicsDirectSpaceState3D::_try_get_face_index(const JPH::Body &p_body, const JPH::SubShapeID &p_sub_shape_id) {
if (!JoltProjectSettings::enable_ray_cast_face_index()) {
if (!JoltProjectSettings::enable_ray_cast_face_index) {
return -1;
}
@ -421,7 +418,7 @@ void JoltPhysicsDirectSpaceState3D::_generate_manifold(const JPH::CollideShapeRe
const JPH::PhysicsSettings &physics_settings = physics_system.GetPhysicsSettings();
const JPH::Vec3 penetration_axis = p_hit.mPenetrationAxis.Normalized();
JPH::ManifoldBetweenTwoFaces(p_hit.mContactPointOn1, p_hit.mContactPointOn2, penetration_axis, physics_settings.mManifoldToleranceSq, p_hit.mShape1Face, p_hit.mShape2Face, r_contact_points1, r_contact_points2 JPH_IF_DEBUG_RENDERER(, p_center_of_mass));
JPH::ManifoldBetweenTwoFaces(p_hit.mContactPointOn1, p_hit.mContactPointOn2, penetration_axis, physics_settings.mManifoldTolerance, p_hit.mShape1Face, p_hit.mShape2Face, r_contact_points1, r_contact_points2 JPH_IF_DEBUG_RENDERER(, p_center_of_mass));
if (r_contact_points1.size() > 4) {
JPH::PruneContactPoints(penetration_axis, r_contact_points1, r_contact_points2 JPH_IF_DEBUG_RENDERER(, p_center_of_mass));
@ -439,7 +436,7 @@ void JoltPhysicsDirectSpaceState3D::_collide_shape_queries(
const JPH::ObjectLayerFilter &p_object_layer_filter,
const JPH::BodyFilter &p_body_filter,
const JPH::ShapeFilter &p_shape_filter) const {
if (JoltProjectSettings::use_enhanced_internal_edge_removal_for_queries()) {
if (JoltProjectSettings::use_enhanced_internal_edge_removal_for_queries) {
space->get_narrow_phase_query().CollideShapeWithInternalEdgeRemoval(p_shape, p_scale, p_transform_com, p_settings, p_base_offset, p_collector, p_broad_phase_layer_filter, p_object_layer_filter, p_body_filter, p_shape_filter);
} else {
space->get_narrow_phase_query().CollideShape(p_shape, p_scale, p_transform_com, p_settings, p_base_offset, p_collector, p_broad_phase_layer_filter, p_object_layer_filter, p_body_filter, p_shape_filter);
@ -457,7 +454,7 @@ void JoltPhysicsDirectSpaceState3D::_collide_shape_kinematics(
const JPH::ObjectLayerFilter &p_object_layer_filter,
const JPH::BodyFilter &p_body_filter,
const JPH::ShapeFilter &p_shape_filter) const {
if (JoltProjectSettings::use_enhanced_internal_edge_removal_for_motion_queries()) {
if (JoltProjectSettings::use_enhanced_internal_edge_removal_for_motion_queries) {
space->get_narrow_phase_query().CollideShapeWithInternalEdgeRemoval(p_shape, p_scale, p_transform_com, p_settings, p_base_offset, p_collector, p_broad_phase_layer_filter, p_object_layer_filter, p_body_filter, p_shape_filter);
} else {
space->get_narrow_phase_query().CollideShape(p_shape, p_scale, p_transform_com, p_settings, p_base_offset, p_collector, p_broad_phase_layer_filter, p_object_layer_filter, p_body_filter, p_shape_filter);
@ -590,11 +587,10 @@ int JoltPhysicsDirectSpaceState3D::intersect_shape(const ShapeParameters &p_para
Transform3D transform = p_parameters.transform;
JOLT_ENSURE_SCALE_NOT_ZERO(transform, "intersect_shape was passed an invalid transform.");
Vector3 scale = transform.basis.get_scale();
Vector3 scale;
JoltMath::decompose(transform, scale);
JOLT_ENSURE_SCALE_VALID(jolt_shape, scale, "intersect_shape was passed an invalid transform.");
transform.basis.orthonormalize();
const Vector3 com_scaled = to_godot(jolt_shape->GetCenterOfMass());
const Transform3D transform_com = transform.translated_local(com_scaled);
@ -647,11 +643,10 @@ bool JoltPhysicsDirectSpaceState3D::cast_motion(const ShapeParameters &p_paramet
Transform3D transform = p_parameters.transform;
JOLT_ENSURE_SCALE_NOT_ZERO(transform, "cast_motion (maybe from ShapeCast3D?) was passed an invalid transform.");
Vector3 scale = transform.basis.get_scale();
Vector3 scale;
JoltMath::decompose(transform, scale);
JOLT_ENSURE_SCALE_VALID(jolt_shape, scale, "cast_motion (maybe from ShapeCast3D?) was passed an invalid transform.");
transform.basis.orthonormalize();
const Vector3 com_scaled = to_godot(jolt_shape->GetCenterOfMass());
Transform3D transform_com = transform.translated_local(com_scaled);
@ -659,7 +654,7 @@ bool JoltPhysicsDirectSpaceState3D::cast_motion(const ShapeParameters &p_paramet
settings.mMaxSeparationDistance = (float)p_parameters.margin;
const JoltQueryFilter3D query_filter(*this, p_parameters.collision_mask, p_parameters.collide_with_bodies, p_parameters.collide_with_areas, p_parameters.exclude);
_cast_motion_impl(*jolt_shape, transform_com, scale, p_parameters.motion, JoltProjectSettings::use_enhanced_internal_edge_removal_for_queries(), true, settings, query_filter, query_filter, query_filter, JPH::ShapeFilter(), r_closest_safe, r_closest_unsafe);
_cast_motion_impl(*jolt_shape, transform_com, scale, p_parameters.motion, JoltProjectSettings::use_enhanced_internal_edge_removal_for_queries, true, settings, query_filter, query_filter, query_filter, JPH::ShapeFilter(), r_closest_safe, r_closest_unsafe);
return true;
}
@ -684,11 +679,10 @@ bool JoltPhysicsDirectSpaceState3D::collide_shape(const ShapeParameters &p_param
Transform3D transform = p_parameters.transform;
JOLT_ENSURE_SCALE_NOT_ZERO(transform, "collide_shape was passed an invalid transform.");
Vector3 scale = transform.basis.get_scale();
Vector3 scale;
JoltMath::decompose(transform, scale);
JOLT_ENSURE_SCALE_VALID(jolt_shape, scale, "collide_shape was passed an invalid transform.");
transform.basis.orthonormalize();
const Vector3 com_scaled = to_godot(jolt_shape->GetCenterOfMass());
const Transform3D transform_com = transform.translated_local(com_scaled);
@ -754,11 +748,10 @@ bool JoltPhysicsDirectSpaceState3D::rest_info(const ShapeParameters &p_parameter
Transform3D transform = p_parameters.transform;
JOLT_ENSURE_SCALE_NOT_ZERO(transform, "get_rest_info (maybe from ShapeCast3D?) was passed an invalid transform.");
Vector3 scale = transform.basis.get_scale();
Vector3 scale;
JoltMath::decompose(transform, scale);
JOLT_ENSURE_SCALE_VALID(jolt_shape, scale, "get_rest_info (maybe from ShapeCast3D?) was passed an invalid transform.");
transform.basis.orthonormalize();
const Vector3 com_scaled = to_godot(jolt_shape->GetCenterOfMass());
const Transform3D transform_com = transform.translated_local(com_scaled);
@ -794,7 +787,6 @@ bool JoltPhysicsDirectSpaceState3D::rest_info(const ShapeParameters &p_parameter
r_info->normal = to_godot(-hit.mPenetrationAxis.Normalized());
r_info->rid = object->get_rid();
r_info->collider_id = object->get_instance_id();
r_info->shape = 0;
r_info->linear_velocity = object->get_velocity_at_position(hit_point);
return true;
@ -890,8 +882,8 @@ bool JoltPhysicsDirectSpaceState3D::body_test_motion(const JoltBody3D &p_body, c
Transform3D transform = p_parameters.from;
JOLT_ENSURE_SCALE_NOT_ZERO(transform, vformat("body_test_motion (maybe from move_and_slide?) was passed an invalid transform along with body '%s'.", p_body.to_string()));
Vector3 scale = transform.basis.get_scale();
transform.basis.orthonormalize();
Vector3 scale;
JoltMath::decompose(transform, scale);
space->try_optimize();

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_PHYSICS_DIRECT_SPACE_STATE_3D_H
#define JOLT_PHYSICS_DIRECT_SPACE_STATE_3D_H
#pragma once
#include "servers/physics_server_3d.h"
@ -83,5 +82,3 @@ public:
JoltSpace3D &get_space() const { return *space; }
};
#endif // JOLT_PHYSICS_DIRECT_SPACE_STATE_3D_H

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_QUERY_COLLECTORS_H
#define JOLT_QUERY_COLLECTORS_H
#pragma once
#include "../jolt_project_settings.h"
#include "jolt_space_3d.h"
@ -244,5 +243,3 @@ public:
}
}
};
#endif // JOLT_QUERY_COLLECTORS_H

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_QUERY_FILTER_3D_H
#define JOLT_QUERY_FILTER_3D_H
#pragma once
#include "core/templates/hash_set.h"
#include "core/templates/rid.h"
@ -63,5 +62,3 @@ public:
virtual bool ShouldCollide(const JPH::BodyID &p_body_id) const override;
virtual bool ShouldCollideLocked(const JPH::Body &p_body) const override;
};
#endif // JOLT_QUERY_FILTER_3D_H

View file

@ -57,7 +57,7 @@ constexpr double DEFAULT_CONTACT_MAX_SEPARATION = 0.05;
constexpr double DEFAULT_CONTACT_MAX_ALLOWED_PENETRATION = 0.01;
constexpr double DEFAULT_CONTACT_DEFAULT_BIAS = 0.8;
constexpr double DEFAULT_SLEEP_THRESHOLD_LINEAR = 0.1;
constexpr double DEFAULT_SLEEP_THRESHOLD_ANGULAR = 8.0 * Math_PI / 180;
constexpr double DEFAULT_SLEEP_THRESHOLD_ANGULAR = 8.0 * Math::PI / 180;
constexpr double DEFAULT_SOLVER_ITERATIONS = 8;
} // namespace
@ -98,23 +98,23 @@ JoltSpace3D::JoltSpace3D(JPH::JobSystem *p_job_system) :
layers(new JoltLayers()),
contact_listener(new JoltContactListener3D(this)),
physics_system(new JPH::PhysicsSystem()) {
physics_system->Init((JPH::uint)JoltProjectSettings::get_max_bodies(), 0, (JPH::uint)JoltProjectSettings::get_max_pairs(), (JPH::uint)JoltProjectSettings::get_max_contact_constraints(), *layers, *layers, *layers);
physics_system->Init((JPH::uint)JoltProjectSettings::max_bodies, 0, (JPH::uint)JoltProjectSettings::max_body_pairs, (JPH::uint)JoltProjectSettings::max_contact_constraints, *layers, *layers, *layers);
JPH::PhysicsSettings settings;
settings.mBaumgarte = JoltProjectSettings::get_baumgarte_stabilization_factor();
settings.mSpeculativeContactDistance = JoltProjectSettings::get_speculative_contact_distance();
settings.mPenetrationSlop = JoltProjectSettings::get_penetration_slop();
settings.mLinearCastThreshold = JoltProjectSettings::get_ccd_movement_threshold();
settings.mLinearCastMaxPenetration = JoltProjectSettings::get_ccd_max_penetration();
settings.mBodyPairCacheMaxDeltaPositionSq = JoltProjectSettings::get_body_pair_cache_distance_sq();
settings.mBodyPairCacheCosMaxDeltaRotationDiv2 = JoltProjectSettings::get_body_pair_cache_angle_cos_div2();
settings.mNumVelocitySteps = (JPH::uint)JoltProjectSettings::get_simulation_velocity_steps();
settings.mNumPositionSteps = (JPH::uint)JoltProjectSettings::get_simulation_position_steps();
settings.mMinVelocityForRestitution = JoltProjectSettings::get_bounce_velocity_threshold();
settings.mTimeBeforeSleep = JoltProjectSettings::get_sleep_time_threshold();
settings.mPointVelocitySleepThreshold = JoltProjectSettings::get_sleep_velocity_threshold();
settings.mUseBodyPairContactCache = JoltProjectSettings::is_body_pair_contact_cache_enabled();
settings.mAllowSleeping = JoltProjectSettings::is_sleep_allowed();
settings.mBaumgarte = JoltProjectSettings::baumgarte_stabilization_factor;
settings.mSpeculativeContactDistance = JoltProjectSettings::speculative_contact_distance;
settings.mPenetrationSlop = JoltProjectSettings::penetration_slop;
settings.mLinearCastThreshold = JoltProjectSettings::ccd_movement_threshold;
settings.mLinearCastMaxPenetration = JoltProjectSettings::ccd_max_penetration;
settings.mBodyPairCacheMaxDeltaPositionSq = JoltProjectSettings::body_pair_cache_distance_sq;
settings.mBodyPairCacheCosMaxDeltaRotationDiv2 = JoltProjectSettings::body_pair_cache_angle_cos_div2;
settings.mNumVelocitySteps = (JPH::uint)JoltProjectSettings::simulation_velocity_steps;
settings.mNumPositionSteps = (JPH::uint)JoltProjectSettings::simulation_position_steps;
settings.mMinVelocityForRestitution = JoltProjectSettings::bounce_velocity_threshold;
settings.mTimeBeforeSleep = JoltProjectSettings::sleep_time_threshold;
settings.mPointVelocitySleepThreshold = JoltProjectSettings::sleep_velocity_threshold;
settings.mUseBodyPairContactCache = JoltProjectSettings::body_pair_contact_cache_enabled;
settings.mAllowSleeping = JoltProjectSettings::sleep_allowed;
physics_system->SetPhysicsSettings(settings);
physics_system->SetGravity(JPH::Vec3::sZero());
@ -122,7 +122,7 @@ JoltSpace3D::JoltSpace3D(JPH::JobSystem *p_job_system) :
physics_system->SetSoftBodyContactListener(contact_listener);
physics_system->SetCombineFriction([](const JPH::Body &p_body1, const JPH::SubShapeID &p_sub_shape_id1, const JPH::Body &p_body2, const JPH::SubShapeID &p_sub_shape_id2) {
return ABS(MIN(p_body1.GetFriction(), p_body2.GetFriction()));
return Math::abs(MIN(p_body1.GetFriction(), p_body2.GetFriction()));
});
physics_system->SetCombineRestitution([](const JPH::Body &p_body1, const JPH::SubShapeID &p_sub_shape_id1, const JPH::Body &p_body2, const JPH::SubShapeID &p_sub_shape_id2) {
@ -169,21 +169,21 @@ void JoltSpace3D::step(float p_step) {
WARN_PRINT_ONCE(vformat("Jolt Physics manifold cache exceeded capacity and contacts were ignored. "
"Consider increasing maximum number of contact constraints in project settings. "
"Maximum number of contact constraints is currently set to %d.",
JoltProjectSettings::get_max_contact_constraints()));
JoltProjectSettings::max_contact_constraints));
}
if ((update_error & JPH::EPhysicsUpdateError::BodyPairCacheFull) != JPH::EPhysicsUpdateError::None) {
WARN_PRINT_ONCE(vformat("Jolt Physics body pair cache exceeded capacity and contacts were ignored. "
"Consider increasing maximum number of body pairs in project settings. "
"Maximum number of body pairs is currently set to %d.",
JoltProjectSettings::get_max_pairs()));
JoltProjectSettings::max_body_pairs));
}
if ((update_error & JPH::EPhysicsUpdateError::ContactConstraintsFull) != JPH::EPhysicsUpdateError::None) {
WARN_PRINT_ONCE(vformat("Jolt Physics contact constraint buffer exceeded capacity and contacts were ignored. "
"Consider increasing maximum number of contact constraints in project settings. "
"Maximum number of contact constraints is currently set to %d.",
JoltProjectSettings::get_max_contact_constraints()));
JoltProjectSettings::max_contact_constraints));
}
_post_step(p_step);
@ -227,7 +227,7 @@ double JoltSpace3D::get_param(PhysicsServer3D::SpaceParameter p_param) const {
return DEFAULT_SLEEP_THRESHOLD_ANGULAR;
}
case PhysicsServer3D::SPACE_PARAM_BODY_TIME_TO_SLEEP: {
return JoltProjectSettings::get_sleep_time_threshold();
return JoltProjectSettings::sleep_time_threshold;
}
case PhysicsServer3D::SPACE_PARAM_SOLVER_ITERATIONS: {
return DEFAULT_SOLVER_ITERATIONS;
@ -353,7 +353,7 @@ JPH::BodyID JoltSpace3D::add_rigid_body(const JoltObject3D &p_object, const JPH:
ERR_PRINT_ONCE(vformat("Failed to create underlying Jolt Physics body for '%s'. "
"Consider increasing maximum number of bodies in project settings. "
"Maximum number of bodies is currently set to %d.",
p_object.to_string(), JoltProjectSettings::get_max_bodies()));
p_object.to_string(), JoltProjectSettings::max_bodies));
return JPH::BodyID();
}
@ -370,7 +370,7 @@ JPH::BodyID JoltSpace3D::add_soft_body(const JoltObject3D &p_object, const JPH::
ERR_PRINT_ONCE(vformat("Failed to create underlying Jolt Physics body for '%s'. "
"Consider increasing maximum number of bodies in project settings. "
"Maximum number of bodies is currently set to %d.",
p_object.to_string(), JoltProjectSettings::get_max_bodies()));
p_object.to_string(), JoltProjectSettings::max_bodies));
return JPH::BodyID();
}

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_SPACE_3D_H
#define JOLT_SPACE_3D_H
#pragma once
#include "jolt_body_accessor_3d.h"
@ -45,8 +44,6 @@
#include "Jolt/Physics/Constraints/Constraint.h"
#include "Jolt/Physics/PhysicsSystem.h"
#include <stdint.h>
class JoltArea3D;
class JoltBody3D;
class JoltContactListener3D;
@ -162,5 +159,3 @@ public:
void set_max_debug_contacts(int p_count);
#endif
};
#endif // JOLT_SPACE_3D_H

View file

@ -64,7 +64,7 @@ constexpr TValue align_up(TValue p_value, TAlignment p_alignment) {
} //namespace
JoltTempAllocator::JoltTempAllocator() :
capacity((uint64_t)JoltProjectSettings::get_temp_memory_b()),
capacity((uint64_t)JoltProjectSettings::temp_memory_b),
base(static_cast<uint8_t *>(JPH::Allocate((size_t)capacity))) {
}
@ -89,7 +89,7 @@ void *JoltTempAllocator::Allocate(uint32_t p_size) {
WARN_PRINT_ONCE(vformat("Jolt Physics temporary memory allocator exceeded capacity of %d MiB. "
"Falling back to slower general-purpose allocator. "
"Consider increasing maximum temporary memory in project settings.",
JoltProjectSettings::get_temp_memory_mib()));
JoltProjectSettings::temp_memory_mib));
ptr = JPH::Allocate(p_size);
}

View file

@ -28,8 +28,7 @@
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/**************************************************************************/
#ifndef JOLT_TEMP_ALLOCATOR_H
#define JOLT_TEMP_ALLOCATOR_H
#pragma once
#include "Jolt/Jolt.h"
@ -49,5 +48,3 @@ public:
virtual void *Allocate(JPH::uint p_size) override;
virtual void Free(void *p_ptr, JPH::uint p_size) override;
};
#endif // JOLT_TEMP_ALLOCATOR_H