Path: blob/master/scene/3d/gpu_particles_collision_3d.cpp
9896 views
/**************************************************************************/1/* gpu_particles_collision_3d.cpp */2/**************************************************************************/3/* This file is part of: */4/* GODOT ENGINE */5/* https://godotengine.org */6/**************************************************************************/7/* Copyright (c) 2014-present Godot Engine contributors (see AUTHORS.md). */8/* Copyright (c) 2007-2014 Juan Linietsky, Ariel Manzur. */9/* */10/* Permission is hereby granted, free of charge, to any person obtaining */11/* a copy of this software and associated documentation files (the */12/* "Software"), to deal in the Software without restriction, including */13/* without limitation the rights to use, copy, modify, merge, publish, */14/* distribute, sublicense, and/or sell copies of the Software, and to */15/* permit persons to whom the Software is furnished to do so, subject to */16/* the following conditions: */17/* */18/* The above copyright notice and this permission notice shall be */19/* included in all copies or substantial portions of the Software. */20/* */21/* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, */22/* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF */23/* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. */24/* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY */25/* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, */26/* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE */27/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */28/**************************************************************************/2930#include "gpu_particles_collision_3d.h"3132#include "core/object/worker_thread_pool.h"33#include "mesh_instance_3d.h"34#include "scene/3d/camera_3d.h"35#include "scene/main/viewport.h"3637void GPUParticlesCollision3D::set_cull_mask(uint32_t p_cull_mask) {38cull_mask = p_cull_mask;39RS::get_singleton()->particles_collision_set_cull_mask(collision, p_cull_mask);40}4142uint32_t GPUParticlesCollision3D::get_cull_mask() const {43return cull_mask;44}4546void GPUParticlesCollision3D::_bind_methods() {47ClassDB::bind_method(D_METHOD("set_cull_mask", "mask"), &GPUParticlesCollision3D::set_cull_mask);48ClassDB::bind_method(D_METHOD("get_cull_mask"), &GPUParticlesCollision3D::get_cull_mask);4950ADD_PROPERTY(PropertyInfo(Variant::INT, "cull_mask", PROPERTY_HINT_LAYERS_3D_RENDER), "set_cull_mask", "get_cull_mask");51}5253GPUParticlesCollision3D::GPUParticlesCollision3D(RS::ParticlesCollisionType p_type) {54collision = RS::get_singleton()->particles_collision_create();55RS::get_singleton()->particles_collision_set_collision_type(collision, p_type);56set_base(collision);57}5859GPUParticlesCollision3D::~GPUParticlesCollision3D() {60ERR_FAIL_NULL(RenderingServer::get_singleton());61RS::get_singleton()->free(collision);62}6364/////////////////////////////////6566void GPUParticlesCollisionSphere3D::_bind_methods() {67ClassDB::bind_method(D_METHOD("set_radius", "radius"), &GPUParticlesCollisionSphere3D::set_radius);68ClassDB::bind_method(D_METHOD("get_radius"), &GPUParticlesCollisionSphere3D::get_radius);6970ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "radius", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_radius", "get_radius");71}7273void GPUParticlesCollisionSphere3D::set_radius(real_t p_radius) {74radius = p_radius;75RS::get_singleton()->particles_collision_set_sphere_radius(_get_collision(), radius);76update_gizmos();77}7879real_t GPUParticlesCollisionSphere3D::get_radius() const {80return radius;81}8283AABB GPUParticlesCollisionSphere3D::get_aabb() const {84return AABB(Vector3(-radius, -radius, -radius), Vector3(radius * 2, radius * 2, radius * 2));85}8687GPUParticlesCollisionSphere3D::GPUParticlesCollisionSphere3D() :88GPUParticlesCollision3D(RS::PARTICLES_COLLISION_TYPE_SPHERE_COLLIDE) {89}9091GPUParticlesCollisionSphere3D::~GPUParticlesCollisionSphere3D() {92}9394///////////////////////////9596void GPUParticlesCollisionBox3D::_bind_methods() {97ClassDB::bind_method(D_METHOD("set_size", "size"), &GPUParticlesCollisionBox3D::set_size);98ClassDB::bind_method(D_METHOD("get_size"), &GPUParticlesCollisionBox3D::get_size);99100ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "size", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_size", "get_size");101}102103#ifndef DISABLE_DEPRECATED104bool GPUParticlesCollisionBox3D::_set(const StringName &p_name, const Variant &p_value) {105if (p_name == "extents") { // Compatibility with Godot 3.x.106set_size((Vector3)p_value * 2);107return true;108}109return false;110}111112bool GPUParticlesCollisionBox3D::_get(const StringName &p_name, Variant &r_property) const {113if (p_name == "extents") { // Compatibility with Godot 3.x.114r_property = size / 2;115return true;116}117return false;118}119#endif // DISABLE_DEPRECATED120121void GPUParticlesCollisionBox3D::set_size(const Vector3 &p_size) {122size = p_size;123RS::get_singleton()->particles_collision_set_box_extents(_get_collision(), size / 2);124update_gizmos();125}126127Vector3 GPUParticlesCollisionBox3D::get_size() const {128return size;129}130131AABB GPUParticlesCollisionBox3D::get_aabb() const {132return AABB(-size / 2, size);133}134135GPUParticlesCollisionBox3D::GPUParticlesCollisionBox3D() :136GPUParticlesCollision3D(RS::PARTICLES_COLLISION_TYPE_BOX_COLLIDE) {137}138139GPUParticlesCollisionBox3D::~GPUParticlesCollisionBox3D() {140}141142///////////////////////////////143///////////////////////////144145void GPUParticlesCollisionSDF3D::_find_meshes(const AABB &p_aabb, Node *p_at_node, List<PlotMesh> &plot_meshes) {146MeshInstance3D *mi = Object::cast_to<MeshInstance3D>(p_at_node);147if (mi && mi->is_visible_in_tree()) {148if ((mi->get_layer_mask() & bake_mask) == 0) {149return;150}151152Ref<Mesh> mesh = mi->get_mesh();153if (mesh.is_valid()) {154AABB aabb = mesh->get_aabb();155156Transform3D xf = get_global_transform().affine_inverse() * mi->get_global_transform();157158if (p_aabb.intersects(xf.xform(aabb))) {159PlotMesh pm;160pm.local_xform = xf;161pm.mesh = mesh;162plot_meshes.push_back(pm);163}164}165}166167Node3D *s = Object::cast_to<Node3D>(p_at_node);168if (s) {169if (s->is_visible_in_tree()) {170Array meshes = p_at_node->call("get_meshes");171for (int i = 0; i < meshes.size(); i += 2) {172Transform3D mxf = meshes[i];173Ref<Mesh> mesh = meshes[i + 1];174if (mesh.is_null()) {175continue;176}177178AABB aabb = mesh->get_aabb();179180Transform3D xf = get_global_transform().affine_inverse() * (s->get_global_transform() * mxf);181182if (p_aabb.intersects(xf.xform(aabb))) {183PlotMesh pm;184pm.local_xform = xf;185pm.mesh = mesh;186plot_meshes.push_back(pm);187}188}189}190}191192for (int i = 0; i < p_at_node->get_child_count(); i++) {193Node *child = p_at_node->get_child(i);194_find_meshes(p_aabb, child, plot_meshes);195}196}197198uint32_t GPUParticlesCollisionSDF3D::_create_bvh(LocalVector<BVH> &bvh_tree, FacePos *p_faces, uint32_t p_face_count, const Face3 *p_triangles, float p_thickness) {199if (p_face_count == 1) {200return BVH::LEAF_BIT | p_faces[0].index;201}202203uint32_t index = bvh_tree.size();204{205BVH bvh;206207for (uint32_t i = 0; i < p_face_count; i++) {208const Face3 &f = p_triangles[p_faces[i].index];209AABB aabb(f.vertex[0], Vector3());210aabb.expand_to(f.vertex[1]);211aabb.expand_to(f.vertex[2]);212if (p_thickness > 0.0) {213Vector3 normal = p_triangles[p_faces[i].index].get_plane().normal;214aabb.expand_to(f.vertex[0] - normal * p_thickness);215aabb.expand_to(f.vertex[1] - normal * p_thickness);216aabb.expand_to(f.vertex[2] - normal * p_thickness);217}218if (i == 0) {219bvh.bounds = aabb;220} else {221bvh.bounds.merge_with(aabb);222}223}224bvh_tree.push_back(bvh);225}226227uint32_t middle = p_face_count / 2;228229SortArray<FacePos, FaceSort> s;230s.compare.axis = bvh_tree[index].bounds.get_longest_axis_index();231s.sort(p_faces, p_face_count);232233uint32_t left = _create_bvh(bvh_tree, p_faces, middle, p_triangles, p_thickness);234uint32_t right = _create_bvh(bvh_tree, p_faces + middle, p_face_count - middle, p_triangles, p_thickness);235236bvh_tree[index].children[0] = left;237bvh_tree[index].children[1] = right;238239return index;240}241242static _FORCE_INLINE_ real_t Vector3_dot2(const Vector3 &p_vec3) {243return p_vec3.dot(p_vec3);244}245246void GPUParticlesCollisionSDF3D::_find_closest_distance(const Vector3 &p_pos, const BVH *p_bvh, uint32_t p_bvh_cell, const Face3 *p_triangles, float p_thickness, float &r_closest_distance) {247if (p_bvh_cell & BVH::LEAF_BIT) {248p_bvh_cell &= BVH::LEAF_MASK; //remove bit249250Vector3 point = p_pos;251Plane p = p_triangles[p_bvh_cell].get_plane();252float d = p.distance_to(point);253float inside_d = 1e20;254if (d < 0 && d > -p_thickness) {255//inside planes, do this in 2D256257Vector3 x_axis = (p_triangles[p_bvh_cell].vertex[0] - p_triangles[p_bvh_cell].vertex[1]).normalized();258Vector3 y_axis = p.normal.cross(x_axis).normalized();259260Vector2 points[3];261for (int i = 0; i < 3; i++) {262points[i] = Vector2(x_axis.dot(p_triangles[p_bvh_cell].vertex[i]), y_axis.dot(p_triangles[p_bvh_cell].vertex[i]));263}264265Vector2 p2d = Vector2(x_axis.dot(point), y_axis.dot(point));266267{268// https://www.shadertoy.com/view/XsXSz4269270Vector2 e0 = points[1] - points[0];271Vector2 e1 = points[2] - points[1];272Vector2 e2 = points[0] - points[2];273274Vector2 v0 = p2d - points[0];275Vector2 v1 = p2d - points[1];276Vector2 v2 = p2d - points[2];277278Vector2 pq0 = v0 - e0 * CLAMP(v0.dot(e0) / e0.dot(e0), 0.0, 1.0);279Vector2 pq1 = v1 - e1 * CLAMP(v1.dot(e1) / e1.dot(e1), 0.0, 1.0);280Vector2 pq2 = v2 - e2 * CLAMP(v2.dot(e2) / e2.dot(e2), 0.0, 1.0);281282float s = SIGN(e0.x * e2.y - e0.y * e2.x);283Vector2 d2 = Vector2(pq0.dot(pq0), s * (v0.x * e0.y - v0.y * e0.x)).min(Vector2(pq1.dot(pq1), s * (v1.x * e1.y - v1.y * e1.x))).min(Vector2(pq2.dot(pq2), s * (v2.x * e2.y - v2.y * e2.x)));284285inside_d = -Math::sqrt(d2.x) * SIGN(d2.y);286}287288//make sure distance to planes is not shorter if inside289if (inside_d < 0) {290inside_d = MAX(inside_d, d);291inside_d = MAX(inside_d, -(p_thickness + d));292}293294r_closest_distance = MIN(r_closest_distance, inside_d);295} else {296if (d < 0) {297point -= p.normal * p_thickness; //flatten298}299300// https://iquilezles.org/www/articles/distfunctions/distfunctions.htm301Vector3 a = p_triangles[p_bvh_cell].vertex[0];302Vector3 b = p_triangles[p_bvh_cell].vertex[1];303Vector3 c = p_triangles[p_bvh_cell].vertex[2];304305Vector3 ba = b - a;306Vector3 pa = point - a;307Vector3 cb = c - b;308Vector3 pb = point - b;309Vector3 ac = a - c;310Vector3 pc = point - c;311Vector3 nor = ba.cross(ac);312313inside_d = Math::sqrt(314(SIGN(ba.cross(nor).dot(pa)) + SIGN(cb.cross(nor).dot(pb)) + SIGN(ac.cross(nor).dot(pc)) < 2.0)315? MIN(MIN(316Vector3_dot2(ba * CLAMP(ba.dot(pa) / Vector3_dot2(ba), 0.0, 1.0) - pa),317Vector3_dot2(cb * CLAMP(cb.dot(pb) / Vector3_dot2(cb), 0.0, 1.0) - pb)),318Vector3_dot2(ac * CLAMP(ac.dot(pc) / Vector3_dot2(ac), 0.0, 1.0) - pc))319: nor.dot(pa) * nor.dot(pa) / Vector3_dot2(nor));320321r_closest_distance = MIN(r_closest_distance, inside_d);322}323324} else {325bool pass = true;326if (!p_bvh[p_bvh_cell].bounds.has_point(p_pos)) {327//outside, find closest point328Vector3 he = p_bvh[p_bvh_cell].bounds.size * 0.5;329Vector3 center = p_bvh[p_bvh_cell].bounds.position + he;330331Vector3 rel = (p_pos - center).abs();332Vector3 closest = rel.min(he);333float d = rel.distance_to(closest);334335if (d >= r_closest_distance) {336pass = false; //already closer than this aabb, discard337}338}339340if (pass) {341_find_closest_distance(p_pos, p_bvh, p_bvh[p_bvh_cell].children[0], p_triangles, p_thickness, r_closest_distance);342_find_closest_distance(p_pos, p_bvh, p_bvh[p_bvh_cell].children[1], p_triangles, p_thickness, r_closest_distance);343}344}345}346347void GPUParticlesCollisionSDF3D::_compute_sdf_z(uint32_t p_z, ComputeSDFParams *params) {348int32_t z_ofs = p_z * params->size.y * params->size.x;349for (int32_t y = 0; y < params->size.y; y++) {350int32_t y_ofs = z_ofs + y * params->size.x;351for (int32_t x = 0; x < params->size.x; x++) {352int32_t x_ofs = y_ofs + x;353float &cell = params->cells[x_ofs];354355Vector3 pos = params->cell_offset + Vector3(x, y, p_z) * params->cell_size;356357cell = 1e20;358359_find_closest_distance(pos, params->bvh, 0, params->triangles, params->thickness, cell);360}361}362}363364void GPUParticlesCollisionSDF3D::_compute_sdf(ComputeSDFParams *params) {365WorkerThreadPool::GroupID group_task = WorkerThreadPool::get_singleton()->add_template_group_task(this, &GPUParticlesCollisionSDF3D::_compute_sdf_z, params, params->size.z);366while (!WorkerThreadPool::get_singleton()->is_group_task_completed(group_task)) {367OS::get_singleton()->delay_usec(10000);368if (bake_step_function) {369bake_step_function(WorkerThreadPool::get_singleton()->get_group_processed_element_count(group_task) * 100 / params->size.z, "Baking SDF");370}371}372WorkerThreadPool::get_singleton()->wait_for_group_task_completion(group_task);373}374375Vector3i GPUParticlesCollisionSDF3D::get_estimated_cell_size() const {376static const int subdivs[RESOLUTION_MAX] = { 16, 32, 64, 128, 256, 512 };377int subdiv = subdivs[get_resolution()];378379AABB aabb(-size / 2, size);380381float cell_size = aabb.get_longest_axis_size() / float(subdiv);382383Vector3i sdf_size = Vector3i(aabb.size / cell_size);384sdf_size = sdf_size.maxi(1);385return sdf_size;386}387388Ref<Image> GPUParticlesCollisionSDF3D::bake() {389static const int subdivs[RESOLUTION_MAX] = { 16, 32, 64, 128, 256, 512 };390int subdiv = subdivs[get_resolution()];391392AABB aabb(-size / 2, size);393394float cell_size = aabb.get_longest_axis_size() / float(subdiv);395396Vector3i sdf_size = Vector3i(aabb.size / cell_size);397sdf_size = sdf_size.maxi(1);398399if (bake_begin_function) {400bake_begin_function(100);401}402403aabb.size = Vector3(sdf_size) * cell_size;404405List<PlotMesh> plot_meshes;406_find_meshes(aabb, get_parent(), plot_meshes);407408LocalVector<Face3> faces;409410if (bake_step_function) {411bake_step_function(0, "Finding Meshes");412}413414for (const PlotMesh &pm : plot_meshes) {415for (int i = 0; i < pm.mesh->get_surface_count(); i++) {416if (pm.mesh->surface_get_primitive_type(i) != Mesh::PRIMITIVE_TRIANGLES) {417continue; //only triangles418}419420Array a = pm.mesh->surface_get_arrays(i);421422Vector<Vector3> vertices = a[Mesh::ARRAY_VERTEX];423const Vector3 *vr = vertices.ptr();424Vector<int> index = a[Mesh::ARRAY_INDEX];425426if (index.size()) {427int facecount = index.size() / 3;428const int *ir = index.ptr();429430for (int j = 0; j < facecount; j++) {431Face3 face;432433for (int k = 0; k < 3; k++) {434face.vertex[k] = pm.local_xform.xform(vr[ir[j * 3 + k]]);435}436437//test against original bounds438if (!Geometry3D::triangle_box_overlap(aabb.get_center(), aabb.size * 0.5, face.vertex)) {439continue;440}441442faces.push_back(face);443}444445} else {446int facecount = vertices.size() / 3;447448for (int j = 0; j < facecount; j++) {449Face3 face;450451for (int k = 0; k < 3; k++) {452face.vertex[k] = pm.local_xform.xform(vr[j * 3 + k]);453}454455//test against original bounds456if (!Geometry3D::triangle_box_overlap(aabb.get_center(), aabb.size * 0.5, face.vertex)) {457continue;458}459460faces.push_back(face);461}462}463}464}465466//compute bvh467if (faces.size() <= 1) {468ERR_PRINT("No faces detected during GPUParticlesCollisionSDF3D bake. Check whether there are visible meshes matching the bake mask within its extents.");469if (bake_end_function) {470bake_end_function();471}472return Ref<Image>();473}474475LocalVector<FacePos> face_pos;476477face_pos.resize(faces.size());478479float th = cell_size * thickness;480481for (uint32_t i = 0; i < faces.size(); i++) {482face_pos[i].index = i;483face_pos[i].center = (faces[i].vertex[0] + faces[i].vertex[1] + faces[i].vertex[2]) / 2;484if (th > 0.0) {485face_pos[i].center -= faces[i].get_plane().normal * th * 0.5;486}487}488489if (bake_step_function) {490bake_step_function(0, "Creating BVH");491}492493LocalVector<BVH> bvh;494495_create_bvh(bvh, face_pos.ptr(), face_pos.size(), faces.ptr(), th);496497Vector<uint8_t> cells_data;498cells_data.resize(sdf_size.z * sdf_size.y * sdf_size.x * (int)sizeof(float));499500if (bake_step_function) {501bake_step_function(0, "Baking SDF");502}503504ComputeSDFParams params;505params.cells = (float *)cells_data.ptrw();506params.size = sdf_size;507params.cell_size = cell_size;508params.cell_offset = aabb.position + Vector3(cell_size * 0.5, cell_size * 0.5, cell_size * 0.5);509params.bvh = bvh.ptr();510params.triangles = faces.ptr();511params.thickness = th;512_compute_sdf(¶ms);513514Ref<Image> ret = Image::create_from_data(sdf_size.x, sdf_size.y * sdf_size.z, false, Image::FORMAT_RF, cells_data);515ret->convert(Image::FORMAT_RH); //convert to half, save space516ret->set_meta("depth", sdf_size.z); //hack, make sure to add to the docs of this function517518if (bake_end_function) {519bake_end_function();520}521522return ret;523}524525PackedStringArray GPUParticlesCollisionSDF3D::get_configuration_warnings() const {526PackedStringArray warnings = GPUParticlesCollision3D::get_configuration_warnings();527528if (bake_mask == 0) {529warnings.push_back(RTR("The Bake Mask has no bits enabled, which means baking will not produce any collision for this GPUParticlesCollisionSDF3D.\nTo resolve this, enable at least one bit in the Bake Mask property."));530}531532return warnings;533}534535void GPUParticlesCollisionSDF3D::_bind_methods() {536ClassDB::bind_method(D_METHOD("set_size", "size"), &GPUParticlesCollisionSDF3D::set_size);537ClassDB::bind_method(D_METHOD("get_size"), &GPUParticlesCollisionSDF3D::get_size);538539ClassDB::bind_method(D_METHOD("set_resolution", "resolution"), &GPUParticlesCollisionSDF3D::set_resolution);540ClassDB::bind_method(D_METHOD("get_resolution"), &GPUParticlesCollisionSDF3D::get_resolution);541542ClassDB::bind_method(D_METHOD("set_texture", "texture"), &GPUParticlesCollisionSDF3D::set_texture);543ClassDB::bind_method(D_METHOD("get_texture"), &GPUParticlesCollisionSDF3D::get_texture);544545ClassDB::bind_method(D_METHOD("set_thickness", "thickness"), &GPUParticlesCollisionSDF3D::set_thickness);546ClassDB::bind_method(D_METHOD("get_thickness"), &GPUParticlesCollisionSDF3D::get_thickness);547548ClassDB::bind_method(D_METHOD("set_bake_mask", "mask"), &GPUParticlesCollisionSDF3D::set_bake_mask);549ClassDB::bind_method(D_METHOD("get_bake_mask"), &GPUParticlesCollisionSDF3D::get_bake_mask);550ClassDB::bind_method(D_METHOD("set_bake_mask_value", "layer_number", "value"), &GPUParticlesCollisionSDF3D::set_bake_mask_value);551ClassDB::bind_method(D_METHOD("get_bake_mask_value", "layer_number"), &GPUParticlesCollisionSDF3D::get_bake_mask_value);552553ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "size", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_size", "get_size");554ADD_PROPERTY(PropertyInfo(Variant::INT, "resolution", PROPERTY_HINT_ENUM, "16,32,64,128,256,512"), "set_resolution", "get_resolution");555ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "thickness", PROPERTY_HINT_RANGE, "0.0,2.0,0.01,suffix:m"), "set_thickness", "get_thickness");556ADD_PROPERTY(PropertyInfo(Variant::INT, "bake_mask", PROPERTY_HINT_LAYERS_3D_RENDER), "set_bake_mask", "get_bake_mask");557ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "texture", PROPERTY_HINT_RESOURCE_TYPE, "Texture3D"), "set_texture", "get_texture");558559BIND_ENUM_CONSTANT(RESOLUTION_16);560BIND_ENUM_CONSTANT(RESOLUTION_32);561BIND_ENUM_CONSTANT(RESOLUTION_64);562BIND_ENUM_CONSTANT(RESOLUTION_128);563BIND_ENUM_CONSTANT(RESOLUTION_256);564BIND_ENUM_CONSTANT(RESOLUTION_512);565BIND_ENUM_CONSTANT(RESOLUTION_MAX);566}567568#ifndef DISABLE_DEPRECATED569bool GPUParticlesCollisionSDF3D::_set(const StringName &p_name, const Variant &p_value) {570if (p_name == "extents") { // Compatibility with Godot 3.x.571set_size((Vector3)p_value * 2);572return true;573}574return false;575}576577bool GPUParticlesCollisionSDF3D::_get(const StringName &p_name, Variant &r_property) const {578if (p_name == "extents") { // Compatibility with Godot 3.x.579r_property = size / 2;580return true;581}582return false;583}584#endif // DISABLE_DEPRECATED585586void GPUParticlesCollisionSDF3D::set_thickness(float p_thickness) {587thickness = p_thickness;588}589590float GPUParticlesCollisionSDF3D::get_thickness() const {591return thickness;592}593594void GPUParticlesCollisionSDF3D::set_size(const Vector3 &p_size) {595size = p_size;596RS::get_singleton()->particles_collision_set_box_extents(_get_collision(), size / 2);597update_gizmos();598}599600Vector3 GPUParticlesCollisionSDF3D::get_size() const {601return size;602}603604void GPUParticlesCollisionSDF3D::set_resolution(Resolution p_resolution) {605resolution = p_resolution;606update_gizmos();607}608609GPUParticlesCollisionSDF3D::Resolution GPUParticlesCollisionSDF3D::get_resolution() const {610return resolution;611}612613void GPUParticlesCollisionSDF3D::set_bake_mask(uint32_t p_mask) {614bake_mask = p_mask;615update_configuration_warnings();616}617618uint32_t GPUParticlesCollisionSDF3D::get_bake_mask() const {619return bake_mask;620}621622void GPUParticlesCollisionSDF3D::set_bake_mask_value(int p_layer_number, bool p_value) {623ERR_FAIL_COND_MSG(p_layer_number < 1 || p_layer_number > 20, vformat("The render layer number (%d) must be between 1 and 20 (inclusive).", p_layer_number));624uint32_t mask = get_bake_mask();625if (p_value) {626mask |= 1 << (p_layer_number - 1);627} else {628mask &= ~(1 << (p_layer_number - 1));629}630set_bake_mask(mask);631}632633bool GPUParticlesCollisionSDF3D::get_bake_mask_value(int p_layer_number) const {634ERR_FAIL_COND_V_MSG(p_layer_number < 1 || p_layer_number > 20, false, vformat("The render layer number (%d) must be between 1 and 20 (inclusive).", p_layer_number));635return bake_mask & (1 << (p_layer_number - 1));636}637638void GPUParticlesCollisionSDF3D::set_texture(const Ref<Texture3D> &p_texture) {639texture = p_texture;640RID tex = texture.is_valid() ? texture->get_rid() : RID();641RS::get_singleton()->particles_collision_set_field_texture(_get_collision(), tex);642}643644Ref<Texture3D> GPUParticlesCollisionSDF3D::get_texture() const {645return texture;646}647648AABB GPUParticlesCollisionSDF3D::get_aabb() const {649return AABB(-size / 2, size);650}651652GPUParticlesCollisionSDF3D::BakeBeginFunc GPUParticlesCollisionSDF3D::bake_begin_function = nullptr;653GPUParticlesCollisionSDF3D::BakeStepFunc GPUParticlesCollisionSDF3D::bake_step_function = nullptr;654GPUParticlesCollisionSDF3D::BakeEndFunc GPUParticlesCollisionSDF3D::bake_end_function = nullptr;655656GPUParticlesCollisionSDF3D::GPUParticlesCollisionSDF3D() :657GPUParticlesCollision3D(RS::PARTICLES_COLLISION_TYPE_SDF_COLLIDE) {658}659660GPUParticlesCollisionSDF3D::~GPUParticlesCollisionSDF3D() {661}662663////////////////////////////664////////////////////////////665666void GPUParticlesCollisionHeightField3D::_notification(int p_what) {667switch (p_what) {668case NOTIFICATION_INTERNAL_PROCESS: {669if (update_mode == UPDATE_MODE_ALWAYS) {670RS::get_singleton()->particles_collision_height_field_update(_get_collision());671}672673if (follow_camera_mode && get_viewport()) {674Camera3D *cam = get_viewport()->get_camera_3d();675if (cam) {676Transform3D xform = get_global_transform();677Vector3 x_axis = xform.basis.get_column(Vector3::AXIS_X).normalized();678Vector3 z_axis = xform.basis.get_column(Vector3::AXIS_Z).normalized();679float x_len = xform.basis.get_scale().x;680float z_len = xform.basis.get_scale().z;681682Vector3 cam_pos = cam->get_global_transform().origin;683Transform3D new_xform = xform;684685while (x_axis.dot(cam_pos - new_xform.origin) > x_len) {686new_xform.origin += x_axis * x_len;687}688while (x_axis.dot(cam_pos - new_xform.origin) < -x_len) {689new_xform.origin -= x_axis * x_len;690}691692while (z_axis.dot(cam_pos - new_xform.origin) > z_len) {693new_xform.origin += z_axis * z_len;694}695while (z_axis.dot(cam_pos - new_xform.origin) < -z_len) {696new_xform.origin -= z_axis * z_len;697}698699if (new_xform != xform) {700set_global_transform(new_xform);701RS::get_singleton()->particles_collision_height_field_update(_get_collision());702}703}704}705} break;706707case NOTIFICATION_TRANSFORM_CHANGED: {708RS::get_singleton()->particles_collision_height_field_update(_get_collision());709} break;710}711}712713void GPUParticlesCollisionHeightField3D::_bind_methods() {714ClassDB::bind_method(D_METHOD("set_size", "size"), &GPUParticlesCollisionHeightField3D::set_size);715ClassDB::bind_method(D_METHOD("get_size"), &GPUParticlesCollisionHeightField3D::get_size);716717ClassDB::bind_method(D_METHOD("set_resolution", "resolution"), &GPUParticlesCollisionHeightField3D::set_resolution);718ClassDB::bind_method(D_METHOD("get_resolution"), &GPUParticlesCollisionHeightField3D::get_resolution);719720ClassDB::bind_method(D_METHOD("set_update_mode", "update_mode"), &GPUParticlesCollisionHeightField3D::set_update_mode);721ClassDB::bind_method(D_METHOD("get_update_mode"), &GPUParticlesCollisionHeightField3D::get_update_mode);722723ClassDB::bind_method(D_METHOD("set_heightfield_mask", "heightfield_mask"), &GPUParticlesCollisionHeightField3D::set_heightfield_mask);724ClassDB::bind_method(D_METHOD("get_heightfield_mask"), &GPUParticlesCollisionHeightField3D::get_heightfield_mask);725726ClassDB::bind_method(D_METHOD("set_heightfield_mask_value", "layer_number", "value"), &GPUParticlesCollisionHeightField3D::set_heightfield_mask_value);727ClassDB::bind_method(D_METHOD("get_heightfield_mask_value", "layer_number"), &GPUParticlesCollisionHeightField3D::get_heightfield_mask_value);728729ClassDB::bind_method(D_METHOD("set_follow_camera_enabled", "enabled"), &GPUParticlesCollisionHeightField3D::set_follow_camera_enabled);730ClassDB::bind_method(D_METHOD("is_follow_camera_enabled"), &GPUParticlesCollisionHeightField3D::is_follow_camera_enabled);731732ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "size", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_size", "get_size");733ADD_PROPERTY(PropertyInfo(Variant::INT, "resolution", PROPERTY_HINT_ENUM, "256 (Fastest),512 (Fast),1024 (Average),2048 (Slow),4096 (Slower),8192 (Slowest)"), "set_resolution", "get_resolution");734ADD_PROPERTY(PropertyInfo(Variant::INT, "update_mode", PROPERTY_HINT_ENUM, "When Moved (Fast),Always (Slow)"), "set_update_mode", "get_update_mode");735ADD_PROPERTY(PropertyInfo(Variant::BOOL, "follow_camera_enabled"), "set_follow_camera_enabled", "is_follow_camera_enabled");736ADD_PROPERTY(PropertyInfo(Variant::INT, "heightfield_mask", PROPERTY_HINT_LAYERS_3D_RENDER), "set_heightfield_mask", "get_heightfield_mask");737738BIND_ENUM_CONSTANT(RESOLUTION_256);739BIND_ENUM_CONSTANT(RESOLUTION_512);740BIND_ENUM_CONSTANT(RESOLUTION_1024);741BIND_ENUM_CONSTANT(RESOLUTION_2048);742BIND_ENUM_CONSTANT(RESOLUTION_4096);743BIND_ENUM_CONSTANT(RESOLUTION_8192);744BIND_ENUM_CONSTANT(RESOLUTION_MAX);745746BIND_ENUM_CONSTANT(UPDATE_MODE_WHEN_MOVED);747BIND_ENUM_CONSTANT(UPDATE_MODE_ALWAYS);748}749750#ifndef DISABLE_DEPRECATED751bool GPUParticlesCollisionHeightField3D::_set(const StringName &p_name, const Variant &p_value) {752if (p_name == "extents") { // Compatibility with Godot 3.x.753set_size((Vector3)p_value * 2);754return true;755}756return false;757}758759bool GPUParticlesCollisionHeightField3D::_get(const StringName &p_name, Variant &r_property) const {760if (p_name == "extents") { // Compatibility with Godot 3.x.761r_property = size / 2;762return true;763}764return false;765}766#endif // DISABLE_DEPRECATED767768void GPUParticlesCollisionHeightField3D::set_size(const Vector3 &p_size) {769size = p_size;770RS::get_singleton()->particles_collision_set_box_extents(_get_collision(), size / 2);771update_gizmos();772RS::get_singleton()->particles_collision_height_field_update(_get_collision());773}774775Vector3 GPUParticlesCollisionHeightField3D::get_size() const {776return size;777}778779void GPUParticlesCollisionHeightField3D::set_resolution(Resolution p_resolution) {780resolution = p_resolution;781RS::get_singleton()->particles_collision_set_height_field_resolution(_get_collision(), RS::ParticlesCollisionHeightfieldResolution(resolution));782update_gizmos();783RS::get_singleton()->particles_collision_height_field_update(_get_collision());784}785786GPUParticlesCollisionHeightField3D::Resolution GPUParticlesCollisionHeightField3D::get_resolution() const {787return resolution;788}789790void GPUParticlesCollisionHeightField3D::set_update_mode(UpdateMode p_update_mode) {791update_mode = p_update_mode;792set_process_internal(follow_camera_mode || update_mode == UPDATE_MODE_ALWAYS);793}794795GPUParticlesCollisionHeightField3D::UpdateMode GPUParticlesCollisionHeightField3D::get_update_mode() const {796return update_mode;797}798799void GPUParticlesCollisionHeightField3D::set_heightfield_mask(uint32_t p_heightfield_mask) {800heightfield_mask = p_heightfield_mask;801RS::get_singleton()->particles_collision_set_height_field_mask(_get_collision(), p_heightfield_mask);802}803804uint32_t GPUParticlesCollisionHeightField3D::get_heightfield_mask() const {805return heightfield_mask;806}807808void GPUParticlesCollisionHeightField3D::set_heightfield_mask_value(int p_layer_number, bool p_value) {809ERR_FAIL_COND_MSG(p_layer_number < 1, "Render layer number must be between 1 and 20 inclusive.");810ERR_FAIL_COND_MSG(p_layer_number > 20, "Render layer number must be between 1 and 20 inclusive.");811uint32_t mask = get_heightfield_mask();812if (p_value) {813mask |= 1 << (p_layer_number - 1);814} else {815mask &= ~(1 << (p_layer_number - 1));816}817set_heightfield_mask(mask);818}819820bool GPUParticlesCollisionHeightField3D::get_heightfield_mask_value(int p_layer_number) const {821ERR_FAIL_COND_V_MSG(p_layer_number < 1, false, "Render layer number must be between 1 and 20 inclusive.");822ERR_FAIL_COND_V_MSG(p_layer_number > 20, false, "Render layer number must be between 1 and 20 inclusive.");823return heightfield_mask & (1 << (p_layer_number - 1));824}825826void GPUParticlesCollisionHeightField3D::set_follow_camera_enabled(bool p_enabled) {827follow_camera_mode = p_enabled;828set_process_internal(follow_camera_mode || update_mode == UPDATE_MODE_ALWAYS);829}830831bool GPUParticlesCollisionHeightField3D::is_follow_camera_enabled() const {832return follow_camera_mode;833}834835AABB GPUParticlesCollisionHeightField3D::get_aabb() const {836return AABB(-size / 2, size);837}838839GPUParticlesCollisionHeightField3D::GPUParticlesCollisionHeightField3D() :840GPUParticlesCollision3D(RS::PARTICLES_COLLISION_TYPE_HEIGHTFIELD_COLLIDE) {841}842843GPUParticlesCollisionHeightField3D::~GPUParticlesCollisionHeightField3D() {844}845846////////////////////////////847////////////////////////////848849void GPUParticlesAttractor3D::set_cull_mask(uint32_t p_cull_mask) {850cull_mask = p_cull_mask;851RS::get_singleton()->particles_collision_set_cull_mask(collision, p_cull_mask);852}853854uint32_t GPUParticlesAttractor3D::get_cull_mask() const {855return cull_mask;856}857858void GPUParticlesAttractor3D::set_strength(real_t p_strength) {859strength = p_strength;860RS::get_singleton()->particles_collision_set_attractor_strength(collision, p_strength);861}862863real_t GPUParticlesAttractor3D::get_strength() const {864return strength;865}866867void GPUParticlesAttractor3D::set_attenuation(real_t p_attenuation) {868attenuation = p_attenuation;869RS::get_singleton()->particles_collision_set_attractor_attenuation(collision, p_attenuation);870}871872real_t GPUParticlesAttractor3D::get_attenuation() const {873return attenuation;874}875876void GPUParticlesAttractor3D::set_directionality(real_t p_directionality) {877directionality = p_directionality;878RS::get_singleton()->particles_collision_set_attractor_directionality(collision, p_directionality);879update_gizmos();880}881882real_t GPUParticlesAttractor3D::get_directionality() const {883return directionality;884}885886void GPUParticlesAttractor3D::_bind_methods() {887ClassDB::bind_method(D_METHOD("set_cull_mask", "mask"), &GPUParticlesAttractor3D::set_cull_mask);888ClassDB::bind_method(D_METHOD("get_cull_mask"), &GPUParticlesAttractor3D::get_cull_mask);889890ClassDB::bind_method(D_METHOD("set_strength", "strength"), &GPUParticlesAttractor3D::set_strength);891ClassDB::bind_method(D_METHOD("get_strength"), &GPUParticlesAttractor3D::get_strength);892893ClassDB::bind_method(D_METHOD("set_attenuation", "attenuation"), &GPUParticlesAttractor3D::set_attenuation);894ClassDB::bind_method(D_METHOD("get_attenuation"), &GPUParticlesAttractor3D::get_attenuation);895896ClassDB::bind_method(D_METHOD("set_directionality", "amount"), &GPUParticlesAttractor3D::set_directionality);897ClassDB::bind_method(D_METHOD("get_directionality"), &GPUParticlesAttractor3D::get_directionality);898899ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "strength", PROPERTY_HINT_RANGE, "-128,128,0.01,or_greater,or_less"), "set_strength", "get_strength");900ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "attenuation", PROPERTY_HINT_EXP_EASING, "0,8,0.01"), "set_attenuation", "get_attenuation");901ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "directionality", PROPERTY_HINT_RANGE, "0,1,0.01"), "set_directionality", "get_directionality");902ADD_PROPERTY(PropertyInfo(Variant::INT, "cull_mask", PROPERTY_HINT_LAYERS_3D_RENDER), "set_cull_mask", "get_cull_mask");903}904905GPUParticlesAttractor3D::GPUParticlesAttractor3D(RS::ParticlesCollisionType p_type) {906collision = RS::get_singleton()->particles_collision_create();907RS::get_singleton()->particles_collision_set_collision_type(collision, p_type);908set_base(collision);909}910GPUParticlesAttractor3D::~GPUParticlesAttractor3D() {911ERR_FAIL_NULL(RenderingServer::get_singleton());912RS::get_singleton()->free(collision);913}914915/////////////////////////////////916917void GPUParticlesAttractorSphere3D::_bind_methods() {918ClassDB::bind_method(D_METHOD("set_radius", "radius"), &GPUParticlesAttractorSphere3D::set_radius);919ClassDB::bind_method(D_METHOD("get_radius"), &GPUParticlesAttractorSphere3D::get_radius);920921ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "radius", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_radius", "get_radius");922}923924void GPUParticlesAttractorSphere3D::set_radius(real_t p_radius) {925radius = p_radius;926RS::get_singleton()->particles_collision_set_sphere_radius(_get_collision(), radius);927update_gizmos();928}929930real_t GPUParticlesAttractorSphere3D::get_radius() const {931return radius;932}933934AABB GPUParticlesAttractorSphere3D::get_aabb() const {935return AABB(Vector3(-radius, -radius, -radius), Vector3(radius * 2, radius * 2, radius * 2));936}937938GPUParticlesAttractorSphere3D::GPUParticlesAttractorSphere3D() :939GPUParticlesAttractor3D(RS::PARTICLES_COLLISION_TYPE_SPHERE_ATTRACT) {940}941942GPUParticlesAttractorSphere3D::~GPUParticlesAttractorSphere3D() {943}944945///////////////////////////946947void GPUParticlesAttractorBox3D::_bind_methods() {948ClassDB::bind_method(D_METHOD("set_size", "size"), &GPUParticlesAttractorBox3D::set_size);949ClassDB::bind_method(D_METHOD("get_size"), &GPUParticlesAttractorBox3D::get_size);950951ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "size", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_size", "get_size");952}953954#ifndef DISABLE_DEPRECATED955bool GPUParticlesAttractorBox3D::_set(const StringName &p_name, const Variant &p_value) {956if (p_name == "extents") { // Compatibility with Godot 3.x.957set_size((Vector3)p_value * 2);958return true;959}960return false;961}962963bool GPUParticlesAttractorBox3D::_get(const StringName &p_name, Variant &r_property) const {964if (p_name == "extents") { // Compatibility with Godot 3.x.965r_property = size / 2;966return true;967}968return false;969}970#endif // DISABLE_DEPRECATED971972void GPUParticlesAttractorBox3D::set_size(const Vector3 &p_size) {973size = p_size;974RS::get_singleton()->particles_collision_set_box_extents(_get_collision(), size / 2);975update_gizmos();976}977978Vector3 GPUParticlesAttractorBox3D::get_size() const {979return size;980}981982AABB GPUParticlesAttractorBox3D::get_aabb() const {983return AABB(-size / 2, size);984}985986GPUParticlesAttractorBox3D::GPUParticlesAttractorBox3D() :987GPUParticlesAttractor3D(RS::PARTICLES_COLLISION_TYPE_BOX_ATTRACT) {988}989990GPUParticlesAttractorBox3D::~GPUParticlesAttractorBox3D() {991}992993///////////////////////////994995void GPUParticlesAttractorVectorField3D::_bind_methods() {996ClassDB::bind_method(D_METHOD("set_size", "size"), &GPUParticlesAttractorVectorField3D::set_size);997ClassDB::bind_method(D_METHOD("get_size"), &GPUParticlesAttractorVectorField3D::get_size);998999ClassDB::bind_method(D_METHOD("set_texture", "texture"), &GPUParticlesAttractorVectorField3D::set_texture);1000ClassDB::bind_method(D_METHOD("get_texture"), &GPUParticlesAttractorVectorField3D::get_texture);10011002ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "size", PROPERTY_HINT_RANGE, "0.01,1024,0.01,or_greater,suffix:m"), "set_size", "get_size");1003ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "texture", PROPERTY_HINT_RESOURCE_TYPE, "Texture3D"), "set_texture", "get_texture");1004}10051006#ifndef DISABLE_DEPRECATED1007bool GPUParticlesAttractorVectorField3D::_set(const StringName &p_name, const Variant &p_value) {1008if (p_name == "extents") { // Compatibility with Godot 3.x.1009set_size((Vector3)p_value * 2);1010return true;1011}1012return false;1013}10141015bool GPUParticlesAttractorVectorField3D::_get(const StringName &p_name, Variant &r_property) const {1016if (p_name == "extents") { // Compatibility with Godot 3.x.1017r_property = size / 2;1018return true;1019}1020return false;1021}1022#endif // DISABLE_DEPRECATED10231024void GPUParticlesAttractorVectorField3D::set_size(const Vector3 &p_size) {1025size = p_size;1026RS::get_singleton()->particles_collision_set_box_extents(_get_collision(), size / 2);1027update_gizmos();1028}10291030Vector3 GPUParticlesAttractorVectorField3D::get_size() const {1031return size;1032}10331034void GPUParticlesAttractorVectorField3D::set_texture(const Ref<Texture3D> &p_texture) {1035texture = p_texture;1036RID tex = texture.is_valid() ? texture->get_rid() : RID();1037RS::get_singleton()->particles_collision_set_field_texture(_get_collision(), tex);1038}10391040Ref<Texture3D> GPUParticlesAttractorVectorField3D::get_texture() const {1041return texture;1042}10431044AABB GPUParticlesAttractorVectorField3D::get_aabb() const {1045return AABB(-size / 2, size);1046}10471048GPUParticlesAttractorVectorField3D::GPUParticlesAttractorVectorField3D() :1049GPUParticlesAttractor3D(RS::PARTICLES_COLLISION_TYPE_VECTOR_FIELD_ATTRACT) {1050}10511052GPUParticlesAttractorVectorField3D::~GPUParticlesAttractorVectorField3D() {1053}105410551056