Made it compile in Godot 4
- Made a bunch of changes to comply with Godot 4 API - Use Godot's Vector3i and add the missing stuff with helper functions - Transvoxel uses custom attributes API, the old way would not work - Wrap MeshOptimizer in a unique namespace (see build script why) - Added clang-format file for the module as some rules now differ - Prevent thirdparty code and lookup tables from being clang-formatted - Very likely full of runtime bugs that need fixingmaster
parent
758aa07280
commit
922f361cb0
|
@ -0,0 +1,193 @@
|
|||
# Commented out parameters are those with the same value as base LLVM style.
|
||||
# We can uncomment them if we want to change their value, or enforce the
|
||||
# chosen value in case the base style changes (last sync: Clang 13.0).
|
||||
---
|
||||
### General config, applies to all languages ###
|
||||
BasedOnStyle: LLVM
|
||||
AccessModifierOffset: -4
|
||||
AlignAfterOpenBracket: DontAlign
|
||||
# AlignArrayOfStructures: None
|
||||
# AlignConsecutiveMacros: None
|
||||
# AlignConsecutiveAssignments: None
|
||||
# AlignConsecutiveBitFields: None
|
||||
# AlignConsecutiveDeclarations: None
|
||||
# AlignEscapedNewlines: Right
|
||||
AlignOperands: DontAlign
|
||||
AlignTrailingComments: false
|
||||
# AllowAllArgumentsOnNextLine: true
|
||||
# AllowAllConstructorInitializersOnNextLine: true
|
||||
AllowAllParametersOfDeclarationOnNextLine: false
|
||||
|
||||
# TODO I want this, but if I enable it, enums will always end up with a line break before the opening brace,
|
||||
# even if I set `BreakBeforeBraces: Attach` or specify `BraceWrapping`...
|
||||
# AllowShortEnumsOnASingleLine: false
|
||||
|
||||
# AllowShortBlocksOnASingleLine: Never
|
||||
# AllowShortCaseLabelsOnASingleLine: false
|
||||
AllowShortFunctionsOnASingleLine: Empty
|
||||
# AllowShortLambdasOnASingleLine: All
|
||||
# AllowShortIfStatementsOnASingleLine: Never
|
||||
# AllowShortLoopsOnASingleLine: false
|
||||
# AlwaysBreakAfterDefinitionReturnType: None
|
||||
# AlwaysBreakAfterReturnType: None
|
||||
# AlwaysBreakBeforeMultilineStrings: false
|
||||
# AlwaysBreakTemplateDeclarations: MultiLine
|
||||
# AttributeMacros:
|
||||
# - __capability
|
||||
# BinPackArguments: true
|
||||
# BinPackParameters: true
|
||||
#BraceWrapping:
|
||||
# AfterCaseLabel: false
|
||||
# AfterClass: false
|
||||
# AfterControlStatement: Never
|
||||
# AfterEnum: true
|
||||
# AfterFunction: false
|
||||
# AfterNamespace: false
|
||||
# AfterObjCDeclaration: false
|
||||
# AfterStruct: false
|
||||
# AfterUnion: false
|
||||
# AfterExternBlock: false
|
||||
# BeforeCatch: false
|
||||
# BeforeElse: false
|
||||
# BeforeLambdaBody: false
|
||||
# BeforeWhile: false
|
||||
# IndentBraces: false
|
||||
# SplitEmptyFunction: true
|
||||
# SplitEmptyRecord: true
|
||||
# SplitEmptyNamespace: true
|
||||
# BreakBeforeBinaryOperators: None
|
||||
# BreakBeforeConceptDeclarations: true
|
||||
# BreakBeforeBraces: Attach
|
||||
# BreakBeforeInheritanceComma: false
|
||||
# BreakInheritanceList: BeforeColon
|
||||
# BreakBeforeTernaryOperators: true
|
||||
# BreakConstructorInitializersBeforeComma: false
|
||||
BreakConstructorInitializers: AfterColon
|
||||
# BreakStringLiterals: true
|
||||
ColumnLimit: 120 # Sorry but I can't stand longer lines
|
||||
# CommentPragmas: '^ IWYU pragma:'
|
||||
# CompactNamespaces: false
|
||||
ConstructorInitializerAllOnOneLineOrOnePerLine: true
|
||||
ConstructorInitializerIndentWidth: 8
|
||||
ContinuationIndentWidth: 8
|
||||
Cpp11BracedListStyle: false
|
||||
# DeriveLineEnding: true
|
||||
# DerivePointerAlignment: false
|
||||
# DisableFormat: false
|
||||
# EmptyLineAfterAccessModifier: Never
|
||||
# EmptyLineBeforeAccessModifier: LogicalBlock
|
||||
# ExperimentalAutoDetectBinPacking: false
|
||||
# FixNamespaceComments: true
|
||||
# ForEachMacros:
|
||||
# - foreach
|
||||
# - Q_FOREACH
|
||||
# - BOOST_FOREACH
|
||||
# IfMacros:
|
||||
# - KJ_IF_MAYBE
|
||||
# IncludeBlocks: Preserve
|
||||
IncludeCategories:
|
||||
- Regex: '".*"'
|
||||
Priority: 1
|
||||
- Regex: '^<.*\.h>'
|
||||
Priority: 2
|
||||
- Regex: '^<.*'
|
||||
Priority: 3
|
||||
# IncludeIsMainRegex: '(Test)?$'
|
||||
# IncludeIsMainSourceRegex: ''
|
||||
# IndentAccessModifiers: false
|
||||
IndentCaseLabels: true
|
||||
# IndentCaseBlocks: false
|
||||
# IndentGotoLabels: true
|
||||
# IndentPPDirectives: None
|
||||
# IndentExternBlock: AfterExternBlock
|
||||
# IndentRequires: false
|
||||
IndentWidth: 4
|
||||
# IndentWrappedFunctionNames: false
|
||||
# InsertTrailingCommas: None
|
||||
# JavaScriptQuotes: Leave
|
||||
# JavaScriptWrapImports: true
|
||||
KeepEmptyLinesAtTheStartOfBlocks: false
|
||||
# LambdaBodyIndentation: Signature
|
||||
# MacroBlockBegin: ''
|
||||
# MacroBlockEnd: ''
|
||||
# MaxEmptyLinesToKeep: 1
|
||||
# NamespaceIndentation: None
|
||||
# PenaltyBreakAssignment: 2
|
||||
# PenaltyBreakBeforeFirstCallParameter: 19
|
||||
# PenaltyBreakComment: 300
|
||||
# PenaltyBreakFirstLessLess: 120
|
||||
# PenaltyBreakString: 1000
|
||||
# PenaltyBreakTemplateDeclaration: 10
|
||||
# PenaltyExcessCharacter: 1000000
|
||||
# PenaltyReturnTypeOnItsOwnLine: 60
|
||||
# PenaltyIndentedWhitespace: 0
|
||||
# PointerAlignment: Right
|
||||
# PPIndentWidth: -1
|
||||
# ReferenceAlignment: Pointer
|
||||
# ReflowComments: true
|
||||
# ShortNamespaceLines: 1
|
||||
# SortIncludes: CaseSensitive
|
||||
# SortJavaStaticImport: Before
|
||||
# SortUsingDeclarations: true
|
||||
# SpaceAfterCStyleCast: false
|
||||
# SpaceAfterLogicalNot: false
|
||||
# SpaceAfterTemplateKeyword: true
|
||||
# SpaceBeforeAssignmentOperators: true
|
||||
# SpaceBeforeCaseColon: false
|
||||
# SpaceBeforeCpp11BracedList: false
|
||||
# SpaceBeforeCtorInitializerColon: true
|
||||
# SpaceBeforeInheritanceColon: true
|
||||
# SpaceBeforeParens: ControlStatements
|
||||
# SpaceAroundPointerQualifiers: Default
|
||||
# SpaceBeforeRangeBasedForLoopColon: true
|
||||
# SpaceInEmptyParentheses: false
|
||||
# SpacesBeforeTrailingComments: 1
|
||||
# SpaceInEmptyBlock: false
|
||||
# SpaceInEmptyParentheses: false
|
||||
# SpacesBeforeTrailingComments: 1
|
||||
# SpacesInAngles: Never
|
||||
# SpacesInContainerLiterals: true
|
||||
# SpacesInConditionalStatement: false
|
||||
# SpacesInContainerLiterals: true
|
||||
# SpacesInCStyleCastParentheses: false
|
||||
## Godot TODO: We'll want to use a min of 1, but we need to see how to fix
|
||||
## our comment capitalization at the same time.
|
||||
SpacesInLineCommentPrefix:
|
||||
Minimum: 0
|
||||
Maximum: -1
|
||||
# SpacesInParentheses: false
|
||||
# SpacesInSquareBrackets: false
|
||||
# SpaceBeforeSquareBrackets: false
|
||||
# BitFieldColonSpacing: Both
|
||||
# StatementAttributeLikeMacros:
|
||||
# - Q_EMIT
|
||||
# StatementMacros:
|
||||
# - Q_UNUSED
|
||||
# - QT_REQUIRE_VERSION
|
||||
TabWidth: 4
|
||||
# UseCRLF: false
|
||||
UseTab: Always
|
||||
# WhitespaceSensitiveMacros:
|
||||
# - STRINGIZE
|
||||
# - PP_STRINGIZE
|
||||
# - BOOST_PP_STRINGIZE
|
||||
# - NS_SWIFT_NAME
|
||||
# - CF_SWIFT_NAME
|
||||
---
|
||||
### C++ specific config ###
|
||||
Language: Cpp
|
||||
Standard: c++17
|
||||
---
|
||||
### ObjC specific config ###
|
||||
Language: ObjC
|
||||
# ObjCBinPackProtocolList: Auto
|
||||
ObjCBlockIndentWidth: 4
|
||||
# ObjCBreakBeforeNestedBlockParam: true
|
||||
# ObjCSpaceAfterProperty: false
|
||||
# ObjCSpaceBeforeProtocolList: true
|
||||
---
|
||||
### Java specific config ###
|
||||
Language: Java
|
||||
# BreakAfterJavaFieldAnnotations: false
|
||||
JavaImportGroups: ['org.godotengine', 'android', 'androidx', 'com.android', 'com.google', 'java', 'javax']
|
||||
...
|
11
SCsub
11
SCsub
|
@ -63,8 +63,15 @@ if env["tools"]:
|
|||
]
|
||||
voxel_files += voxel_editor_files
|
||||
|
||||
# See https://github.com/zeux/meshoptimizer/issues/311
|
||||
env_voxel.Append(CPPDEFINES=["MESHOPTIMIZER_ZYLANN_NEVER_COLLAPSE_BORDERS"])
|
||||
env_voxel.Append(CPPDEFINES=[
|
||||
# See https://github.com/zeux/meshoptimizer/issues/311
|
||||
"MESHOPTIMIZER_ZYLANN_NEVER_COLLAPSE_BORDERS",
|
||||
# Because of the above, the MeshOptimizer library in this module is different to an official one.
|
||||
# Godot 4 includes an official version, which means they would both conflict at linking time.
|
||||
# To prevent this clash we wrap the entire library within an additional namespace.
|
||||
# This should be solved either by solving issue #311 or by porting the module to a dynamic library (GDExtension).
|
||||
"MESHOPTIMIZER_ZYLANN_WRAP_LIBRARY_IN_NAMESPACE"
|
||||
])
|
||||
|
||||
if RUN_TESTS:
|
||||
voxel_files += [
|
||||
|
|
|
@ -30,16 +30,14 @@ namespace Cube {
|
|||
//
|
||||
|
||||
// Ordered as per the cube corners diagram
|
||||
const Vector3 g_corner_position[CORNER_COUNT] = {
|
||||
Vector3(1, 0, 0),
|
||||
Vector3(0, 0, 0),
|
||||
Vector3(0, 0, 1),
|
||||
Vector3(1, 0, 1),
|
||||
Vector3(1, 1, 0),
|
||||
Vector3(0, 1, 0),
|
||||
Vector3(0, 1, 1),
|
||||
Vector3(1, 1, 1)
|
||||
};
|
||||
const Vector3 g_corner_position[CORNER_COUNT] = { Vector3(1, 0, 0), //
|
||||
Vector3(0, 0, 0), //
|
||||
Vector3(0, 0, 1), //
|
||||
Vector3(1, 0, 1), //
|
||||
Vector3(1, 1, 0), //
|
||||
Vector3(0, 1, 0), //
|
||||
Vector3(0, 1, 1), //
|
||||
Vector3(1, 1, 1) };
|
||||
|
||||
const int g_side_quad_triangles[SIDE_COUNT][6] = {
|
||||
{ 0, 2, 1, 0, 3, 2 }, // LEFT (+x)
|
||||
|
@ -66,33 +64,34 @@ const Vector3i g_side_normals[SIDE_COUNT] = {
|
|||
Vector3i(0, 0, 1), // FRONT
|
||||
};
|
||||
|
||||
const float g_side_tangents[SIDE_COUNT][4] = {
|
||||
{ 0.f, 0.f, -1.f, 1.f },
|
||||
{ 0.f, 0.f, 1.f, 1.f },
|
||||
const float g_side_tangents[SIDE_COUNT][4] = { //
|
||||
{ 0.f, 0.f, -1.f, 1.f }, //
|
||||
{ 0.f, 0.f, 1.f, 1.f }, //
|
||||
|
||||
{ 1.f, 0.f, 0.f, 1.f },
|
||||
{ -1.f, 0.f, 0.f, 1.f },
|
||||
{ 1.f, 0.f, 0.f, 1.f }, //
|
||||
{ -1.f, 0.f, 0.f, 1.f }, //
|
||||
|
||||
{ -1.f, 0.f, 0.f, 1.f },
|
||||
{ -1.f, 0.f, 0.f, 1.f }, //
|
||||
{ 1.f, 0.f, 0.f, 1.f }
|
||||
};
|
||||
|
||||
// Corners have same winding, relative to the face's normal
|
||||
const unsigned int g_side_corners[SIDE_COUNT][4] = {
|
||||
{ 3, 0, 4, 7 },
|
||||
{ 1, 2, 6, 5 },
|
||||
{ 1, 0, 3, 2 },
|
||||
{ 4, 5, 6, 7 },
|
||||
{ 0, 1, 5, 4 },
|
||||
{ 2, 3, 7, 6 }
|
||||
//
|
||||
{ 3, 0, 4, 7 }, //
|
||||
{ 1, 2, 6, 5 }, //
|
||||
{ 1, 0, 3, 2 }, //
|
||||
{ 4, 5, 6, 7 }, //
|
||||
{ 0, 1, 5, 4 }, //
|
||||
{ 2, 3, 7, 6 } //
|
||||
};
|
||||
|
||||
const unsigned int g_side_edges[SIDE_COUNT][4] = {
|
||||
{ 3, 7, 11, 4 },
|
||||
{ 1, 6, 9, 5 },
|
||||
{ 0, 1, 2, 3 },
|
||||
{ 8, 9, 10, 11 },
|
||||
{ 0, 5, 8, 4 },
|
||||
const unsigned int g_side_edges[SIDE_COUNT][4] = { //
|
||||
{ 3, 7, 11, 4 }, //
|
||||
{ 1, 6, 9, 5 }, //
|
||||
{ 0, 1, 2, 3 }, //
|
||||
{ 8, 9, 10, 11 }, //
|
||||
{ 0, 5, 8, 4 }, //
|
||||
{ 2, 6, 10, 7 }
|
||||
};
|
||||
|
||||
|
@ -109,38 +108,38 @@ const unsigned int g_side_edges[SIDE_COUNT][4] = {
|
|||
//};
|
||||
|
||||
const Vector3i g_corner_inormals[CORNER_COUNT] = {
|
||||
Vector3i(1, -1, -1),
|
||||
Vector3i(-1, -1, -1),
|
||||
Vector3i(-1, -1, 1),
|
||||
Vector3i(1, -1, 1),
|
||||
Vector3i(1, -1, -1), //
|
||||
Vector3i(-1, -1, -1), //
|
||||
Vector3i(-1, -1, 1), //
|
||||
Vector3i(1, -1, 1), //
|
||||
|
||||
Vector3i(1, 1, -1),
|
||||
Vector3i(-1, 1, -1),
|
||||
Vector3i(-1, 1, 1),
|
||||
Vector3i(1, 1, 1)
|
||||
Vector3i(1, 1, -1), //
|
||||
Vector3i(-1, 1, -1), //
|
||||
Vector3i(-1, 1, 1), //
|
||||
Vector3i(1, 1, 1) //
|
||||
};
|
||||
|
||||
const Vector3i g_edge_inormals[EDGE_COUNT] = {
|
||||
Vector3i(0, -1, -1),
|
||||
Vector3i(-1, -1, 0),
|
||||
Vector3i(0, -1, 1),
|
||||
Vector3i(1, -1, 0),
|
||||
Vector3i(0, -1, -1), //
|
||||
Vector3i(-1, -1, 0), //
|
||||
Vector3i(0, -1, 1), //
|
||||
Vector3i(1, -1, 0), //
|
||||
|
||||
Vector3i(1, 0, -1),
|
||||
Vector3i(-1, 0, -1),
|
||||
Vector3i(-1, 0, 1),
|
||||
Vector3i(1, 0, 1),
|
||||
Vector3i(1, 0, -1), //
|
||||
Vector3i(-1, 0, -1), //
|
||||
Vector3i(-1, 0, 1), //
|
||||
Vector3i(1, 0, 1), //
|
||||
|
||||
Vector3i(0, 1, -1),
|
||||
Vector3i(-1, 1, 0),
|
||||
Vector3i(0, 1, 1),
|
||||
Vector3i(1, 1, 0)
|
||||
Vector3i(0, 1, -1), //
|
||||
Vector3i(-1, 1, 0), //
|
||||
Vector3i(0, 1, 1), //
|
||||
Vector3i(1, 1, 0) //
|
||||
};
|
||||
|
||||
const unsigned int g_edge_corners[EDGE_COUNT][2] = {
|
||||
{ 0, 1 }, { 1, 2 }, { 2, 3 }, { 3, 0 },
|
||||
{ 0, 4 }, { 1, 5 }, { 2, 6 }, { 3, 7 },
|
||||
{ 4, 5 }, { 5, 6 }, { 6, 7 }, { 7, 4 }
|
||||
{ 0, 1 }, { 1, 2 }, { 2, 3 }, { 3, 0 }, //
|
||||
{ 0, 4 }, { 1, 5 }, { 2, 6 }, { 3, 7 }, //
|
||||
{ 4, 5 }, { 5, 6 }, { 6, 7 }, { 7, 4 } //
|
||||
};
|
||||
|
||||
// Order is irrelevant
|
||||
|
@ -178,35 +177,35 @@ const Vector3i g_moore_neighboring_3d[MOORE_NEIGHBORING_3D_COUNT] = {
|
|||
|
||||
// Order is IMPORTANT:
|
||||
// This is used in multithread context, in which we may iterate blocks in XYZ order, to avoid deadlocks.
|
||||
const Vector3i g_ordered_moore_area_3d[MOORE_AREA_3D_COUNT] = {
|
||||
Vector3i(-1, -1, -1),
|
||||
Vector3i(0, -1, -1),
|
||||
Vector3i(1, -1, -1),
|
||||
Vector3i(-1, 0, -1),
|
||||
Vector3i(0, 0, -1),
|
||||
Vector3i(1, 0, -1),
|
||||
Vector3i(-1, 1, -1),
|
||||
Vector3i(0, 1, -1),
|
||||
Vector3i(1, 1, -1),
|
||||
const Vector3i g_ordered_moore_area_3d[MOORE_AREA_3D_COUNT] = { //
|
||||
Vector3i(-1, -1, -1), //
|
||||
Vector3i(0, -1, -1), //
|
||||
Vector3i(1, -1, -1), //
|
||||
Vector3i(-1, 0, -1), //
|
||||
Vector3i(0, 0, -1), //
|
||||
Vector3i(1, 0, -1), //
|
||||
Vector3i(-1, 1, -1), //
|
||||
Vector3i(0, 1, -1), //
|
||||
Vector3i(1, 1, -1), //
|
||||
|
||||
Vector3i(-1, -1, 0),
|
||||
Vector3i(0, -1, 0),
|
||||
Vector3i(1, -1, 0),
|
||||
Vector3i(-1, 0, 0),
|
||||
Vector3i(0, 0, 0),
|
||||
Vector3i(1, 0, 0),
|
||||
Vector3i(-1, 1, 0),
|
||||
Vector3i(0, 1, 0),
|
||||
Vector3i(1, 1, 0),
|
||||
Vector3i(-1, -1, 0), //
|
||||
Vector3i(0, -1, 0), //
|
||||
Vector3i(1, -1, 0), //
|
||||
Vector3i(-1, 0, 0), //
|
||||
Vector3i(0, 0, 0), //
|
||||
Vector3i(1, 0, 0), //
|
||||
Vector3i(-1, 1, 0), //
|
||||
Vector3i(0, 1, 0), //
|
||||
Vector3i(1, 1, 0), //
|
||||
|
||||
Vector3i(-1, -1, 1),
|
||||
Vector3i(0, -1, 1),
|
||||
Vector3i(1, -1, 1),
|
||||
Vector3i(-1, 0, 1),
|
||||
Vector3i(0, 0, 1),
|
||||
Vector3i(1, 0, 1),
|
||||
Vector3i(-1, 1, 1),
|
||||
Vector3i(0, 1, 1),
|
||||
Vector3i(-1, -1, 1), //
|
||||
Vector3i(0, -1, 1), //
|
||||
Vector3i(1, -1, 1), //
|
||||
Vector3i(-1, 0, 1), //
|
||||
Vector3i(0, 0, 1), //
|
||||
Vector3i(1, 0, 1), //
|
||||
Vector3i(-1, 1, 1), //
|
||||
Vector3i(0, 1, 1), //
|
||||
Vector3i(1, 1, 1)
|
||||
};
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#ifndef VOXEL_STRING_NAMES_H
|
||||
#define VOXEL_STRING_NAMES_H
|
||||
|
||||
#include <core/string_name.h>
|
||||
#include <core/string/string_name.h>
|
||||
|
||||
class VoxelStringNames {
|
||||
private:
|
||||
|
|
|
@ -17,7 +17,7 @@ Ongoing development
|
|||
|
||||
- Fixes
|
||||
- `VoxelBuffer`: frequently creating buffers with always different sizes no longer wastes memory
|
||||
- `Voxel`: properties were not refreshed when changing `geometry_type`
|
||||
- `Voxel`: properties of the inspector were not refreshed when changing `geometry_type`
|
||||
|
||||
|
||||
06/11/2021 - `godot3.4`
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
#include "voxel_raycast_result.h"
|
||||
|
||||
Vector3 VoxelRaycastResult::_b_get_position() const {
|
||||
return position.to_vec3();
|
||||
Vector3i VoxelRaycastResult::_b_get_position() const {
|
||||
return position;
|
||||
}
|
||||
|
||||
Vector3 VoxelRaycastResult::_b_get_previous_position() const {
|
||||
return previous_position.to_vec3();
|
||||
Vector3i VoxelRaycastResult::_b_get_previous_position() const {
|
||||
return previous_position;
|
||||
}
|
||||
|
||||
float VoxelRaycastResult::_b_get_distance() const {
|
||||
|
@ -19,5 +19,5 @@ void VoxelRaycastResult::_bind_methods() {
|
|||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "position"), "", "get_position");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::VECTOR3, "previous_position"), "", "get_previous_position");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "distance"), "", "get_distance");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "distance"), "", "get_distance");
|
||||
}
|
||||
|
|
|
@ -2,19 +2,19 @@
|
|||
#define VOXEL_RAYCAST_RESULT_H
|
||||
|
||||
#include "../util/math/vector3i.h"
|
||||
#include <core/reference.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
|
||||
// This class exists only to make the script API nicer.
|
||||
class VoxelRaycastResult : public Reference {
|
||||
GDCLASS(VoxelRaycastResult, Reference)
|
||||
class VoxelRaycastResult : public RefCounted {
|
||||
GDCLASS(VoxelRaycastResult, RefCounted)
|
||||
public:
|
||||
Vector3i position;
|
||||
Vector3i previous_position;
|
||||
float distance_along_ray;
|
||||
|
||||
private:
|
||||
Vector3 _b_get_position() const;
|
||||
Vector3 _b_get_previous_position() const;
|
||||
Vector3i _b_get_position() const;
|
||||
Vector3i _b_get_previous_position() const;
|
||||
float _b_get_distance() const;
|
||||
|
||||
static void _bind_methods();
|
||||
|
|
|
@ -89,7 +89,7 @@ float VoxelTool::get_voxel_f(Vector3i pos) const {
|
|||
}
|
||||
|
||||
void VoxelTool::set_voxel(Vector3i pos, uint64_t v) {
|
||||
Box3i box(pos, Vector3i(1));
|
||||
Box3i box(pos, Vector3i(1, 1, 1));
|
||||
if (!is_area_editable(box)) {
|
||||
PRINT_VERBOSE("Area not editable");
|
||||
return;
|
||||
|
@ -99,7 +99,7 @@ void VoxelTool::set_voxel(Vector3i pos, uint64_t v) {
|
|||
}
|
||||
|
||||
void VoxelTool::set_voxel_f(Vector3i pos, float v) {
|
||||
Box3i box(pos, Vector3i(1));
|
||||
Box3i box(pos, Vector3i(1, 1, 1));
|
||||
if (!is_area_editable(box)) {
|
||||
PRINT_VERBOSE("Area not editable");
|
||||
return;
|
||||
|
@ -109,7 +109,7 @@ void VoxelTool::set_voxel_f(Vector3i pos, float v) {
|
|||
}
|
||||
|
||||
void VoxelTool::do_point(Vector3i pos) {
|
||||
Box3i box(pos, Vector3i(1));
|
||||
Box3i box(pos, Vector3i(1, 1, 1));
|
||||
if (!is_area_editable(box)) {
|
||||
return;
|
||||
}
|
||||
|
@ -179,7 +179,8 @@ inline float sdf_blend(float src_value, float dst_value, VoxelTool::Mode mode) {
|
|||
void VoxelTool::do_sphere(Vector3 center, float radius) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
const Box3i box(Vector3i::from_floored(center) - Vector3i(Math::floor(radius)), Vector3i(Math::ceil(radius) * 2));
|
||||
const Box3i box(Vector3iUtil::from_floored(center) - Vector3iUtil::create(Math::floor(radius)),
|
||||
Vector3iUtil::create(Math::ceil(radius) * 2));
|
||||
|
||||
if (!is_area_editable(box)) {
|
||||
PRINT_VERBOSE("Area not editable");
|
||||
|
@ -188,7 +189,7 @@ void VoxelTool::do_sphere(Vector3 center, float radius) {
|
|||
|
||||
if (_channel == VoxelBuffer::CHANNEL_SDF) {
|
||||
box.for_each_cell([this, center, radius](Vector3i pos) {
|
||||
float d = _sdf_scale * sdf_sphere(pos.to_vec3(), center, radius);
|
||||
float d = _sdf_scale * sdf_sphere(pos, center, radius);
|
||||
_set_voxel_f(pos, sdf_blend(d, get_voxel_f(pos), _mode));
|
||||
});
|
||||
|
||||
|
@ -196,7 +197,7 @@ void VoxelTool::do_sphere(Vector3 center, float radius) {
|
|||
int value = _mode == MODE_REMOVE ? _eraser_value : _value;
|
||||
|
||||
box.for_each_cell([this, center, radius, value](Vector3i pos) {
|
||||
float d = pos.to_vec3().distance_to(center);
|
||||
float d = Vector3(pos).distance_to(center);
|
||||
if (d <= radius) {
|
||||
_set_voxel(pos, value);
|
||||
}
|
||||
|
@ -231,7 +232,7 @@ void VoxelTool::sdf_stamp_erase(Ref<VoxelBuffer> stamp, Vector3i pos) {
|
|||
|
||||
void VoxelTool::do_box(Vector3i begin, Vector3i end) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
Vector3i::sort_min_max(begin, end);
|
||||
Vector3iUtil::sort_min_max(begin, end);
|
||||
Box3i box = Box3i::from_min_max(begin, end + Vector3i(1, 1, 1));
|
||||
|
||||
if (!is_area_editable(box)) {
|
||||
|
@ -336,8 +337,8 @@ void VoxelTool::_bind_methods() {
|
|||
ADD_PROPERTY(PropertyInfo(Variant::INT, "mode", PROPERTY_HINT_ENUM, "Add,Remove,Set"), "set_mode", "get_mode");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "sdf_scale"), "set_sdf_scale", "get_sdf_scale");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "texture_index"), "set_texture_index", "get_texture_index");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "texture_opacity"), "set_texture_opacity", "get_texture_opacity");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "texture_falloff"), "set_texture_falloff", "get_texture_falloff");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "texture_opacity"), "set_texture_opacity", "get_texture_opacity");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "texture_falloff"), "set_texture_falloff", "get_texture_falloff");
|
||||
|
||||
BIND_ENUM_CONSTANT(MODE_ADD);
|
||||
BIND_ENUM_CONSTANT(MODE_REMOVE);
|
||||
|
|
|
@ -11,12 +11,11 @@ class VoxelBuffer;
|
|||
|
||||
namespace VoxelToolOps {
|
||||
|
||||
template <typename Op, typename Shape>
|
||||
struct SdfOperation16bit {
|
||||
template <typename Op, typename Shape> struct SdfOperation16bit {
|
||||
Op op;
|
||||
Shape shape;
|
||||
inline uint16_t operator()(Vector3i pos, uint16_t sdf) const {
|
||||
return norm_to_u16(op(u16_to_norm(sdf), shape(pos.to_vec3())));
|
||||
return norm_to_u16(op(u16_to_norm(sdf), shape(Vector3(pos))));
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -68,7 +67,7 @@ struct TextureBlendSphereOp {
|
|||
}
|
||||
|
||||
inline void operator()(Vector3i pos, uint16_t &indices, uint16_t &weights) const {
|
||||
const float distance_squared = pos.to_vec3().distance_squared_to(center);
|
||||
const float distance_squared = Vector3(pos).distance_squared_to(center);
|
||||
if (distance_squared < radius_squared) {
|
||||
const float distance_from_radius = radius - Math::sqrt(distance_squared);
|
||||
const float target_weight = tp.opacity * clamp(tp.sharpness * (distance_from_radius / radius), 0.f, 1.f);
|
||||
|
@ -84,10 +83,10 @@ struct TextureBlendSphereOp {
|
|||
// High-level generic voxel edition utility.
|
||||
// Ease of use comes at cost.
|
||||
// It's not a class to instantiate alone, get it from the voxel objects you want to work with
|
||||
class VoxelTool : public Reference {
|
||||
GDCLASS(VoxelTool, Reference)
|
||||
class VoxelTool : public RefCounted {
|
||||
GDCLASS(VoxelTool, RefCounted)
|
||||
public:
|
||||
enum Mode {
|
||||
enum Mode { //
|
||||
MODE_ADD,
|
||||
MODE_REMOVE,
|
||||
MODE_SET,
|
||||
|
@ -138,8 +137,8 @@ public:
|
|||
void sdf_stamp_erase(Ref<VoxelBuffer> stamp, Vector3i pos);
|
||||
|
||||
virtual void copy(Vector3i pos, Ref<VoxelBuffer> dst, uint8_t channels_mask) const;
|
||||
virtual void paste(Vector3i pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask,
|
||||
uint64_t mask_value);
|
||||
virtual void paste(
|
||||
Vector3i pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask, uint64_t mask_value);
|
||||
|
||||
virtual Ref<VoxelRaycastResult> raycast(Vector3 pos, Vector3 dir, float max_distance, uint32_t collision_mask);
|
||||
|
||||
|
@ -164,53 +163,53 @@ private:
|
|||
// Bindings to convert to more specialized C++ types and handle virtuality,
|
||||
// cuz I don't know if it works by binding straight
|
||||
|
||||
uint64_t _b_get_voxel(Vector3 pos) {
|
||||
return get_voxel(Vector3i::from_floored(pos));
|
||||
uint64_t _b_get_voxel(Vector3i pos) {
|
||||
return get_voxel(pos);
|
||||
}
|
||||
float _b_get_voxel_f(Vector3 pos) {
|
||||
return get_voxel_f(Vector3i::from_floored(pos));
|
||||
float _b_get_voxel_f(Vector3i pos) {
|
||||
return get_voxel_f(pos);
|
||||
}
|
||||
void _b_set_voxel(Vector3 pos, uint64_t v) {
|
||||
set_voxel(Vector3i::from_floored(pos), v);
|
||||
void _b_set_voxel(Vector3i pos, uint64_t v) {
|
||||
set_voxel(pos, v);
|
||||
}
|
||||
void _b_set_voxel_f(Vector3 pos, float v) {
|
||||
set_voxel_f(Vector3i::from_floored(pos), v);
|
||||
void _b_set_voxel_f(Vector3i pos, float v) {
|
||||
set_voxel_f(pos, v);
|
||||
}
|
||||
Ref<VoxelRaycastResult> _b_raycast(Vector3 pos, Vector3 dir, float max_distance, uint32_t collision_mask) {
|
||||
return raycast(pos, dir, max_distance, collision_mask);
|
||||
}
|
||||
void _b_do_point(Vector3 pos) {
|
||||
do_point(Vector3i::from_floored(pos));
|
||||
void _b_do_point(Vector3i pos) {
|
||||
do_point(pos);
|
||||
}
|
||||
void _b_do_line(Vector3 begin, Vector3 end) {
|
||||
do_line(Vector3i::from_floored(begin), Vector3i::from_floored(end));
|
||||
do_line(Vector3iUtil::from_floored(begin), Vector3iUtil::from_floored(end));
|
||||
}
|
||||
void _b_do_circle(Vector3 pos, float radius, Vector3 direction) {
|
||||
do_circle(Vector3i::from_floored(pos), radius, Vector3i::from_floored(direction));
|
||||
do_circle(Vector3iUtil::from_floored(pos), radius, Vector3iUtil::from_floored(direction));
|
||||
}
|
||||
void _b_do_sphere(Vector3 pos, float radius) {
|
||||
do_sphere(pos, radius);
|
||||
}
|
||||
void _b_do_box(Vector3 begin, Vector3 end) {
|
||||
do_box(Vector3i::from_floored(begin), Vector3i::from_floored(end));
|
||||
void _b_do_box(Vector3i begin, Vector3i end) {
|
||||
do_box(begin, end);
|
||||
}
|
||||
void _b_copy(Vector3 pos, Ref<Reference> voxels, int channel_mask) {
|
||||
copy(Vector3i::from_floored(pos), voxels, channel_mask);
|
||||
void _b_copy(Vector3i pos, Ref<VoxelBuffer> voxels, int channel_mask) {
|
||||
copy(pos, voxels, channel_mask);
|
||||
}
|
||||
void _b_paste(Vector3 pos, Ref<Reference> voxels, int channels_mask, int64_t mask_value) {
|
||||
void _b_paste(Vector3i pos, Ref<VoxelBuffer> voxels, int channels_mask, int64_t mask_value) {
|
||||
// TODO May need two functions, one masked, one not masked, or add a parameter, but it breaks compat
|
||||
paste(Vector3i::from_floored(pos), voxels, channels_mask, mask_value > 0xffffffff, mask_value);
|
||||
paste(pos, voxels, channels_mask, mask_value > 0xffffffff, mask_value);
|
||||
}
|
||||
|
||||
Variant _b_get_voxel_metadata(Vector3 pos) const {
|
||||
return get_voxel_metadata(Vector3i::from_floored(pos));
|
||||
Variant _b_get_voxel_metadata(Vector3i pos) const {
|
||||
return get_voxel_metadata(pos);
|
||||
}
|
||||
void _b_set_voxel_metadata(Vector3 pos, Variant meta) {
|
||||
return set_voxel_metadata(Vector3i::from_floored(pos), meta);
|
||||
void _b_set_voxel_metadata(Vector3i pos, Variant meta) {
|
||||
return set_voxel_metadata(pos, meta);
|
||||
}
|
||||
|
||||
bool _b_is_area_editable(AABB box) const {
|
||||
return is_area_editable(Box3i(Vector3i::from_floored(box.position), Vector3i::from_floored(box.size)));
|
||||
return is_area_editable(Box3i(Vector3iUtil::from_floored(box.position), Vector3iUtil::from_floored(box.size)));
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -24,14 +24,13 @@ void VoxelToolBuffer::do_sphere(Vector3 center, float radius) {
|
|||
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
Box3i box(Vector3i::from_floored(center) - Vector3i(Math::floor(radius)), Vector3i(Math::ceil(radius) * 2));
|
||||
Box3i box(Vector3iUtil::from_floored(center) - Vector3iUtil::create(Math::floor(radius)),
|
||||
Vector3iUtil::create(Math::ceil(radius) * 2));
|
||||
box.clip(Box3i(Vector3i(), _buffer->get_buffer().get_size()));
|
||||
|
||||
_buffer->get_buffer().write_box_2_template<VoxelToolOps::TextureBlendSphereOp, uint16_t, uint16_t>(box,
|
||||
VoxelBufferInternal::CHANNEL_INDICES,
|
||||
VoxelBufferInternal::CHANNEL_WEIGHTS,
|
||||
VoxelToolOps::TextureBlendSphereOp(center, radius, _texture_params),
|
||||
Vector3i());
|
||||
VoxelBufferInternal::CHANNEL_INDICES, VoxelBufferInternal::CHANNEL_WEIGHTS,
|
||||
VoxelToolOps::TextureBlendSphereOp(center, radius, _texture_params), Vector3i());
|
||||
|
||||
_post_edit(box);
|
||||
}
|
||||
|
@ -71,8 +70,8 @@ Variant VoxelToolBuffer::get_voxel_metadata(Vector3i pos) const {
|
|||
return _buffer->get_buffer().get_voxel_metadata(pos);
|
||||
}
|
||||
|
||||
void VoxelToolBuffer::paste(Vector3i p_pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask,
|
||||
uint64_t mask_value) {
|
||||
void VoxelToolBuffer::paste(
|
||||
Vector3i p_pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask, uint64_t mask_value) {
|
||||
// TODO Support `use_mask` properly
|
||||
if (use_mask) {
|
||||
mask_value = 0xffffffffffffffff;
|
||||
|
|
|
@ -9,13 +9,12 @@
|
|||
#include "../util/voxel_raycast.h"
|
||||
#include "funcs.h"
|
||||
|
||||
#include <scene/3d/collision_shape.h>
|
||||
#include <scene/3d/mesh_instance.h>
|
||||
#include <scene/3d/physics_body.h>
|
||||
#include <scene/3d/collision_shape_3d.h>
|
||||
#include <scene/3d/mesh_instance_3d.h>
|
||||
#include <scene/3d/physics_body_3d.h>
|
||||
#include <scene/main/timer.h>
|
||||
|
||||
VoxelToolLodTerrain::VoxelToolLodTerrain(VoxelLodTerrain *terrain) :
|
||||
_terrain(terrain) {
|
||||
VoxelToolLodTerrain::VoxelToolLodTerrain(VoxelLodTerrain *terrain) : _terrain(terrain) {
|
||||
ERR_FAIL_COND(terrain == nullptr);
|
||||
// At the moment, only LOD0 is supported.
|
||||
// Don't destroy the terrain while a voxel tool still references it
|
||||
|
@ -26,9 +25,8 @@ bool VoxelToolLodTerrain::is_area_editable(const Box3i &box) const {
|
|||
return _terrain->is_area_editable(box);
|
||||
}
|
||||
|
||||
template <typename Volume_F>
|
||||
float get_sdf_interpolated(const Volume_F &f, Vector3 pos) {
|
||||
const Vector3i c = Vector3i::from_floored(pos);
|
||||
template <typename Volume_F> float get_sdf_interpolated(const Volume_F &f, Vector3 pos) {
|
||||
const Vector3i c = Vector3iUtil::from_floored(pos);
|
||||
|
||||
const float s000 = f(Vector3i(c.x, c.y, c.z));
|
||||
const float s100 = f(Vector3i(c.x + 1, c.y, c.z));
|
||||
|
@ -149,13 +147,12 @@ Ref<VoxelRaycastResult> VoxelToolLodTerrain::raycast(
|
|||
};
|
||||
|
||||
VolumeSampler sampler{ _terrain };
|
||||
d = hit_distance_prev + approximate_distance_to_isosurface_binary_search(sampler,
|
||||
pos + dir * hit_distance_prev,
|
||||
dir, hit_distance - hit_distance_prev,
|
||||
_raycast_binary_search_iterations);
|
||||
d = hit_distance_prev +
|
||||
approximate_distance_to_isosurface_binary_search(sampler, pos + dir * hit_distance_prev, dir,
|
||||
hit_distance - hit_distance_prev, _raycast_binary_search_iterations);
|
||||
}
|
||||
|
||||
res.instance();
|
||||
res.instantiate();
|
||||
res->position = hit_pos;
|
||||
res->previous_position = prev_pos;
|
||||
res->distance_along_ray = d;
|
||||
|
@ -223,9 +220,8 @@ void VoxelToolLodTerrain::do_sphere(Vector3 center, float radius) {
|
|||
VOXEL_PROFILE_SCOPE();
|
||||
ERR_FAIL_COND(_terrain == nullptr);
|
||||
|
||||
const Box3i box = Box3i(
|
||||
Vector3i::from_floored(center) - Vector3i(Math::floor(radius)),
|
||||
Vector3i(Math::ceil(radius) * 2))
|
||||
const Box3i box = Box3i(Vector3iUtil::from_floored(center) - Vector3iUtil::create(Math::floor(radius)),
|
||||
Vector3iUtil::create(Math::ceil(radius) * 2))
|
||||
.clipped(_terrain->get_voxel_bounds());
|
||||
|
||||
if (!is_area_editable(box)) {
|
||||
|
@ -257,11 +253,9 @@ void VoxelToolLodTerrain::do_sphere(Vector3 center, float radius) {
|
|||
_post_edit(box);
|
||||
}
|
||||
|
||||
template <typename Op_T>
|
||||
class VoxelToolAsyncEdit : public IVoxelTask {
|
||||
template <typename Op_T> class VoxelToolAsyncEdit : public IVoxelTask {
|
||||
public:
|
||||
VoxelToolAsyncEdit(Op_T op, std::shared_ptr<VoxelDataLodMap> data) :
|
||||
_op(op), _data(data) {
|
||||
VoxelToolAsyncEdit(Op_T op, std::shared_ptr<VoxelDataLodMap> data) : _op(op), _data(data) {
|
||||
_tracker = gd_make_shared<VoxelAsyncDependencyTracker>(1);
|
||||
}
|
||||
|
||||
|
@ -283,7 +277,9 @@ public:
|
|||
}
|
||||
|
||||
void apply_result() override {}
|
||||
std::shared_ptr<VoxelAsyncDependencyTracker> get_tracker() { return _tracker; }
|
||||
std::shared_ptr<VoxelAsyncDependencyTracker> get_tracker() {
|
||||
return _tracker;
|
||||
}
|
||||
|
||||
private:
|
||||
Op_T _op;
|
||||
|
@ -295,9 +291,8 @@ private:
|
|||
void VoxelToolLodTerrain::do_sphere_async(Vector3 center, float radius) {
|
||||
ERR_FAIL_COND(_terrain == nullptr);
|
||||
|
||||
const Box3i box = Box3i(
|
||||
Vector3i::from_floored(center) - Vector3i(Math::floor(radius)),
|
||||
Vector3i(Math::ceil(radius) * 2))
|
||||
const Box3i box = Box3i(Vector3iUtil::from_floored(center) - Vector3iUtil::create(Math::floor(radius)),
|
||||
Vector3iUtil::create(Math::ceil(radius) * 2))
|
||||
.clipped(_terrain->get_voxel_bounds());
|
||||
|
||||
if (!is_area_editable(box)) {
|
||||
|
@ -337,12 +332,13 @@ float VoxelToolLodTerrain::get_voxel_f_interpolated(Vector3 position) const {
|
|||
const int channel = get_channel();
|
||||
VoxelLodTerrain *terrain = _terrain;
|
||||
// TODO Optimization: is it worth a making a fast-path for this?
|
||||
return get_sdf_interpolated([terrain, channel](Vector3i ipos) {
|
||||
VoxelSingleValue defval;
|
||||
defval.f = 1.f;
|
||||
VoxelSingleValue value = terrain->get_voxel(ipos, VoxelBufferInternal::CHANNEL_SDF, defval);
|
||||
return value.f;
|
||||
},
|
||||
return get_sdf_interpolated(
|
||||
[terrain, channel](Vector3i ipos) {
|
||||
VoxelSingleValue defval;
|
||||
defval.f = 1.f;
|
||||
VoxelSingleValue value = terrain->get_voxel(ipos, VoxelBufferInternal::CHANNEL_SDF, defval);
|
||||
return value.f;
|
||||
},
|
||||
position);
|
||||
}
|
||||
|
||||
|
@ -389,7 +385,7 @@ void VoxelToolLodTerrain::set_raycast_binary_search_iterations(int iterations) {
|
|||
// the source volume, and turned into a rigidbody.
|
||||
// This is one way of doing it, I don't know if it's the best way (there is rarely a best way)
|
||||
// so there are probably other approaches that could be explored in the future, if they have better performance
|
||||
static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, Node *parent_node, Transform transform,
|
||||
static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, Node *parent_node, Transform3D transform,
|
||||
Ref<VoxelMesher> mesher, Array materials) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
|
@ -407,7 +403,7 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
Ref<VoxelBuffer> source_copy_buffer_ref;
|
||||
{
|
||||
VOXEL_PROFILE_SCOPE_NAMED("Copy");
|
||||
source_copy_buffer_ref.instance();
|
||||
source_copy_buffer_ref.instantiate();
|
||||
source_copy_buffer_ref->create(world_box.size.x, world_box.size.y, world_box.size.z);
|
||||
voxel_tool.copy(world_box.pos, source_copy_buffer_ref, channels_mask);
|
||||
}
|
||||
|
@ -416,7 +412,7 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
// Label distinct voxel groups
|
||||
|
||||
static thread_local std::vector<uint8_t> ccl_output;
|
||||
ccl_output.resize(world_box.size.volume());
|
||||
ccl_output.resize(Vector3iUtil::get_volume(world_box.size));
|
||||
|
||||
unsigned int label_count = 0;
|
||||
|
||||
|
@ -425,7 +421,8 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
VOXEL_PROFILE_SCOPE_NAMED("CCL scan");
|
||||
IslandFinder island_finder;
|
||||
island_finder.scan_3d(
|
||||
Box3i(Vector3i(), world_box.size), [&source_copy_buffer](Vector3i pos) {
|
||||
Box3i(Vector3i(), world_box.size),
|
||||
[&source_copy_buffer](Vector3i pos) {
|
||||
// TODO Can be optimized further with direct access
|
||||
return source_copy_buffer.get_voxel_f(pos.x, pos.y, pos.z, main_channel) < 0.f;
|
||||
},
|
||||
|
@ -494,18 +491,14 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
// Eliminate groups that touch the box border,
|
||||
// because that means we can't tell if they are truly hanging in the air or attached to land further away
|
||||
|
||||
const Vector3i lbmax = world_box.size - Vector3i(1);
|
||||
const Vector3i lbmax = world_box.size - Vector3i(1, 1, 1);
|
||||
for (unsigned int label = 1; label < bounds_per_label.size(); ++label) {
|
||||
CRASH_COND(label >= bounds_per_label.size());
|
||||
Bounds &local_bounds = bounds_per_label[label];
|
||||
ERR_CONTINUE(!local_bounds.valid);
|
||||
|
||||
if (
|
||||
local_bounds.min_pos.x == 0 ||
|
||||
local_bounds.min_pos.y == 0 ||
|
||||
local_bounds.min_pos.z == 0 ||
|
||||
local_bounds.max_pos.x == lbmax.x ||
|
||||
local_bounds.max_pos.y == lbmax.y ||
|
||||
if (local_bounds.min_pos.x == 0 || local_bounds.min_pos.y == 0 || local_bounds.min_pos.z == 0 ||
|
||||
local_bounds.max_pos.x == lbmax.x || local_bounds.max_pos.y == lbmax.y ||
|
||||
local_bounds.max_pos.z == lbmax.z) {
|
||||
//
|
||||
local_bounds.valid = false;
|
||||
|
@ -535,12 +528,13 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
continue;
|
||||
}
|
||||
|
||||
const Vector3i world_pos = world_box.pos + local_bounds.min_pos - Vector3i(min_padding);
|
||||
const Vector3i size = local_bounds.max_pos - local_bounds.min_pos + Vector3i(1 + max_padding + min_padding);
|
||||
const Vector3i world_pos = world_box.pos + local_bounds.min_pos - Vector3iUtil::create(min_padding);
|
||||
const Vector3i size =
|
||||
local_bounds.max_pos - local_bounds.min_pos + Vector3iUtil::create(1 + max_padding + min_padding);
|
||||
|
||||
// TODO We should be able to use `VoxelBufferInternal`, just needs some things exposed
|
||||
Ref<VoxelBuffer> buffer_ref;
|
||||
buffer_ref.instance();
|
||||
buffer_ref.instantiate();
|
||||
buffer_ref->create(size.x, size.y, size.z);
|
||||
|
||||
// Read voxels from the source volume
|
||||
|
@ -549,25 +543,24 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
VoxelBufferInternal &buffer = buffer_ref->get_buffer();
|
||||
|
||||
// Cleanup padding borders
|
||||
const Box3i inner_box(Vector3i(min_padding), buffer.get_size() - Vector3i(min_padding + max_padding));
|
||||
Box3i(Vector3i(), buffer.get_size())
|
||||
.difference(inner_box, [&buffer](Box3i box) {
|
||||
buffer.fill_area_f(1.f, box.pos, box.pos + box.size, main_channel);
|
||||
});
|
||||
const Box3i inner_box(Vector3iUtil::create(min_padding),
|
||||
buffer.get_size() - Vector3iUtil::create(min_padding + max_padding));
|
||||
Box3i(Vector3i(), buffer.get_size()).difference(inner_box, [&buffer](Box3i box) {
|
||||
buffer.fill_area_f(1.f, box.pos, box.pos + box.size, main_channel);
|
||||
});
|
||||
|
||||
// Filter out voxels that don't belong to this label
|
||||
for (int z = local_bounds.min_pos.z; z <= local_bounds.max_pos.z; ++z) {
|
||||
for (int x = local_bounds.min_pos.x; x <= local_bounds.max_pos.x; ++x) {
|
||||
for (int y = local_bounds.min_pos.y; y <= local_bounds.max_pos.y; ++y) {
|
||||
const unsigned int ccl_index = Vector3i(x, y, z).get_zxy_index(world_box.size);
|
||||
const unsigned int ccl_index = Vector3iUtil::get_zxy_index(Vector3i(x, y, z), world_box.size);
|
||||
CRASH_COND(ccl_index >= ccl_output.size());
|
||||
const uint8_t label2 = ccl_output[ccl_index];
|
||||
|
||||
if (label2 != 0 && label != label2) {
|
||||
buffer.set_voxel_f(1.f,
|
||||
min_padding + x - local_bounds.min_pos.x,
|
||||
min_padding + y - local_bounds.min_pos.y,
|
||||
min_padding + z - local_bounds.min_pos.z, main_channel);
|
||||
buffer.set_voxel_f(1.f, min_padding + x - local_bounds.min_pos.x,
|
||||
min_padding + y - local_bounds.min_pos.y, min_padding + z - local_bounds.min_pos.z,
|
||||
main_channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -630,15 +623,15 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
// print_line("//");
|
||||
// }
|
||||
|
||||
const Transform local_transform(Basis(), info.world_pos.to_vec3());
|
||||
const Transform3D local_transform(Basis(), info.world_pos);
|
||||
|
||||
for (int i = 0; i < materials.size(); ++i) {
|
||||
Ref<ShaderMaterial> sm = materials[i];
|
||||
if (sm.is_valid() &&
|
||||
sm->get_shader().is_valid() &&
|
||||
if (sm.is_valid() && sm->get_shader().is_valid() &&
|
||||
sm->get_shader()->has_param(VoxelStringNames::get_singleton()->u_block_local_transform)) {
|
||||
// That parameter should have a valid default value matching the local transform relative to the volume,
|
||||
// which is usually per-instance, but in Godot 3 we have no such feature, so we have to duplicate.
|
||||
// That parameter should have a valid default value matching the local transform relative to the
|
||||
// volume, which is usually per-instance, but in Godot 3 we have no such feature, so we have to
|
||||
// duplicate.
|
||||
sm = sm->duplicate(false);
|
||||
sm->set_shader_param(VoxelStringNames::get_singleton()->u_block_local_transform, local_transform);
|
||||
materials[i] = sm;
|
||||
|
@ -673,34 +666,36 @@ static Array separate_floating_chunks(VoxelTool &voxel_tool, Box3i world_box, No
|
|||
// TODO Option to make multiple convex shapes
|
||||
// TODO Use the fast way. This is slow because of the internal TriangleMesh thing.
|
||||
// TODO Don't create a body if the mesh has no triangles
|
||||
Ref<Shape> shape = mesh->create_convex_shape();
|
||||
Ref<Shape3D> shape = mesh->create_convex_shape();
|
||||
ERR_CONTINUE(shape.is_null());
|
||||
CollisionShape *collision_shape = memnew(CollisionShape);
|
||||
CollisionShape3D *collision_shape = memnew(CollisionShape3D);
|
||||
collision_shape->set_shape(shape);
|
||||
// Center the shape somewhat, because Godot is confusing node origin with center of mass
|
||||
const Vector3i size = local_bounds.max_pos - local_bounds.min_pos + Vector3i(1 + max_padding + min_padding);
|
||||
const Vector3 offset = -size.to_vec3() * 0.5f;
|
||||
collision_shape->set_translation(offset);
|
||||
const Vector3i size =
|
||||
local_bounds.max_pos - local_bounds.min_pos + Vector3iUtil::create(1 + max_padding + min_padding);
|
||||
const Vector3 offset = -Vector3(size) * 0.5f;
|
||||
collision_shape->set_position(offset);
|
||||
|
||||
RigidBody *rigid_body = memnew(RigidBody);
|
||||
RigidDynamicBody3D *rigid_body = memnew(RigidDynamicBody3D);
|
||||
rigid_body->set_transform(transform * local_transform.translated(-offset));
|
||||
rigid_body->add_child(collision_shape);
|
||||
rigid_body->set_mode(RigidBody::MODE_KINEMATIC);
|
||||
rigid_body->set_freeze_mode(RigidDynamicBody3D::FREEZE_MODE_KINEMATIC);
|
||||
rigid_body->set_freeze_enabled(true);
|
||||
|
||||
// Switch to rigid after a short time to workaround clipping with terrain,
|
||||
// because colliders are updated asynchronously
|
||||
Timer *timer = memnew(Timer);
|
||||
timer->set_wait_time(0.2);
|
||||
timer->set_one_shot(true);
|
||||
timer->connect("timeout", rigid_body, "set_mode", varray(RigidBody::MODE_RIGID));
|
||||
timer->connect("timeout", callable_mp(rigid_body, &RigidDynamicBody3D::set_freeze_enabled), varray(false));
|
||||
// Cannot use start() here because it requires to be inside the SceneTree,
|
||||
// and we don't know if it will be after we add to the parent.
|
||||
timer->set_autostart(true);
|
||||
rigid_body->add_child(timer);
|
||||
|
||||
MeshInstance *mesh_instance = memnew(MeshInstance);
|
||||
MeshInstance3D *mesh_instance = memnew(MeshInstance3D);
|
||||
mesh_instance->set_mesh(mesh);
|
||||
mesh_instance->set_translation(offset);
|
||||
mesh_instance->set_position(offset);
|
||||
rigid_body->add_child(mesh_instance);
|
||||
|
||||
parent_node->add_child(rigid_body);
|
||||
|
@ -718,7 +713,8 @@ Array VoxelToolLodTerrain::separate_floating_chunks(AABB world_box, Node *parent
|
|||
Ref<VoxelMesher> mesher = _terrain->get_mesher();
|
||||
Array materials;
|
||||
materials.append(_terrain->get_material());
|
||||
const Box3i int_world_box(Vector3i::from_floored(world_box.position), Vector3i::from_ceiled(world_box.size));
|
||||
const Box3i int_world_box(
|
||||
Vector3iUtil::from_floored(world_box.position), Vector3iUtil::from_ceiled(world_box.size));
|
||||
return ::separate_floating_chunks(
|
||||
*this, int_world_box, parent_node, _terrain->get_global_transform(), mesher, materials);
|
||||
}
|
||||
|
@ -728,9 +724,9 @@ void VoxelToolLodTerrain::_bind_methods() {
|
|||
&VoxelToolLodTerrain::set_raycast_binary_search_iterations);
|
||||
ClassDB::bind_method(D_METHOD("get_raycast_binary_search_iterations"),
|
||||
&VoxelToolLodTerrain::get_raycast_binary_search_iterations);
|
||||
ClassDB::bind_method(D_METHOD("get_voxel_f_interpolated", "position"),
|
||||
&VoxelToolLodTerrain::get_voxel_f_interpolated);
|
||||
ClassDB::bind_method(D_METHOD("separate_floating_chunks", "box", "parent_node"),
|
||||
&VoxelToolLodTerrain::separate_floating_chunks);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("get_voxel_f_interpolated", "position"), &VoxelToolLodTerrain::get_voxel_f_interpolated);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("separate_floating_chunks", "box", "parent_node"), &VoxelToolLodTerrain::separate_floating_chunks);
|
||||
ClassDB::bind_method(D_METHOD("do_sphere_async", "center", "radius"), &VoxelToolLodTerrain::do_sphere_async);
|
||||
}
|
||||
|
|
|
@ -5,10 +5,7 @@
|
|||
#include "../util/godot/funcs.h"
|
||||
#include "../util/voxel_raycast.h"
|
||||
|
||||
#include <core/func_ref.h>
|
||||
|
||||
VoxelToolTerrain::VoxelToolTerrain() {
|
||||
}
|
||||
VoxelToolTerrain::VoxelToolTerrain() {}
|
||||
|
||||
VoxelToolTerrain::VoxelToolTerrain(VoxelTerrain *terrain) {
|
||||
ERR_FAIL_COND(terrain == nullptr);
|
||||
|
@ -22,7 +19,8 @@ bool VoxelToolTerrain::is_area_editable(const Box3i &box) const {
|
|||
return _terrain->get_storage().is_area_fully_loaded(box);
|
||||
}
|
||||
|
||||
Ref<VoxelRaycastResult> VoxelToolTerrain::raycast(Vector3 p_pos, Vector3 p_dir, float p_max_distance, uint32_t p_collision_mask) {
|
||||
Ref<VoxelRaycastResult> VoxelToolTerrain::raycast(
|
||||
Vector3 p_pos, Vector3 p_dir, float p_max_distance, uint32_t p_collision_mask) {
|
||||
// TODO Implement broad-phase on blocks to minimize locking and increase performance
|
||||
|
||||
struct RaycastPredicateColor {
|
||||
|
@ -84,8 +82,8 @@ Ref<VoxelRaycastResult> VoxelToolTerrain::raycast(Vector3 p_pos, Vector3 p_dir,
|
|||
Vector3i hit_pos;
|
||||
Vector3i prev_pos;
|
||||
|
||||
const Transform to_world = _terrain->get_global_transform();
|
||||
const Transform to_local = to_world.affine_inverse();
|
||||
const Transform3D to_world = _terrain->get_global_transform();
|
||||
const Transform3D to_local = to_world.affine_inverse();
|
||||
const Vector3 local_pos = to_local.xform(p_pos);
|
||||
const Vector3 local_dir = to_local.basis.xform(p_dir).normalized();
|
||||
const float to_world_scale = to_world.basis.get_axis(0).length();
|
||||
|
@ -99,8 +97,9 @@ Ref<VoxelRaycastResult> VoxelToolTerrain::raycast(Vector3 p_pos, Vector3 p_dir,
|
|||
RaycastPredicateBlocky predicate{ _terrain->get_storage(), **library_ref, p_collision_mask };
|
||||
float hit_distance;
|
||||
float hit_distance_prev;
|
||||
if (voxel_raycast(local_pos, local_dir, predicate, max_distance, hit_pos, prev_pos, hit_distance, hit_distance_prev)) {
|
||||
res.instance();
|
||||
if (voxel_raycast(local_pos, local_dir, predicate, max_distance, hit_pos, prev_pos, hit_distance,
|
||||
hit_distance_prev)) {
|
||||
res.instantiate();
|
||||
res->position = hit_pos;
|
||||
res->previous_position = prev_pos;
|
||||
res->distance_along_ray = hit_distance * to_world_scale;
|
||||
|
@ -110,8 +109,9 @@ Ref<VoxelRaycastResult> VoxelToolTerrain::raycast(Vector3 p_pos, Vector3 p_dir,
|
|||
RaycastPredicateColor predicate{ _terrain->get_storage() };
|
||||
float hit_distance;
|
||||
float hit_distance_prev;
|
||||
if (voxel_raycast(local_pos, local_dir, predicate, max_distance, hit_pos, prev_pos, hit_distance, hit_distance_prev)) {
|
||||
res.instance();
|
||||
if (voxel_raycast(local_pos, local_dir, predicate, max_distance, hit_pos, prev_pos, hit_distance,
|
||||
hit_distance_prev)) {
|
||||
res.instantiate();
|
||||
res->position = hit_pos;
|
||||
res->previous_position = prev_pos;
|
||||
res->distance_along_ray = hit_distance * to_world_scale;
|
||||
|
@ -121,8 +121,9 @@ Ref<VoxelRaycastResult> VoxelToolTerrain::raycast(Vector3 p_pos, Vector3 p_dir,
|
|||
RaycastPredicateSDF predicate{ _terrain->get_storage() };
|
||||
float hit_distance;
|
||||
float hit_distance_prev;
|
||||
if (voxel_raycast(local_pos, local_dir, predicate, max_distance, hit_pos, prev_pos, hit_distance, hit_distance_prev)) {
|
||||
res.instance();
|
||||
if (voxel_raycast(local_pos, local_dir, predicate, max_distance, hit_pos, prev_pos, hit_distance,
|
||||
hit_distance_prev)) {
|
||||
res.instantiate();
|
||||
res->position = hit_pos;
|
||||
res->previous_position = prev_pos;
|
||||
res->distance_along_ray = hit_distance * to_world_scale;
|
||||
|
@ -141,8 +142,8 @@ void VoxelToolTerrain::copy(Vector3i pos, Ref<VoxelBuffer> dst, uint8_t channels
|
|||
_terrain->get_storage().copy(pos, dst->get_buffer(), channels_mask);
|
||||
}
|
||||
|
||||
void VoxelToolTerrain::paste(Vector3i pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask,
|
||||
uint64_t mask_value) {
|
||||
void VoxelToolTerrain::paste(
|
||||
Vector3i pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask, uint64_t mask_value) {
|
||||
ERR_FAIL_COND(_terrain == nullptr);
|
||||
ERR_FAIL_COND(p_voxels.is_null());
|
||||
if (channels_mask == 0) {
|
||||
|
@ -162,7 +163,8 @@ void VoxelToolTerrain::do_sphere(Vector3 center, float radius) {
|
|||
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
const Box3i box(Vector3i::from_floored(center) - Vector3i(Math::floor(radius)), Vector3i(Math::ceil(radius) * 2));
|
||||
const Box3i box(Vector3iUtil::from_floored(center) - Vector3iUtil::create(Math::floor(radius)),
|
||||
Vector3iUtil::create(Math::ceil(radius) * 2));
|
||||
|
||||
if (!is_area_editable(box)) {
|
||||
PRINT_VERBOSE("Area not editable");
|
||||
|
@ -220,12 +222,13 @@ Variant VoxelToolTerrain::get_voxel_metadata(Vector3i pos) const {
|
|||
|
||||
// Executes a function on random voxels in the provided area, using the type channel.
|
||||
// This allows to implement slow "natural" cellular automata behavior, as can be seen in Minecraft.
|
||||
void VoxelToolTerrain::run_blocky_random_tick(AABB voxel_area, int voxel_count, Ref<FuncRef> callback, int batch_count) const {
|
||||
void VoxelToolTerrain::run_blocky_random_tick(
|
||||
AABB voxel_area, int voxel_count, const Callable &callback, int batch_count) const {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
ERR_FAIL_COND(_terrain == nullptr);
|
||||
ERR_FAIL_COND_MSG(_terrain->get_voxel_library().is_null(),
|
||||
"This function requires a volume using VoxelMesherBlocky");
|
||||
ERR_FAIL_COND_MSG(
|
||||
_terrain->get_voxel_library().is_null(), "This function requires a volume using VoxelMesherBlocky");
|
||||
ERR_FAIL_COND(callback.is_null());
|
||||
ERR_FAIL_COND(batch_count <= 0);
|
||||
ERR_FAIL_COND(voxel_count < 0);
|
||||
|
@ -237,8 +240,8 @@ void VoxelToolTerrain::run_blocky_random_tick(AABB voxel_area, int voxel_count,
|
|||
|
||||
const VoxelLibrary &lib = **_terrain->get_voxel_library();
|
||||
|
||||
const Vector3i min_pos = Vector3i::from_floored(voxel_area.position);
|
||||
const Vector3i max_pos = min_pos + Vector3i::from_floored(voxel_area.size);
|
||||
const Vector3i min_pos = Vector3iUtil::from_floored(voxel_area.position);
|
||||
const Vector3i max_pos = min_pos + Vector3iUtil::from_floored(voxel_area.size);
|
||||
|
||||
VoxelDataMap &map = _terrain->get_storage();
|
||||
|
||||
|
@ -259,10 +262,9 @@ void VoxelToolTerrain::run_blocky_random_tick(AABB voxel_area, int voxel_count,
|
|||
|
||||
// Choose blocks at random
|
||||
for (int bi = 0; bi < block_count; ++bi) {
|
||||
const Vector3i block_pos = min_block_pos + Vector3i(
|
||||
Math::rand() % block_area_size.x,
|
||||
Math::rand() % block_area_size.y,
|
||||
Math::rand() % block_area_size.z);
|
||||
const Vector3i block_pos = min_block_pos +
|
||||
Vector3i(Math::rand() % block_area_size.x, Math::rand() % block_area_size.y,
|
||||
Math::rand() % block_area_size.z);
|
||||
|
||||
const Vector3i block_origin = map.block_to_voxel(block_pos);
|
||||
|
||||
|
@ -287,10 +289,7 @@ void VoxelToolTerrain::run_blocky_random_tick(AABB voxel_area, int voxel_count,
|
|||
// Choose a bunch of voxels at random within the block.
|
||||
// Batching this way improves performance a little by reducing block lookups.
|
||||
for (int vi = 0; vi < batch_count; ++vi) {
|
||||
const Vector3i rpos(
|
||||
Math::rand() & bs_mask,
|
||||
Math::rand() & bs_mask,
|
||||
Math::rand() & bs_mask);
|
||||
const Vector3i rpos(Math::rand() & bs_mask, Math::rand() & bs_mask, Math::rand() & bs_mask);
|
||||
|
||||
const uint64_t v = voxels.get_voxel(rpos, channel);
|
||||
picks[vi] = Pick{ v, rpos };
|
||||
|
@ -307,16 +306,17 @@ void VoxelToolTerrain::run_blocky_random_tick(AABB voxel_area, int voxel_count,
|
|||
const Voxel &vt = lib.get_voxel_const(pick.value);
|
||||
|
||||
if (vt.is_random_tickable()) {
|
||||
const Variant vpos = (pick.rpos + block_origin).to_vec3();
|
||||
const Variant vpos = pick.rpos + block_origin;
|
||||
const Variant vv = pick.value;
|
||||
const Variant *args[2];
|
||||
args[0] = &vpos;
|
||||
args[1] = &vv;
|
||||
Variant::CallError error;
|
||||
callback->call_func(args, 2, error);
|
||||
Callable::CallError error;
|
||||
Variant retval; // We don't care about the return value, Callable API requires it
|
||||
callback.call(args, 2, retval, error);
|
||||
// TODO I would really like to know what's the correct way to report such errors...
|
||||
// Examples I found in the engine are inconsistent
|
||||
ERR_FAIL_COND(error.error != Variant::CallError::CALL_OK);
|
||||
ERR_FAIL_COND(error.error != Callable::CallError::CALL_OK);
|
||||
// Return if it fails, we don't want an error spam
|
||||
}
|
||||
}
|
||||
|
@ -325,12 +325,13 @@ void VoxelToolTerrain::run_blocky_random_tick(AABB voxel_area, int voxel_count,
|
|||
}
|
||||
}
|
||||
|
||||
void VoxelToolTerrain::for_each_voxel_metadata_in_area(AABB voxel_area, Ref<FuncRef> callback) {
|
||||
void VoxelToolTerrain::for_each_voxel_metadata_in_area(AABB voxel_area, const Callable &callback) {
|
||||
ERR_FAIL_COND(_terrain == nullptr);
|
||||
ERR_FAIL_COND(callback.is_null());
|
||||
ERR_FAIL_COND(!is_valid_size(voxel_area.size));
|
||||
|
||||
const Box3i voxel_box = Box3i(Vector3i::from_floored(voxel_area.position), Vector3i::from_floored(voxel_area.size));
|
||||
const Box3i voxel_box =
|
||||
Box3i(Vector3iUtil::from_floored(voxel_area.position), Vector3iUtil::from_floored(voxel_area.size));
|
||||
ERR_FAIL_COND(!is_area_editable(voxel_box));
|
||||
|
||||
const Box3i data_block_box = voxel_box.downscaled(_terrain->get_data_block_size());
|
||||
|
@ -348,19 +349,21 @@ void VoxelToolTerrain::for_each_voxel_metadata_in_area(AABB voxel_area, Ref<Func
|
|||
const Box3i rel_voxel_box(voxel_box.pos - block_origin, voxel_box.size);
|
||||
// TODO Worth it locking blocks for metadata?
|
||||
|
||||
block->get_voxels().for_each_voxel_metadata_in_area(rel_voxel_box, [&callback, block_origin](Vector3i rel_pos, Variant meta) {
|
||||
const Variant key = (rel_pos + block_origin).to_vec3();
|
||||
const Variant *args[2] = { &key, &meta };
|
||||
Variant::CallError err;
|
||||
callback->call_func(args, 2, err);
|
||||
block->get_voxels().for_each_voxel_metadata_in_area(
|
||||
rel_voxel_box, [&callback, block_origin](Vector3i rel_pos, Variant meta) {
|
||||
const Variant key = rel_pos + block_origin;
|
||||
const Variant *args[2] = { &key, &meta };
|
||||
Callable::CallError err;
|
||||
Variant retval; // We don't care about the return value, Callable API requires it
|
||||
callback.call(args, 2, retval, err);
|
||||
|
||||
ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK,
|
||||
String("FuncRef call failed at {0}").format(varray(key)));
|
||||
ERR_FAIL_COND_MSG(err.error != Callable::CallError::CALL_OK,
|
||||
String("Callable failed at {0}").format(varray(key)));
|
||||
|
||||
// TODO Can't provide detailed error because FuncRef doesn't give us access to the object
|
||||
// ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK, false,
|
||||
// Variant::get_call_error_text(callback->get_object(), method_name, nullptr, 0, err));
|
||||
});
|
||||
// TODO Can't provide detailed error because FuncRef doesn't give us access to the object
|
||||
// ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK, false,
|
||||
// Variant::get_call_error_text(callback->get_object(), method_name, nullptr, 0, err));
|
||||
});
|
||||
});
|
||||
}
|
||||
|
||||
|
|
|
@ -4,7 +4,6 @@
|
|||
#include "voxel_tool.h"
|
||||
|
||||
class VoxelTerrain;
|
||||
class FuncRef;
|
||||
|
||||
class VoxelToolTerrain : public VoxelTool {
|
||||
GDCLASS(VoxelToolTerrain, VoxelTool)
|
||||
|
@ -13,20 +12,23 @@ public:
|
|||
VoxelToolTerrain(VoxelTerrain *terrain);
|
||||
|
||||
bool is_area_editable(const Box3i &box) const override;
|
||||
Ref<VoxelRaycastResult> raycast(Vector3 p_pos, Vector3 p_dir, float p_max_distance, uint32_t p_collision_mask) override;
|
||||
Ref<VoxelRaycastResult> raycast(
|
||||
Vector3 p_pos, Vector3 p_dir, float p_max_distance, uint32_t p_collision_mask) override;
|
||||
|
||||
void set_voxel_metadata(Vector3i pos, Variant meta) override;
|
||||
Variant get_voxel_metadata(Vector3i pos) const override;
|
||||
|
||||
void copy(Vector3i pos, Ref<VoxelBuffer> dst, uint8_t channels_mask) const override;
|
||||
void paste(Vector3i pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask, uint64_t mask_value) override;
|
||||
void paste(Vector3i pos, Ref<VoxelBuffer> p_voxels, uint8_t channels_mask, bool use_mask,
|
||||
uint64_t mask_value) override;
|
||||
|
||||
void do_sphere(Vector3 center, float radius) override;
|
||||
|
||||
// Specialized API
|
||||
|
||||
void run_blocky_random_tick(AABB voxel_area, int voxel_count, Ref<FuncRef> callback, int block_batch_count) const;
|
||||
void for_each_voxel_metadata_in_area(AABB voxel_area, Ref<FuncRef> callback);
|
||||
void run_blocky_random_tick(
|
||||
AABB voxel_area, int voxel_count, const Callable &callback, int block_batch_count) const;
|
||||
void for_each_voxel_metadata_in_area(AABB voxel_area, const Callable &callback);
|
||||
|
||||
protected:
|
||||
uint64_t _get_voxel(Vector3i pos) const override;
|
||||
|
|
|
@ -93,6 +93,7 @@ const ThirdParty g_third_parties[] = {
|
|||
" May you do good and not evil.\n"
|
||||
" May you find forgiveness for yourself and forgive others.\n"
|
||||
" May you share freely, never taking more than you give.\n" }
|
||||
// TODO Mention Transvoxel Lengyel tables
|
||||
};
|
||||
const unsigned int VOXEL_THIRD_PARTY_COUNT = VOXEL_ARRAY_LENGTH(g_third_parties);
|
||||
} // namespace
|
||||
|
@ -101,17 +102,17 @@ VoxelAboutWindow::VoxelAboutWindow() {
|
|||
// Generated with the help of https://github.com/Zylann/godot_scene_code_converter
|
||||
|
||||
set_title(TTR("About Voxel Tools"));
|
||||
set_resizable(true);
|
||||
set_custom_minimum_size(Vector2(600, 300) * EDSCALE);
|
||||
//set_resizable(true); // TODO How to set if a Window is resizable or not?
|
||||
set_min_size(Vector2(600, 300) * EDSCALE);
|
||||
set_visible(true);
|
||||
|
||||
VBoxContainer *v_box_container = memnew(VBoxContainer);
|
||||
v_box_container->set_anchor(MARGIN_RIGHT, 1);
|
||||
v_box_container->set_anchor(MARGIN_BOTTOM, 1);
|
||||
v_box_container->set_margin(MARGIN_LEFT, 4 * EDSCALE);
|
||||
v_box_container->set_margin(MARGIN_TOP, 4 * EDSCALE);
|
||||
v_box_container->set_margin(MARGIN_RIGHT, -4 * EDSCALE);
|
||||
v_box_container->set_margin(MARGIN_BOTTOM, -4 * EDSCALE);
|
||||
v_box_container->set_anchor(SIDE_RIGHT, 1);
|
||||
v_box_container->set_anchor(SIDE_BOTTOM, 1);
|
||||
v_box_container->set_offset(SIDE_LEFT, 4 * EDSCALE);
|
||||
v_box_container->set_offset(SIDE_TOP, 4 * EDSCALE);
|
||||
v_box_container->set_offset(SIDE_RIGHT, -4 * EDSCALE);
|
||||
v_box_container->set_offset(SIDE_BOTTOM, -4 * EDSCALE);
|
||||
|
||||
// HB
|
||||
HBoxContainer *h_box_container = memnew(HBoxContainer);
|
||||
|
@ -157,8 +158,9 @@ VoxelAboutWindow::VoxelAboutWindow() {
|
|||
}
|
||||
RichTextLabel *rich_text_label = memnew(RichTextLabel);
|
||||
rich_text_label->set_use_bbcode(true);
|
||||
rich_text_label->set_bbcode(about_text);
|
||||
rich_text_label->connect("meta_clicked", this, "_on_about_rich_text_label_meta_clicked");
|
||||
rich_text_label->set_text(about_text);
|
||||
rich_text_label->connect(
|
||||
"meta_clicked", callable_mp(this, &VoxelAboutWindow::_on_about_rich_text_label_meta_clicked));
|
||||
|
||||
tab_container->add_child(rich_text_label);
|
||||
|
||||
|
@ -200,7 +202,8 @@ VoxelAboutWindow::VoxelAboutWindow() {
|
|||
third_party_list->add_item(third_party.name);
|
||||
}
|
||||
|
||||
third_party_list->connect("item_selected", this, "_on_third_party_list_item_selected");
|
||||
third_party_list->connect(
|
||||
"item_selected", callable_mp(this, &VoxelAboutWindow::_on_third_party_list_item_selected));
|
||||
|
||||
_third_party_rich_text_label = memnew(RichTextLabel);
|
||||
_third_party_rich_text_label->set_selection_enabled(true);
|
||||
|
@ -220,12 +223,12 @@ VoxelAboutWindow::VoxelAboutWindow() {
|
|||
v_box_container->add_child(h_box_container);
|
||||
|
||||
HBoxContainer *h_box_container2 = memnew(HBoxContainer);
|
||||
h_box_container2->set_alignment(BoxContainer::ALIGN_CENTER);
|
||||
h_box_container2->set_alignment(BoxContainer::ALIGNMENT_CENTER);
|
||||
|
||||
Button *button = memnew(Button);
|
||||
button->set_text(TTR("Ok"));
|
||||
button->set_custom_minimum_size(Vector2(100 * EDSCALE, 0));
|
||||
button->connect("pressed", this, "hide");
|
||||
button->connect("pressed", callable_mp(this, &VoxelAboutWindow::_on_ok_button_pressed));
|
||||
h_box_container2->add_child(button);
|
||||
|
||||
v_box_container->add_child(h_box_container2);
|
||||
|
@ -235,7 +238,7 @@ VoxelAboutWindow::VoxelAboutWindow() {
|
|||
|
||||
void VoxelAboutWindow::_notification(int p_what) {
|
||||
if (p_what == NOTIFICATION_THEME_CHANGED) {
|
||||
_icon_texture_rect->set_texture(get_icon("VoxelTerrainLarge", "EditorIcons"));
|
||||
_icon_texture_rect->set_texture(get_theme_icon("VoxelTerrainLarge", "EditorIcons"));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -251,14 +254,14 @@ void VoxelAboutWindow::_on_about_rich_text_label_meta_clicked(Variant meta) {
|
|||
void VoxelAboutWindow::_on_third_party_list_item_selected(int index) {
|
||||
ERR_FAIL_COND(index < 0 || index >= int(VOXEL_THIRD_PARTY_COUNT));
|
||||
const ThirdParty &third_party = g_third_parties[index];
|
||||
_third_party_rich_text_label->set_text(String("{0}\n------------------------------\n{1}")
|
||||
.format(varray(third_party.name, third_party.license)));
|
||||
_third_party_rich_text_label->set_text(
|
||||
String("{0}\n------------------------------\n{1}").format(varray(third_party.name, third_party.license)));
|
||||
}
|
||||
|
||||
void VoxelAboutWindow::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_ok_button_pressed"), &VoxelAboutWindow::_on_ok_button_pressed);
|
||||
ClassDB::bind_method(D_METHOD("_on_about_rich_text_label_meta_clicked", "meta"),
|
||||
&VoxelAboutWindow::_on_about_rich_text_label_meta_clicked);
|
||||
ClassDB::bind_method(D_METHOD("_on_third_party_list_item_selected"),
|
||||
&VoxelAboutWindow::_on_third_party_list_item_selected);
|
||||
// ClassDB::bind_method(D_METHOD("_on_ok_button_pressed"), &VoxelAboutWindow::_on_ok_button_pressed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_about_rich_text_label_meta_clicked", "meta"),
|
||||
// &VoxelAboutWindow::_on_about_rich_text_label_meta_clicked);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_third_party_list_item_selected"), &VoxelAboutWindow::_on_third_party_list_item_selected);
|
||||
}
|
||||
|
|
|
@ -6,8 +6,8 @@
|
|||
class TextureRect;
|
||||
class RichTextLabel;
|
||||
|
||||
class VoxelAboutWindow : public WindowDialog {
|
||||
GDCLASS(VoxelAboutWindow, WindowDialog)
|
||||
class VoxelAboutWindow : public Window {
|
||||
GDCLASS(VoxelAboutWindow, Window)
|
||||
public:
|
||||
VoxelAboutWindow();
|
||||
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
set_custom_minimum_size(Vector2(0, EDSCALE * PREVIEW_HEIGHT));
|
||||
|
||||
_texture_rect = memnew(TextureRect);
|
||||
_texture_rect->set_anchors_and_margins_preset(Control::PRESET_WIDE);
|
||||
_texture_rect->set_anchors_and_offsets_preset(Control::PRESET_WIDE);
|
||||
_texture_rect->set_stretch_mode(TextureRect::STRETCH_KEEP_ASPECT_COVERED);
|
||||
add_child(_texture_rect);
|
||||
}
|
||||
|
@ -29,14 +29,16 @@ public:
|
|||
}
|
||||
|
||||
if (_noise.is_valid()) {
|
||||
_noise->disconnect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise->disconnect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &FastNoiseLiteViewer::_on_noise_changed));
|
||||
}
|
||||
|
||||
_noise = noise;
|
||||
|
||||
if (_noise.is_valid()) {
|
||||
set_noise_gradient(Ref<FastNoiseLiteGradient>());
|
||||
_noise->connect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise->connect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &FastNoiseLiteViewer::_on_noise_changed));
|
||||
set_process(true);
|
||||
update_preview();
|
||||
|
||||
|
@ -52,14 +54,16 @@ public:
|
|||
}
|
||||
|
||||
if (_noise_gradient.is_valid()) {
|
||||
_noise_gradient->disconnect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise_gradient->disconnect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &FastNoiseLiteViewer::_on_noise_changed));
|
||||
}
|
||||
|
||||
_noise_gradient = noise_gradient;
|
||||
|
||||
if (_noise_gradient.is_valid()) {
|
||||
set_noise(Ref<FastNoiseLite>());
|
||||
_noise_gradient->connect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise_gradient->connect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &FastNoiseLiteViewer::_on_noise_changed));
|
||||
set_process(true);
|
||||
update_preview();
|
||||
|
||||
|
@ -92,11 +96,9 @@ private:
|
|||
const Vector2i preview_size(PREVIEW_WIDTH, PREVIEW_HEIGHT);
|
||||
|
||||
Ref<Image> im;
|
||||
im.instance();
|
||||
im.instantiate();
|
||||
im->create(preview_size.x, preview_size.y, false, Image::FORMAT_RGB8);
|
||||
|
||||
im->lock();
|
||||
|
||||
if (_noise.is_valid()) {
|
||||
for (int y = 0; y < preview_size.y; ++y) {
|
||||
for (int x = 0; x < preview_size.x; ++x) {
|
||||
|
@ -126,16 +128,14 @@ private:
|
|||
}
|
||||
}
|
||||
|
||||
im->unlock();
|
||||
|
||||
Ref<ImageTexture> tex;
|
||||
tex.instance();
|
||||
tex.instantiate();
|
||||
tex->create_from_image(im);
|
||||
_texture_rect->set_texture(tex);
|
||||
}
|
||||
|
||||
static void _bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_noise_changed"), &FastNoiseLiteViewer::_on_noise_changed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_noise_changed"), &FastNoiseLiteViewer::_on_noise_changed);
|
||||
}
|
||||
|
||||
Ref<FastNoiseLite> _noise;
|
||||
|
@ -150,8 +150,7 @@ class FastNoiseLiteEditorInspectorPlugin : public EditorInspectorPlugin {
|
|||
GDCLASS(FastNoiseLiteEditorInspectorPlugin, EditorInspectorPlugin)
|
||||
public:
|
||||
bool can_handle(Object *p_object) override {
|
||||
return Object::cast_to<FastNoiseLite>(p_object) != NULL ||
|
||||
Object::cast_to<FastNoiseLiteGradient>(p_object);
|
||||
return Object::cast_to<FastNoiseLite>(p_object) != NULL || Object::cast_to<FastNoiseLiteGradient>(p_object);
|
||||
}
|
||||
|
||||
void parse_begin(Object *p_object) override {
|
||||
|
@ -180,6 +179,6 @@ public:
|
|||
|
||||
FastNoiseLiteEditorPlugin::FastNoiseLiteEditorPlugin(EditorNode *p_node) {
|
||||
Ref<FastNoiseLiteEditorInspectorPlugin> plugin;
|
||||
plugin.instance();
|
||||
plugin.instantiate();
|
||||
add_inspector_plugin(plugin);
|
||||
}
|
||||
|
|
|
@ -5,8 +5,8 @@
|
|||
#include "../../util/macros.h"
|
||||
|
||||
#include <core/core_string_names.h>
|
||||
#include <core/object/undo_redo.h>
|
||||
#include <core/os/os.h>
|
||||
#include <core/undo_redo.h>
|
||||
#include <editor/editor_scale.h>
|
||||
#include <scene/gui/check_box.h>
|
||||
#include <scene/gui/dialogs.h>
|
||||
|
@ -26,14 +26,15 @@ public:
|
|||
static const int RESOLUTION = 128;
|
||||
|
||||
VoxelGraphEditorNodePreview() {
|
||||
_image.instance();
|
||||
_image.instantiate();
|
||||
_image->create(RESOLUTION, RESOLUTION, false, Image::FORMAT_L8);
|
||||
_texture.instance();
|
||||
_texture.instantiate();
|
||||
update_texture();
|
||||
_texture_rect = memnew(TextureRect);
|
||||
_texture_rect->set_stretch_mode(TextureRect::STRETCH_SCALE);
|
||||
_texture_rect->set_custom_minimum_size(Vector2(RESOLUTION, RESOLUTION));
|
||||
_texture_rect->set_texture(_texture);
|
||||
_texture_rect->set_texture_filter(CanvasItem::TEXTURE_FILTER_NEAREST);
|
||||
add_child(_texture_rect);
|
||||
}
|
||||
|
||||
|
@ -42,7 +43,7 @@ public:
|
|||
}
|
||||
|
||||
void update_texture() {
|
||||
_texture->create_from_image(_image, 0);
|
||||
_texture->create_from_image(_image);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -69,14 +70,15 @@ class VoxelRangeAnalysisDialog : public AcceptDialog {
|
|||
public:
|
||||
VoxelRangeAnalysisDialog() {
|
||||
set_title(TTR("Debug Range Analysis"));
|
||||
set_custom_minimum_size(EDSCALE * Vector2(300, 280));
|
||||
set_min_size(EDSCALE * Vector2(300, 280));
|
||||
|
||||
VBoxContainer *vb = memnew(VBoxContainer);
|
||||
//vb->set_anchors_preset(Control::PRESET_TOP_WIDE);
|
||||
|
||||
enabled_checkbox = memnew(CheckBox);
|
||||
enabled_checkbox->set_text(TTR("Enabled"));
|
||||
enabled_checkbox->connect("toggled", this, "_on_enabled_checkbox_toggled");
|
||||
enabled_checkbox->connect(
|
||||
"toggled", callable_mp(this, &VoxelRangeAnalysisDialog::_on_enabled_checkbox_toggled));
|
||||
vb->add_child(enabled_checkbox);
|
||||
|
||||
Label *tip = memnew(Label);
|
||||
|
@ -134,14 +136,14 @@ private:
|
|||
label->set_text(text);
|
||||
parent->add_child(label);
|
||||
parent->add_child(sb);
|
||||
sb->connect("value_changed", this, "_on_area_spinbox_value_changed");
|
||||
sb->connect("value_changed", callable_mp(this, &VoxelRangeAnalysisDialog::_on_area_spinbox_value_changed));
|
||||
}
|
||||
|
||||
static void _bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_enabled_checkbox_toggled", "enabled"),
|
||||
&VoxelRangeAnalysisDialog::_on_enabled_checkbox_toggled);
|
||||
ClassDB::bind_method(D_METHOD("_on_area_spinbox_value_changed", "value"),
|
||||
&VoxelRangeAnalysisDialog::_on_area_spinbox_value_changed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_enabled_checkbox_toggled", "enabled"),
|
||||
// &VoxelRangeAnalysisDialog::_on_enabled_checkbox_toggled);
|
||||
// ClassDB::bind_method(D_METHOD("_on_area_spinbox_value_changed", "value"),
|
||||
// &VoxelRangeAnalysisDialog::_on_area_spinbox_value_changed);
|
||||
|
||||
ADD_SIGNAL(MethodInfo("analysis_toggled", PropertyInfo(Variant::BOOL, "enabled")));
|
||||
ADD_SIGNAL(MethodInfo("area_changed"));
|
||||
|
@ -160,19 +162,20 @@ private:
|
|||
|
||||
VoxelGraphEditor::VoxelGraphEditor() {
|
||||
VBoxContainer *vbox_container = memnew(VBoxContainer);
|
||||
vbox_container->set_anchors_and_margins_preset(Control::PRESET_WIDE);
|
||||
vbox_container->set_anchors_and_offsets_preset(Control::PRESET_WIDE);
|
||||
|
||||
{
|
||||
HBoxContainer *toolbar = memnew(HBoxContainer);
|
||||
|
||||
Button *update_previews_button = memnew(Button);
|
||||
update_previews_button->set_text("Update Previews");
|
||||
update_previews_button->connect("pressed", this, "_on_update_previews_button_pressed");
|
||||
update_previews_button->connect(
|
||||
"pressed", callable_mp(this, &VoxelGraphEditor::_on_update_previews_button_pressed));
|
||||
toolbar->add_child(update_previews_button);
|
||||
|
||||
Button *profile_button = memnew(Button);
|
||||
profile_button->set_text("Profile");
|
||||
profile_button->connect("pressed", this, "_on_profile_button_pressed");
|
||||
profile_button->connect("pressed", callable_mp(this, &VoxelGraphEditor::_on_profile_button_pressed));
|
||||
toolbar->add_child(profile_button);
|
||||
|
||||
_profile_label = memnew(Label);
|
||||
|
@ -186,7 +189,8 @@ VoxelGraphEditor::VoxelGraphEditor() {
|
|||
|
||||
Button *range_analysis_button = memnew(Button);
|
||||
range_analysis_button->set_text("Analyze Range...");
|
||||
range_analysis_button->connect("pressed", this, "_on_analyze_range_button_pressed");
|
||||
range_analysis_button->connect(
|
||||
"pressed", callable_mp(this, &VoxelGraphEditor::_on_analyze_range_button_pressed));
|
||||
toolbar->add_child(range_analysis_button);
|
||||
|
||||
vbox_container->add_child(toolbar);
|
||||
|
@ -196,12 +200,14 @@ VoxelGraphEditor::VoxelGraphEditor() {
|
|||
_graph_edit->set_anchors_preset(Control::PRESET_WIDE);
|
||||
_graph_edit->set_right_disconnects(true);
|
||||
_graph_edit->set_v_size_flags(Control::SIZE_EXPAND_FILL);
|
||||
_graph_edit->connect("gui_input", this, "_on_graph_edit_gui_input");
|
||||
_graph_edit->connect("connection_request", this, "_on_graph_edit_connection_request");
|
||||
_graph_edit->connect("delete_nodes_request", this, "_on_graph_edit_delete_nodes_request");
|
||||
_graph_edit->connect("disconnection_request", this, "_on_graph_edit_disconnection_request");
|
||||
_graph_edit->connect("node_selected", this, "_on_graph_edit_node_selected");
|
||||
_graph_edit->connect("node_unselected", this, "_on_graph_edit_node_unselected");
|
||||
_graph_edit->connect("gui_input", callable_mp(this, &VoxelGraphEditor::_on_graph_edit_gui_input));
|
||||
_graph_edit->connect("connection_request", callable_mp(this, &VoxelGraphEditor::_on_graph_edit_connection_request));
|
||||
_graph_edit->connect(
|
||||
"delete_nodes_request", callable_mp(this, &VoxelGraphEditor::_on_graph_edit_delete_nodes_request));
|
||||
_graph_edit->connect(
|
||||
"disconnection_request", callable_mp(this, &VoxelGraphEditor::_on_graph_edit_disconnection_request));
|
||||
_graph_edit->connect("node_selected", callable_mp(this, &VoxelGraphEditor::_on_graph_edit_node_selected));
|
||||
_graph_edit->connect("node_unselected", callable_mp(this, &VoxelGraphEditor::_on_graph_edit_node_unselected));
|
||||
vbox_container->add_child(_graph_edit);
|
||||
|
||||
add_child(vbox_container);
|
||||
|
@ -212,7 +218,7 @@ VoxelGraphEditor::VoxelGraphEditor() {
|
|||
String name = VoxelGraphNodeDB::get_category_name(VoxelGraphNodeDB::Category(i));
|
||||
PopupMenu *menu = memnew(PopupMenu);
|
||||
menu->set_name(name);
|
||||
menu->connect("id_pressed", this, "_on_context_menu_id_pressed");
|
||||
menu->connect("id_pressed", callable_mp(this, &VoxelGraphEditor::_on_context_menu_id_pressed));
|
||||
_context_menu->add_child(menu);
|
||||
_context_menu->add_submenu_item(name, name, i);
|
||||
category_menus[i] = menu;
|
||||
|
@ -226,8 +232,10 @@ VoxelGraphEditor::VoxelGraphEditor() {
|
|||
add_child(_context_menu);
|
||||
|
||||
_range_analysis_dialog = memnew(VoxelRangeAnalysisDialog);
|
||||
_range_analysis_dialog->connect("analysis_toggled", this, "_on_range_analysis_toggled");
|
||||
_range_analysis_dialog->connect("area_changed", this, "_on_range_analysis_area_changed");
|
||||
_range_analysis_dialog->connect(
|
||||
"analysis_toggled", callable_mp(this, &VoxelGraphEditor::_on_range_analysis_toggled));
|
||||
_range_analysis_dialog->connect(
|
||||
"area_changed", callable_mp(this, &VoxelGraphEditor::_on_range_analysis_area_changed));
|
||||
add_child(_range_analysis_dialog);
|
||||
}
|
||||
|
||||
|
@ -237,8 +245,10 @@ void VoxelGraphEditor::set_graph(Ref<VoxelGeneratorGraph> graph) {
|
|||
}
|
||||
|
||||
if (_graph.is_valid()) {
|
||||
_graph->disconnect(CoreStringNames::get_singleton()->changed, this, "_on_graph_changed");
|
||||
_graph->disconnect(VoxelGeneratorGraph::SIGNAL_NODE_NAME_CHANGED, this, "_on_graph_node_name_changed");
|
||||
_graph->disconnect(
|
||||
CoreStringNames::get_singleton()->changed, callable_mp(this, &VoxelGraphEditor::_on_graph_changed));
|
||||
_graph->disconnect(VoxelGeneratorGraph::SIGNAL_NODE_NAME_CHANGED,
|
||||
callable_mp(this, &VoxelGraphEditor::_on_graph_node_name_changed));
|
||||
}
|
||||
|
||||
_graph = graph;
|
||||
|
@ -250,8 +260,10 @@ void VoxelGraphEditor::set_graph(Ref<VoxelGeneratorGraph> graph) {
|
|||
if (_graph->get_nodes_count() == 0) {
|
||||
_graph->load_plane_preset();
|
||||
}
|
||||
_graph->connect(CoreStringNames::get_singleton()->changed, this, "_on_graph_changed");
|
||||
_graph->connect(VoxelGeneratorGraph::SIGNAL_NODE_NAME_CHANGED, this, "_on_graph_node_name_changed");
|
||||
_graph->connect(
|
||||
CoreStringNames::get_singleton()->changed, callable_mp(this, &VoxelGraphEditor::_on_graph_changed));
|
||||
_graph->connect(VoxelGeneratorGraph::SIGNAL_NODE_NAME_CHANGED,
|
||||
callable_mp(this, &VoxelGraphEditor::_on_graph_node_name_changed));
|
||||
}
|
||||
|
||||
_debug_renderer.clear();
|
||||
|
@ -270,14 +282,14 @@ void VoxelGraphEditor::set_voxel_node(VoxelNode *node) {
|
|||
_debug_renderer.set_world(nullptr);
|
||||
} else {
|
||||
PRINT_VERBOSE(String("Reference node for VoxelGraph previews: {0}").format(varray(node->get_path())));
|
||||
_debug_renderer.set_world(_voxel_node->get_world().ptr());
|
||||
_debug_renderer.set_world(_voxel_node->get_world_3d().ptr());
|
||||
}
|
||||
}
|
||||
|
||||
void VoxelGraphEditor::_notification(int p_what) {
|
||||
switch (p_what) {
|
||||
case NOTIFICATION_INTERNAL_PROCESS:
|
||||
_process(get_tree()->get_idle_process_time());
|
||||
_process(get_tree()->get_process_time());
|
||||
break;
|
||||
|
||||
case NOTIFICATION_VISIBILITY_CHANGED:
|
||||
|
@ -324,13 +336,10 @@ void VoxelGraphEditor::build_gui_from_graph() {
|
|||
|
||||
// Nodes
|
||||
|
||||
PoolIntArray node_ids = graph.get_node_ids();
|
||||
{
|
||||
PoolIntArray::Read node_ids_read = node_ids.read();
|
||||
for (int i = 0; i < node_ids.size(); ++i) {
|
||||
const uint32_t node_id = node_ids_read[i];
|
||||
create_node_gui(node_id);
|
||||
}
|
||||
PackedInt32Array node_ids = graph.get_node_ids();
|
||||
for (int i = 0; i < node_ids.size(); ++i) {
|
||||
const uint32_t node_id = node_ids[i];
|
||||
create_node_gui(node_id);
|
||||
}
|
||||
|
||||
// Connections
|
||||
|
@ -370,14 +379,14 @@ void VoxelGraphEditor::create_node_gui(uint32_t node_id) {
|
|||
ERR_FAIL_COND(_graph_edit->has_node(ui_node_name));
|
||||
|
||||
VoxelGraphEditorNode *node_view = memnew(VoxelGraphEditorNode);
|
||||
node_view->set_offset(graph.get_node_gui_position(node_id) * EDSCALE);
|
||||
node_view->set_position_offset(graph.get_node_gui_position(node_id) * EDSCALE);
|
||||
|
||||
StringName node_name = graph.get_node_name(node_id);
|
||||
update_node_view_title(node_view, node_name, node_type.name);
|
||||
|
||||
node_view->set_name(ui_node_name);
|
||||
node_view->node_id = node_id;
|
||||
node_view->connect("dragged", this, "_on_graph_node_dragged", varray(node_id));
|
||||
node_view->connect("dragged", callable_mp(this, &VoxelGraphEditor::_on_graph_node_dragged), varray(node_id));
|
||||
//node_view.resizable = true
|
||||
//node_view.rect_size = Vector2(200, 100)
|
||||
|
||||
|
@ -432,7 +441,7 @@ void VoxelGraphEditor::create_node_gui(uint32_t node_id) {
|
|||
}
|
||||
|
||||
node_view->add_child(property_control);
|
||||
node_view->set_slot(i, has_left, Variant::REAL, port_color, has_right, Variant::REAL, port_color);
|
||||
node_view->set_slot(i, has_left, Variant::FLOAT, port_color, has_right, Variant::FLOAT, port_color);
|
||||
}
|
||||
|
||||
if (node_type_id == VoxelGeneratorGraph::NODE_SDF_PREVIEW) {
|
||||
|
@ -500,7 +509,7 @@ void VoxelGraphEditor::_on_graph_edit_gui_input(Ref<InputEvent> event) {
|
|||
|
||||
if (mb.is_valid()) {
|
||||
if (mb->is_pressed()) {
|
||||
if (mb->get_button_index() == BUTTON_RIGHT) {
|
||||
if (mb->get_button_index() == MouseButton::RIGHT) {
|
||||
_click_position = mb->get_position();
|
||||
_context_menu->set_position(get_global_mouse_position());
|
||||
_context_menu->popup();
|
||||
|
@ -524,8 +533,7 @@ void VoxelGraphEditor::_on_graph_edit_connection_request(
|
|||
|
||||
_undo_redo->add_do_method(
|
||||
*_graph, "add_connection", src_node_view->node_id, from_slot, dst_node_view->node_id, to_slot);
|
||||
_undo_redo->add_do_method(
|
||||
_graph_edit, "connect_node", from_node_name, from_slot, to_node_name, to_slot);
|
||||
_undo_redo->add_do_method(_graph_edit, "connect_node", from_node_name, from_slot, to_node_name, to_slot);
|
||||
|
||||
_undo_redo->add_undo_method(
|
||||
*_graph, "remove_connection", src_node_view->node_id, from_slot, dst_node_view->node_id, to_slot);
|
||||
|
@ -597,13 +605,13 @@ void VoxelGraphEditor::_on_graph_edit_delete_nodes_request() {
|
|||
const ProgramGraph::Connection &con = connections[j];
|
||||
|
||||
if (con.src.node_id == node_id || con.dst.node_id == node_id) {
|
||||
_undo_redo->add_undo_method(*_graph, "add_connection",
|
||||
con.src.node_id, con.src.port_index, con.dst.node_id, con.dst.port_index);
|
||||
_undo_redo->add_undo_method(*_graph, "add_connection", con.src.node_id, con.src.port_index,
|
||||
con.dst.node_id, con.dst.port_index);
|
||||
|
||||
const String src_node_name = node_to_gui_name(con.src.node_id);
|
||||
const String dst_node_name = node_to_gui_name(con.dst.node_id);
|
||||
_undo_redo->add_undo_method(_graph_edit, "connect_node",
|
||||
src_node_name, con.src.port_index, dst_node_name, con.dst.port_index);
|
||||
_undo_redo->add_undo_method(_graph_edit, "connect_node", src_node_name, con.src.port_index,
|
||||
dst_node_name, con.dst.port_index);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -624,7 +632,7 @@ void VoxelGraphEditor::set_node_position(int id, Vector2 offset) {
|
|||
String node_name = node_to_gui_name(id);
|
||||
GraphNode *node_view = Object::cast_to<GraphNode>(_graph_edit->get_node(node_name));
|
||||
if (node_view != nullptr) {
|
||||
node_view->set_offset(offset);
|
||||
node_view->set_position_offset(offset);
|
||||
}
|
||||
_graph->set_node_gui_position(id, offset / EDSCALE);
|
||||
}
|
||||
|
@ -679,8 +687,7 @@ void VoxelGraphEditor::_check_nothing_selected() {
|
|||
|
||||
void reset_modulates(GraphEdit &graph_edit) {
|
||||
for (int child_index = 0; child_index < graph_edit.get_child_count(); ++child_index) {
|
||||
VoxelGraphEditorNode *node_view =
|
||||
Object::cast_to<VoxelGraphEditorNode>(graph_edit.get_child(child_index));
|
||||
VoxelGraphEditorNode *node_view = Object::cast_to<VoxelGraphEditorNode>(graph_edit.get_child(child_index));
|
||||
if (node_view == nullptr) {
|
||||
continue;
|
||||
}
|
||||
|
@ -741,15 +748,14 @@ void VoxelGraphEditor::update_range_analysis_previews() {
|
|||
|
||||
const AABB aabb = _range_analysis_dialog->get_aabb();
|
||||
_graph->debug_analyze_range(
|
||||
Vector3i::from_floored(aabb.position), Vector3i::from_floored(aabb.position + aabb.size), true);
|
||||
Vector3iUtil::from_floored(aabb.position), Vector3iUtil::from_floored(aabb.position + aabb.size), true);
|
||||
|
||||
const VoxelGraphRuntime::State &state = _graph->get_last_state_from_current_thread();
|
||||
|
||||
const Color greyed_out_color(1, 1, 1, 0.5);
|
||||
|
||||
for (int child_index = 0; child_index < _graph_edit->get_child_count(); ++child_index) {
|
||||
VoxelGraphEditorNode *node_view =
|
||||
Object::cast_to<VoxelGraphEditorNode>(_graph_edit->get_child(child_index));
|
||||
VoxelGraphEditorNode *node_view = Object::cast_to<VoxelGraphEditorNode>(_graph_edit->get_child(child_index));
|
||||
if (node_view == nullptr) {
|
||||
continue;
|
||||
}
|
||||
|
@ -780,8 +786,7 @@ void VoxelGraphEditor::update_range_analysis_previews() {
|
|||
Span<const int> execution_map = VoxelGeneratorGraph::get_last_execution_map_debug_from_current_thread();
|
||||
for (unsigned int i = 0; i < execution_map.size(); ++i) {
|
||||
String node_view_path = node_to_gui_name(execution_map[i]);
|
||||
VoxelGraphEditorNode *node_view =
|
||||
Object::cast_to<VoxelGraphEditorNode>(_graph_edit->get_node(node_view_path));
|
||||
VoxelGraphEditorNode *node_view = Object::cast_to<VoxelGraphEditorNode>(_graph_edit->get_node(node_view_path));
|
||||
node_view->set_modulate(Color(1, 1, 1));
|
||||
}
|
||||
}
|
||||
|
@ -796,11 +801,10 @@ void VoxelGraphEditor::update_range_analysis_gizmo() {
|
|||
return;
|
||||
}
|
||||
|
||||
const Transform parent_transform = _voxel_node->get_global_transform();
|
||||
const Transform3D parent_transform = _voxel_node->get_global_transform();
|
||||
const AABB aabb = _range_analysis_dialog->get_aabb();
|
||||
_debug_renderer.begin();
|
||||
_debug_renderer.draw_box(
|
||||
parent_transform * Transform(Basis().scaled(aabb.size), aabb.position),
|
||||
_debug_renderer.draw_box(parent_transform * Transform3D(Basis().scaled(aabb.size), aabb.position),
|
||||
VoxelDebug::ID_VOXEL_GRAPH_DEBUG_BOUNDS);
|
||||
_debug_renderer.end();
|
||||
}
|
||||
|
@ -871,9 +875,7 @@ void VoxelGraphEditor::update_slice_previews() {
|
|||
}
|
||||
}
|
||||
|
||||
_graph->generate_set(
|
||||
Span<float>(x_vec, 0, x_vec.size()),
|
||||
Span<float>(y_vec, 0, y_vec.size()),
|
||||
_graph->generate_set(Span<float>(x_vec, 0, x_vec.size()), Span<float>(y_vec, 0, y_vec.size()),
|
||||
Span<float>(z_vec, 0, z_vec.size()));
|
||||
|
||||
const VoxelGraphRuntime::State &last_state = VoxelGeneratorGraph::get_last_state_from_current_thread();
|
||||
|
@ -886,8 +888,6 @@ void VoxelGraphEditor::update_slice_previews() {
|
|||
Image &im = **info.control->get_image();
|
||||
ERR_FAIL_COND(im.get_width() * im.get_height() != static_cast<int>(buffer.size));
|
||||
|
||||
im.lock();
|
||||
|
||||
unsigned int i = 0;
|
||||
for (int y = 0; y < im.get_height(); ++y) {
|
||||
for (int x = 0; x < im.get_width(); ++x) {
|
||||
|
@ -898,16 +898,13 @@ void VoxelGraphEditor::update_slice_previews() {
|
|||
}
|
||||
}
|
||||
|
||||
im.unlock();
|
||||
|
||||
info.control->update_texture();
|
||||
}
|
||||
}
|
||||
|
||||
void VoxelGraphEditor::clear_range_analysis_tooltips() {
|
||||
for (int child_index = 0; child_index < _graph_edit->get_child_count(); ++child_index) {
|
||||
VoxelGraphEditorNode *node_view =
|
||||
Object::cast_to<VoxelGraphEditorNode>(_graph_edit->get_child(child_index));
|
||||
VoxelGraphEditorNode *node_view = Object::cast_to<VoxelGraphEditorNode>(_graph_edit->get_child(child_index));
|
||||
if (node_view == nullptr) {
|
||||
continue;
|
||||
}
|
||||
|
@ -951,7 +948,7 @@ void VoxelGraphEditor::_on_profile_button_pressed() {
|
|||
}
|
||||
|
||||
void VoxelGraphEditor::_on_analyze_range_button_pressed() {
|
||||
_range_analysis_dialog->popup_centered_minsize();
|
||||
_range_analysis_dialog->popup_centered();
|
||||
}
|
||||
|
||||
void VoxelGraphEditor::_on_range_analysis_toggled(bool enabled) {
|
||||
|
@ -965,31 +962,33 @@ void VoxelGraphEditor::_on_range_analysis_area_changed() {
|
|||
}
|
||||
|
||||
void VoxelGraphEditor::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_edit_gui_input", "event"), &VoxelGraphEditor::_on_graph_edit_gui_input);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("_on_graph_edit_connection_request", "from_node_name", "from_slot", "to_node_name", "to_slot"),
|
||||
&VoxelGraphEditor::_on_graph_edit_connection_request);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("_on_graph_edit_disconnection_request", "from_node_name", "from_slot", "to_node_name", "to_slot"),
|
||||
&VoxelGraphEditor::_on_graph_edit_disconnection_request);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_edit_delete_nodes_request"),
|
||||
&VoxelGraphEditor::_on_graph_edit_delete_nodes_request);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_edit_node_selected"), &VoxelGraphEditor::_on_graph_edit_node_selected);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_edit_node_unselected"), &VoxelGraphEditor::_on_graph_edit_node_unselected);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_node_dragged", "from", "to", "id"),
|
||||
&VoxelGraphEditor::_on_graph_node_dragged);
|
||||
ClassDB::bind_method(D_METHOD("_on_context_menu_id_pressed", "id"), &VoxelGraphEditor::_on_context_menu_id_pressed);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_changed"), &VoxelGraphEditor::_on_graph_changed);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_node_name_changed"), &VoxelGraphEditor::_on_graph_node_name_changed);
|
||||
ClassDB::bind_method(D_METHOD("_on_update_previews_button_pressed"),
|
||||
&VoxelGraphEditor::_on_update_previews_button_pressed);
|
||||
ClassDB::bind_method(D_METHOD("_on_profile_button_pressed"), &VoxelGraphEditor::_on_profile_button_pressed);
|
||||
ClassDB::bind_method(D_METHOD("_on_analyze_range_button_pressed"),
|
||||
&VoxelGraphEditor::_on_analyze_range_button_pressed);
|
||||
ClassDB::bind_method(D_METHOD("_on_range_analysis_toggled", "enabled"),
|
||||
&VoxelGraphEditor::_on_range_analysis_toggled);
|
||||
ClassDB::bind_method(D_METHOD("_on_range_analysis_area_changed"),
|
||||
&VoxelGraphEditor::_on_range_analysis_area_changed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_graph_edit_gui_input", "event"), &VoxelGraphEditor::_on_graph_edit_gui_input);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_graph_edit_connection_request", "from_node_name", "from_slot", "to_node_name", "to_slot"),
|
||||
// &VoxelGraphEditor::_on_graph_edit_connection_request);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_graph_edit_disconnection_request", "from_node_name", "from_slot", "to_node_name", "to_slot"),
|
||||
// &VoxelGraphEditor::_on_graph_edit_disconnection_request);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_graph_edit_delete_nodes_request"), &VoxelGraphEditor::_on_graph_edit_delete_nodes_request);
|
||||
// ClassDB::bind_method(D_METHOD("_on_graph_edit_node_selected"), &VoxelGraphEditor::_on_graph_edit_node_selected);
|
||||
// ClassDB::bind_method(D_METHOD("_on_graph_edit_node_unselected"),
|
||||
// &VoxelGraphEditor::_on_graph_edit_node_unselected);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_graph_node_dragged", "from", "to", "id"), &VoxelGraphEditor::_on_graph_node_dragged);
|
||||
// ClassDB::bind_method(D_METHOD("_on_context_menu_id_pressed", "id"),
|
||||
// &VoxelGraphEditor::_on_context_menu_id_pressed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_graph_changed"), &VoxelGraphEditor::_on_graph_changed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_graph_node_name_changed"), &VoxelGraphEditor::_on_graph_node_name_changed);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_update_previews_button_pressed"), &VoxelGraphEditor::_on_update_previews_button_pressed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_profile_button_pressed"), &VoxelGraphEditor::_on_profile_button_pressed);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_analyze_range_button_pressed"), &VoxelGraphEditor::_on_analyze_range_button_pressed);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_range_analysis_toggled", "enabled"), &VoxelGraphEditor::_on_range_analysis_toggled);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_range_analysis_area_changed"), &VoxelGraphEditor::_on_range_analysis_area_changed);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("_check_nothing_selected"), &VoxelGraphEditor::_check_nothing_selected);
|
||||
|
||||
|
|
|
@ -11,7 +11,7 @@ class AcceptDialog;
|
|||
class UndoRedo;
|
||||
class VoxelRangeAnalysisDialog;
|
||||
class VoxelNode;
|
||||
class Spatial;
|
||||
class Node3D;
|
||||
|
||||
class VoxelGraphEditor : public Control {
|
||||
GDCLASS(VoxelGraphEditor, Control)
|
||||
|
@ -22,7 +22,9 @@ public:
|
|||
VoxelGraphEditor();
|
||||
|
||||
void set_graph(Ref<VoxelGeneratorGraph> graph);
|
||||
inline Ref<VoxelGeneratorGraph> get_graph() const { return _graph; }
|
||||
inline Ref<VoxelGeneratorGraph> get_graph() const {
|
||||
return _graph;
|
||||
}
|
||||
|
||||
void set_undo_redo(UndoRedo *undo_redo);
|
||||
void set_voxel_node(VoxelNode *node);
|
||||
|
@ -75,7 +77,7 @@ private:
|
|||
Vector2 _click_position;
|
||||
bool _nothing_selected_check_scheduled = false;
|
||||
float _time_before_preview_update = 0.f;
|
||||
Spatial *_voxel_node = nullptr;
|
||||
Node3D *_voxel_node = nullptr;
|
||||
VoxelDebug::DebugRenderer _debug_renderer;
|
||||
};
|
||||
|
||||
|
|
|
@ -11,8 +11,10 @@ VoxelGraphEditorPlugin::VoxelGraphEditorPlugin(EditorNode *p_node) {
|
|||
//EditorInterface *ed = get_editor_interface();
|
||||
_graph_editor = memnew(VoxelGraphEditor);
|
||||
_graph_editor->set_custom_minimum_size(Size2(0, 300) * EDSCALE);
|
||||
_graph_editor->connect(VoxelGraphEditor::SIGNAL_NODE_SELECTED, this, "_on_graph_editor_node_selected");
|
||||
_graph_editor->connect(VoxelGraphEditor::SIGNAL_NOTHING_SELECTED, this, "_on_graph_editor_nothing_selected");
|
||||
_graph_editor->connect(VoxelGraphEditor::SIGNAL_NODE_SELECTED,
|
||||
callable_mp(this, &VoxelGraphEditorPlugin::_on_graph_editor_node_selected));
|
||||
_graph_editor->connect(VoxelGraphEditor::SIGNAL_NOTHING_SELECTED,
|
||||
callable_mp(this, &VoxelGraphEditorPlugin::_on_graph_editor_nothing_selected));
|
||||
_bottom_panel_button = add_control_to_bottom_panel(_graph_editor, TTR("Voxel Graph"));
|
||||
_bottom_panel_button->hide();
|
||||
}
|
||||
|
@ -91,14 +93,14 @@ void VoxelGraphEditorPlugin::_hide_deferred() {
|
|||
|
||||
void VoxelGraphEditorPlugin::_on_graph_editor_node_selected(uint32_t node_id) {
|
||||
Ref<VoxelGraphNodeInspectorWrapper> wrapper;
|
||||
wrapper.instance();
|
||||
wrapper.instantiate();
|
||||
wrapper->setup(_graph_editor->get_graph(), node_id, &get_undo_redo());
|
||||
// Note: it's neither explicit nor documented, but the reference will stay alive due to EditorHistory::_add_object
|
||||
get_editor_interface()->inspect_object(*wrapper);
|
||||
// TODO Absurd situation here...
|
||||
// `inspect_object()` gets to a point where Godot hides ALL plugins for some reason...
|
||||
// And all this, to have the graph editor rebuilt and shown again, because it DOES also handle that resource type -_-
|
||||
// https://github.com/godotengine/godot/issues/40166
|
||||
// And all this, to have the graph editor rebuilt and shown again, because it DOES also handle that resource type
|
||||
// -_- https://github.com/godotengine/godot/issues/40166
|
||||
}
|
||||
|
||||
void VoxelGraphEditorPlugin::_on_graph_editor_nothing_selected() {
|
||||
|
@ -113,9 +115,9 @@ void VoxelGraphEditorPlugin::_on_graph_editor_nothing_selected() {
|
|||
}
|
||||
|
||||
void VoxelGraphEditorPlugin::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_editor_node_selected", "node_id"),
|
||||
&VoxelGraphEditorPlugin::_on_graph_editor_node_selected);
|
||||
ClassDB::bind_method(D_METHOD("_on_graph_editor_nothing_selected"),
|
||||
&VoxelGraphEditorPlugin::_on_graph_editor_nothing_selected);
|
||||
// ClassDB::bind_method(D_METHOD("_on_graph_editor_node_selected", "node_id"),
|
||||
// &VoxelGraphEditorPlugin::_on_graph_editor_node_selected);
|
||||
// ClassDB::bind_method(
|
||||
// D_METHOD("_on_graph_editor_nothing_selected"), &VoxelGraphEditorPlugin::_on_graph_editor_nothing_selected);
|
||||
ClassDB::bind_method(D_METHOD("_hide_deferred"), &VoxelGraphEditorPlugin::_hide_deferred);
|
||||
}
|
||||
|
|
|
@ -23,7 +23,7 @@ private:
|
|||
static void _bind_methods();
|
||||
|
||||
VoxelGraphEditor *_graph_editor = nullptr;
|
||||
ToolButton *_bottom_panel_button = nullptr;
|
||||
Button *_bottom_panel_button = nullptr;
|
||||
bool _deferred_visibility_scheduled = false;
|
||||
};
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#include "voxel_graph_node_inspector_wrapper.h"
|
||||
#include "../../generators/graph/voxel_graph_node_db.h"
|
||||
#include "../../util/macros.h"
|
||||
#include <core/undo_redo.h>
|
||||
#include <core/object/undo_redo.h>
|
||||
|
||||
void VoxelGraphNodeInspectorWrapper::setup(Ref<VoxelGeneratorGraph> p_graph, uint32_t p_node_id, UndoRedo *ur) {
|
||||
_graph = p_graph;
|
||||
|
@ -36,7 +36,7 @@ void VoxelGraphNodeInspectorWrapper::_get_property_list(List<PropertyInfo> *p_li
|
|||
pi.name = param.name;
|
||||
pi.type = param.type;
|
||||
pi.class_name = param.class_name;
|
||||
if (!param.class_name.empty()) {
|
||||
if (!param.class_name.is_empty()) {
|
||||
pi.hint = PROPERTY_HINT_RESOURCE_TYPE;
|
||||
pi.hint_string = pi.class_name;
|
||||
} else if (param.has_range) {
|
||||
|
@ -135,7 +135,8 @@ bool VoxelGraphNodeInspectorWrapper::_get(const StringName &p_name, Variant &r_r
|
|||
}
|
||||
|
||||
// This method is an undocumented hack used in `EditorInspector::_edit_set` so we can implement UndoRedo ourselves.
|
||||
// If we don't do this, then the inspector's UndoRedo will use the wrapper, which won't mark the real resource as modified.
|
||||
// If we don't do this, then the inspector's UndoRedo will use the wrapper, which won't mark the real resource as
|
||||
// modified.
|
||||
bool VoxelGraphNodeInspectorWrapper::_dont_undo_redo() const {
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -2,18 +2,20 @@
|
|||
#define VOXEL_GRAPH_NODE_INSPECTOR_WRAPPER_H
|
||||
|
||||
#include "../../generators/graph/voxel_generator_graph.h"
|
||||
#include <core/reference.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
|
||||
class UndoRedo;
|
||||
|
||||
// Nodes aren't resources so this translates them into a form the inspector can understand.
|
||||
// This makes it easier to support undo/redo and sub-resources.
|
||||
// WARNING: `AnimationPlayer` will allow to keyframe properties, but there really is no support for that.
|
||||
class VoxelGraphNodeInspectorWrapper : public Reference {
|
||||
GDCLASS(VoxelGraphNodeInspectorWrapper, Reference)
|
||||
class VoxelGraphNodeInspectorWrapper : public RefCounted {
|
||||
GDCLASS(VoxelGraphNodeInspectorWrapper, RefCounted)
|
||||
public:
|
||||
void setup(Ref<VoxelGeneratorGraph> p_graph, uint32_t p_node_id, UndoRedo *ur);
|
||||
inline Ref<VoxelGeneratorGraph> get_graph() const { return _graph; }
|
||||
inline Ref<VoxelGeneratorGraph> get_graph() const {
|
||||
return _graph;
|
||||
}
|
||||
|
||||
protected:
|
||||
void _get_property_list(List<PropertyInfo> *p_list) const;
|
||||
|
|
|
@ -38,16 +38,19 @@ void VoxelInstanceLibraryEditorInspectorPlugin::add_buttons() {
|
|||
HBoxContainer *hb = memnew(HBoxContainer);
|
||||
|
||||
MenuButton *button_add = memnew(MenuButton);
|
||||
button_add->set_icon(icon_provider->get_icon("Add", "EditorIcons"));
|
||||
button_add->set_icon(icon_provider->get_theme_icon(SNAME("Add"), SNAME("EditorIcons")));
|
||||
button_add->get_popup()->add_item("MultiMesh item (fast)", BUTTON_ADD_MULTIMESH_ITEM);
|
||||
button_add->get_popup()->add_item("Scene item (slow)", BUTTON_ADD_SCENE_ITEM);
|
||||
button_add->get_popup()->connect("id_pressed", button_listener, "_on_button_pressed");
|
||||
button_add->get_popup()->connect(
|
||||
"id_pressed", callable_mp(button_listener, &VoxelInstanceLibraryEditorPlugin::_on_button_pressed));
|
||||
hb->add_child(button_add);
|
||||
|
||||
Button *button_remove = memnew(Button);
|
||||
button_remove->set_icon(icon_provider->get_icon("Remove", "EditorIcons"));
|
||||
button_remove->set_icon(icon_provider->get_theme_icon(SNAME("Remove"), SNAME("EditorIcons")));
|
||||
button_remove->set_flat(true);
|
||||
button_remove->connect("pressed", button_listener, "_on_button_pressed", varray(BUTTON_REMOVE_ITEM));
|
||||
button_remove->connect("pressed",
|
||||
callable_mp(button_listener, &VoxelInstanceLibraryEditorPlugin::_on_button_pressed),
|
||||
varray(BUTTON_REMOVE_ITEM));
|
||||
hb->add_child(button_remove);
|
||||
|
||||
Control *spacer = memnew(Control);
|
||||
|
@ -56,7 +59,8 @@ void VoxelInstanceLibraryEditorInspectorPlugin::add_buttons() {
|
|||
|
||||
Button *button_update = memnew(Button);
|
||||
button_update->set_text(TTR("Update From Scene..."));
|
||||
button_update->connect("pressed", button_listener, "_on_button_pressed",
|
||||
button_update->connect("pressed",
|
||||
callable_mp(button_listener, &VoxelInstanceLibraryEditorPlugin::_on_button_pressed),
|
||||
varray(BUTTON_UPDATE_MULTIMESH_ITEM_FROM_SCENE));
|
||||
hb->add_child(button_update);
|
||||
|
||||
|
@ -69,7 +73,8 @@ VoxelInstanceLibraryEditorPlugin::VoxelInstanceLibraryEditorPlugin(EditorNode *p
|
|||
Control *base_control = get_editor_interface()->get_base_control();
|
||||
|
||||
_confirmation_dialog = memnew(ConfirmationDialog);
|
||||
_confirmation_dialog->connect("confirmed", this, "_on_remove_item_confirmed");
|
||||
_confirmation_dialog->connect(
|
||||
"confirmed", callable_mp(this, &VoxelInstanceLibraryEditorPlugin::_on_remove_item_confirmed));
|
||||
base_control->add_child(_confirmation_dialog);
|
||||
|
||||
_info_dialog = memnew(AcceptDialog);
|
||||
|
@ -81,9 +86,10 @@ VoxelInstanceLibraryEditorPlugin::VoxelInstanceLibraryEditorPlugin(EditorNode *p
|
|||
for (List<String>::Element *E = extensions.front(); E; E = E->next()) {
|
||||
_open_scene_dialog->add_filter("*." + E->get());
|
||||
}
|
||||
_open_scene_dialog->set_mode(EditorFileDialog::MODE_OPEN_FILE);
|
||||
_open_scene_dialog->set_file_mode(EditorFileDialog::FILE_MODE_OPEN_FILE);
|
||||
base_control->add_child(_open_scene_dialog);
|
||||
_open_scene_dialog->connect("file_selected", this, "_on_open_scene_dialog_file_selected");
|
||||
_open_scene_dialog->connect(
|
||||
"file_selected", callable_mp(this, &VoxelInstanceLibraryEditorPlugin::_on_open_scene_dialog_file_selected));
|
||||
}
|
||||
|
||||
bool VoxelInstanceLibraryEditorPlugin::handles(Object *p_object) const {
|
||||
|
@ -99,7 +105,7 @@ void VoxelInstanceLibraryEditorPlugin::edit(Object *p_object) {
|
|||
void VoxelInstanceLibraryEditorPlugin::_notification(int p_what) {
|
||||
if (p_what == NOTIFICATION_ENTER_TREE) {
|
||||
Control *base_control = get_editor_interface()->get_base_control();
|
||||
_inspector_plugin.instance();
|
||||
_inspector_plugin.instantiate();
|
||||
_inspector_plugin->button_listener = this;
|
||||
_inspector_plugin->icon_provider = base_control;
|
||||
// TODO Why can other Godot plugins do this in the constructor??
|
||||
|
@ -120,14 +126,14 @@ void VoxelInstanceLibraryEditorPlugin::_on_button_pressed(int id) {
|
|||
ERR_FAIL_COND(_library.is_null());
|
||||
|
||||
Ref<VoxelInstanceLibraryItem> item;
|
||||
item.instance();
|
||||
item.instantiate();
|
||||
// Setup some defaults
|
||||
Ref<CubeMesh> mesh;
|
||||
mesh.instance();
|
||||
Ref<BoxMesh> mesh;
|
||||
mesh.instantiate();
|
||||
item->set_mesh(mesh, 0);
|
||||
item->set_lod_index(2);
|
||||
Ref<VoxelInstanceGenerator> generator;
|
||||
generator.instance();
|
||||
generator.instantiate();
|
||||
item->set_generator(generator);
|
||||
|
||||
const int item_id = _library->get_next_available_id();
|
||||
|
@ -229,12 +235,12 @@ void VoxelInstanceLibraryEditorPlugin::add_scene_item(String fpath) {
|
|||
ERR_FAIL_COND(scene.is_null());
|
||||
|
||||
Ref<VoxelInstanceLibrarySceneItem> item;
|
||||
item.instance();
|
||||
item.instantiate();
|
||||
// Setup some defaults
|
||||
item->set_lod_index(2);
|
||||
item->set_scene(scene);
|
||||
Ref<VoxelInstanceGenerator> generator;
|
||||
generator.instance();
|
||||
generator.instantiate();
|
||||
generator->set_density(0.01f); // Low density for scenes because that's heavier
|
||||
item->set_generator(generator);
|
||||
|
||||
|
@ -258,7 +264,7 @@ void VoxelInstanceLibraryEditorPlugin::update_multimesh_item_from_scene(String f
|
|||
Ref<VoxelInstanceLibraryItem> item = item_base;
|
||||
ERR_FAIL_COND_MSG(item.is_null(), "Item not using multimeshes");
|
||||
|
||||
Node *node = scene->instance();
|
||||
Node *node = scene->instantiate();
|
||||
ERR_FAIL_COND(node == nullptr);
|
||||
|
||||
Variant data_before = item->serialize_multimesh_item_properties();
|
||||
|
@ -275,9 +281,9 @@ void VoxelInstanceLibraryEditorPlugin::update_multimesh_item_from_scene(String f
|
|||
}
|
||||
|
||||
void VoxelInstanceLibraryEditorPlugin::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_button_pressed", "id"), &VoxelInstanceLibraryEditorPlugin::_on_button_pressed);
|
||||
ClassDB::bind_method(D_METHOD("_on_remove_item_confirmed"),
|
||||
&VoxelInstanceLibraryEditorPlugin::_on_remove_item_confirmed);
|
||||
ClassDB::bind_method(D_METHOD("_on_open_scene_dialog_file_selected", "fpath"),
|
||||
&VoxelInstanceLibraryEditorPlugin::_on_open_scene_dialog_file_selected);
|
||||
// ClassDB::bind_method(D_METHOD("_on_button_pressed", "id"),
|
||||
// &VoxelInstanceLibraryEditorPlugin::_on_button_pressed); ClassDB::bind_method(
|
||||
// D_METHOD("_on_remove_item_confirmed"), &VoxelInstanceLibraryEditorPlugin::_on_remove_item_confirmed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_open_scene_dialog_file_selected", "fpath"),
|
||||
// &VoxelInstanceLibraryEditorPlugin::_on_open_scene_dialog_file_selected);
|
||||
}
|
||||
|
|
|
@ -32,6 +32,8 @@ public:
|
|||
bool handles(Object *p_object) const override;
|
||||
void edit(Object *p_object) override;
|
||||
|
||||
void _on_button_pressed(int id);
|
||||
|
||||
private:
|
||||
void _notification(int p_what);
|
||||
|
||||
|
@ -39,7 +41,6 @@ private:
|
|||
void add_scene_item(String fpath);
|
||||
void update_multimesh_item_from_scene(String fpath, int item_id);
|
||||
|
||||
void _on_button_pressed(int id);
|
||||
void _on_remove_item_confirmed();
|
||||
void _on_open_scene_dialog_file_selected(String fpath);
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
#include "../graph/voxel_graph_node_inspector_wrapper.h"
|
||||
|
||||
#include <editor/editor_scale.h>
|
||||
#include <scene/3d/camera.h>
|
||||
#include <scene/3d/camera_3d.h>
|
||||
#include <scene/gui/menu_button.h>
|
||||
|
||||
class VoxelTerrainEditorTaskIndicator : public HBoxContainer {
|
||||
|
@ -36,7 +36,7 @@ public:
|
|||
// Set a monospace font.
|
||||
// Can't do this in constructor, fonts are not available then. Also the theme can change.
|
||||
for (unsigned int i = 0; i < _stats.size(); ++i) {
|
||||
_stats[i].label->add_font_override("font", get_font("source", "EditorFonts"));
|
||||
_stats[i].label->add_theme_font_override("font", get_theme_font("source", "EditorFonts"));
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -170,7 +170,8 @@ VoxelTerrainEditorPlugin::VoxelTerrainEditorPlugin(EditorNode *p_node) {
|
|||
}
|
||||
menu_button->get_popup()->add_separator();
|
||||
menu_button->get_popup()->add_item(TTR("About Voxel Tools..."), MENU_ABOUT);
|
||||
menu_button->get_popup()->connect("id_pressed", this, "_on_menu_item_selected");
|
||||
menu_button->get_popup()->connect(
|
||||
"id_pressed", callable_mp(this, &VoxelTerrainEditorPlugin::_on_menu_item_selected));
|
||||
menu_button->hide();
|
||||
add_control_to_container(CONTAINER_SPATIAL_EDITOR_MENU, menu_button);
|
||||
_menu_button = menu_button;
|
||||
|
@ -247,8 +248,8 @@ void VoxelTerrainEditorPlugin::set_node(VoxelNode *node) {
|
|||
// Using this to know when the node becomes really invalid, because ObjectID is unreliable in Godot 3.x,
|
||||
// and we may want to keep access to the node when we select some different kinds of objects.
|
||||
// Also moving the node around in the tree triggers exit/enter so have to listen for both.
|
||||
_node->disconnect("tree_entered", this, "_on_terrain_tree_entered");
|
||||
_node->disconnect("tree_exited", this, "_on_terrain_tree_exited");
|
||||
_node->disconnect("tree_entered", callable_mp(this, &VoxelTerrainEditorPlugin::_on_terrain_tree_entered));
|
||||
_node->disconnect("tree_exited", callable_mp(this, &VoxelTerrainEditorPlugin::_on_terrain_tree_exited));
|
||||
|
||||
VoxelLodTerrain *vlt = Object::cast_to<VoxelLodTerrain>(_node);
|
||||
if (vlt != nullptr) {
|
||||
|
@ -259,8 +260,10 @@ void VoxelTerrainEditorPlugin::set_node(VoxelNode *node) {
|
|||
_node = node;
|
||||
|
||||
if (_node != nullptr) {
|
||||
_node->connect("tree_entered", this, "_on_terrain_tree_entered", varray(_node));
|
||||
_node->connect("tree_exited", this, "_on_terrain_tree_exited", varray(_node));
|
||||
_node->connect(
|
||||
"tree_entered", callable_mp(this, &VoxelTerrainEditorPlugin::_on_terrain_tree_entered), varray(_node));
|
||||
_node->connect(
|
||||
"tree_exited", callable_mp(this, &VoxelTerrainEditorPlugin::_on_terrain_tree_exited), varray(_node));
|
||||
|
||||
VoxelLodTerrain *vlt = Object::cast_to<VoxelLodTerrain>(_node);
|
||||
if (vlt != nullptr) {
|
||||
|
@ -288,15 +291,16 @@ void VoxelTerrainEditorPlugin::make_visible(bool visible) {
|
|||
// So we'll need to check if _node is null all over the place
|
||||
}
|
||||
|
||||
bool VoxelTerrainEditorPlugin::forward_spatial_gui_input(Camera *p_camera, const Ref<InputEvent> &p_event) {
|
||||
VoxelServer::get_singleton()->set_viewer_distance(_editor_viewer_id, p_camera->get_zfar());
|
||||
EditorPlugin::AfterGUIInput VoxelTerrainEditorPlugin::forward_spatial_gui_input(
|
||||
Camera3D *p_camera, const Ref<InputEvent> &p_event) {
|
||||
VoxelServer::get_singleton()->set_viewer_distance(_editor_viewer_id, p_camera->get_far());
|
||||
_editor_camera_last_position = p_camera->get_global_transform().origin;
|
||||
|
||||
if (_editor_viewer_follows_camera) {
|
||||
VoxelServer::get_singleton()->set_viewer_position(_editor_viewer_id, _editor_camera_last_position);
|
||||
}
|
||||
|
||||
return false;
|
||||
return EditorPlugin::AFTER_GUI_INPUT_PASS;
|
||||
}
|
||||
|
||||
void VoxelTerrainEditorPlugin::_on_menu_item_selected(int id) {
|
||||
|
@ -339,7 +343,8 @@ void VoxelTerrainEditorPlugin::_on_terrain_tree_exited(Node *node) {
|
|||
}
|
||||
|
||||
void VoxelTerrainEditorPlugin::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("_on_menu_item_selected", "id"), &VoxelTerrainEditorPlugin::_on_menu_item_selected);
|
||||
ClassDB::bind_method(D_METHOD("_on_terrain_tree_entered"), &VoxelTerrainEditorPlugin::_on_terrain_tree_entered);
|
||||
ClassDB::bind_method(D_METHOD("_on_terrain_tree_exited"), &VoxelTerrainEditorPlugin::_on_terrain_tree_exited);
|
||||
// ClassDB::bind_method(D_METHOD("_on_menu_item_selected", "id"),
|
||||
// &VoxelTerrainEditorPlugin::_on_menu_item_selected);
|
||||
// ClassDB::bind_method(D_METHOD("_on_terrain_tree_entered"), &VoxelTerrainEditorPlugin::_on_terrain_tree_entered);
|
||||
// ClassDB::bind_method(D_METHOD("_on_terrain_tree_exited"), &VoxelTerrainEditorPlugin::_on_terrain_tree_exited);
|
||||
}
|
||||
|
|
|
@ -16,7 +16,7 @@ public:
|
|||
bool handles(Object *p_object) const override;
|
||||
void edit(Object *p_object) override;
|
||||
void make_visible(bool visible) override;
|
||||
bool forward_spatial_gui_input(Camera *p_camera, const Ref<InputEvent> &p_event) override;
|
||||
EditorPlugin::AfterGUIInput forward_spatial_gui_input(Camera3D *p_camera, const Ref<InputEvent> &p_event) override;
|
||||
|
||||
protected:
|
||||
void _notification(int p_what);
|
||||
|
@ -30,7 +30,7 @@ private:
|
|||
|
||||
static void _bind_methods();
|
||||
|
||||
enum MenuID {
|
||||
enum MenuID { //
|
||||
MENU_RESTART_STREAM,
|
||||
MENU_REMESH,
|
||||
MENU_STREAM_FOLLOW_CAMERA,
|
||||
|
|
|
@ -4,11 +4,11 @@
|
|||
|
||||
VoxEditorPlugin::VoxEditorPlugin(EditorNode *p_node) {
|
||||
Ref<VoxelVoxImporter> vox_scene_importer;
|
||||
vox_scene_importer.instance();
|
||||
vox_scene_importer.instantiate();
|
||||
//add_import_plugin(vox_importer);
|
||||
ResourceFormatImporter::get_singleton()->add_importer(vox_scene_importer);
|
||||
|
||||
Ref<VoxelVoxMeshImporter> vox_mesh_importer;
|
||||
vox_mesh_importer.instance();
|
||||
vox_mesh_importer.instantiate();
|
||||
ResourceFormatImporter::get_singleton()->add_importer(vox_mesh_importer);
|
||||
}
|
||||
|
|
|
@ -5,27 +5,21 @@
|
|||
namespace VoxImportUtils {
|
||||
|
||||
static void scale_surface(Array &surface, float scale) {
|
||||
PoolVector3Array positions = surface[Mesh::ARRAY_VERTEX];
|
||||
PackedVector3Array positions = surface[Mesh::ARRAY_VERTEX];
|
||||
// Avoiding stupid CoW, assuming this array holds the only instance of this vector
|
||||
surface[Mesh::ARRAY_VERTEX] = PoolVector3Array();
|
||||
{
|
||||
PoolVector3Array::Write w = positions.write();
|
||||
for (int vertex_index = 0; vertex_index < positions.size(); ++vertex_index) {
|
||||
w[vertex_index] *= scale;
|
||||
}
|
||||
surface[Mesh::ARRAY_VERTEX] = PackedVector3Array();
|
||||
for (int vertex_index = 0; vertex_index < positions.size(); ++vertex_index) {
|
||||
positions.write[vertex_index] *= scale;
|
||||
}
|
||||
surface[Mesh::ARRAY_VERTEX] = positions;
|
||||
}
|
||||
|
||||
static void offset_surface(Array &surface, Vector3 offset) {
|
||||
PoolVector3Array positions = surface[Mesh::ARRAY_VERTEX];
|
||||
PackedVector3Array positions = surface[Mesh::ARRAY_VERTEX];
|
||||
// Avoiding stupid CoW, assuming this array holds the only instance of this vector
|
||||
surface[Mesh::ARRAY_VERTEX] = PoolVector3Array();
|
||||
{
|
||||
PoolVector3Array::Write w = positions.write();
|
||||
for (int vertex_index = 0; vertex_index < positions.size(); ++vertex_index) {
|
||||
w[vertex_index] += offset;
|
||||
}
|
||||
surface[Mesh::ARRAY_VERTEX] = PackedVector3Array();
|
||||
for (int vertex_index = 0; vertex_index < positions.size(); ++vertex_index) {
|
||||
positions.write[vertex_index] += offset;
|
||||
}
|
||||
surface[Mesh::ARRAY_VERTEX] = positions;
|
||||
}
|
||||
|
@ -37,18 +31,18 @@ Ref<Mesh> build_mesh(const VoxelBufferInternal &voxels, VoxelMesher &mesher,
|
|||
VoxelMesher::Input input = { voxels, 0 };
|
||||
mesher.build(output, input);
|
||||
|
||||
if (output.surfaces.empty()) {
|
||||
if (output.surfaces.is_empty()) {
|
||||
return Ref<ArrayMesh>();
|
||||
}
|
||||
|
||||
Ref<ArrayMesh> mesh;
|
||||
mesh.instance();
|
||||
mesh.instantiate();
|
||||
|
||||
int surface_index = 0;
|
||||
for (int i = 0; i < output.surfaces.size(); ++i) {
|
||||
Array surface = output.surfaces[i];
|
||||
|
||||
if (surface.empty()) {
|
||||
if (surface.is_empty()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -65,7 +59,7 @@ Ref<Mesh> build_mesh(const VoxelBufferInternal &voxels, VoxelMesher &mesher,
|
|||
offset_surface(surface, p_offset);
|
||||
}
|
||||
|
||||
mesh->add_surface_from_arrays(output.primitive_type, surface, Array(), output.compression_flags);
|
||||
mesh->add_surface_from_arrays(output.primitive_type, surface, Array(), Dictionary(), output.mesh_flags);
|
||||
surface_index_to_material.push_back(i);
|
||||
++surface_index;
|
||||
}
|
||||
|
|
|
@ -7,9 +7,9 @@
|
|||
#include "../../util/profiling.h"
|
||||
#include "vox_import_funcs.h"
|
||||
|
||||
#include <core/os/file_access.h>
|
||||
#include <scene/3d/mesh_instance.h>
|
||||
#include <scene/3d/spatial.h>
|
||||
#include <core/io/file_access.h>
|
||||
#include <scene/3d/mesh_instance_3d.h>
|
||||
#include <scene/3d/node_3d.h>
|
||||
#include <scene/resources/mesh.h>
|
||||
#include <scene/resources/packed_scene.h>
|
||||
|
||||
|
@ -50,24 +50,26 @@ float VoxelVoxImporter::get_priority() const {
|
|||
// int VoxelVoxImporter::get_import_order() const {
|
||||
// }
|
||||
|
||||
void VoxelVoxImporter::get_import_options(List<ImportOption> *r_options, int p_preset) const {
|
||||
void VoxelVoxImporter::get_import_options(const String &p_path, List<ImportOption> *r_options, int p_preset) const {
|
||||
VoxelStringNames *sn = VoxelStringNames::get_singleton();
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::BOOL, sn->store_colors_in_texture), false));
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::REAL, sn->scale), 1.f));
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::FLOAT, sn->scale), 1.f));
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::BOOL, sn->enable_baked_lighting), true));
|
||||
}
|
||||
|
||||
bool VoxelVoxImporter::get_option_visibility(const String &p_option, const Map<StringName, Variant> &p_options) const {
|
||||
bool VoxelVoxImporter::get_option_visibility(
|
||||
const String &p_path, const String &p_option, const Map<StringName, Variant> &p_options) const {
|
||||
return true;
|
||||
}
|
||||
|
||||
static void add_mesh_instance(Ref<Mesh> mesh, Node *parent, Node *owner, Vector3 offset, bool p_enable_baked_lighting) {
|
||||
MeshInstance *mesh_instance = memnew(MeshInstance);
|
||||
MeshInstance3D *mesh_instance = memnew(MeshInstance3D);
|
||||
mesh_instance->set_mesh(mesh);
|
||||
parent->add_child(mesh_instance);
|
||||
mesh_instance->set_owner(owner);
|
||||
mesh_instance->set_translation(offset);
|
||||
mesh_instance->set_flag(GeometryInstance::FLAG_USE_BAKED_LIGHT, p_enable_baked_lighting);
|
||||
mesh_instance->set_position(offset);
|
||||
// Assuming `GI_MODE_DYNAMIC` means GIProbe and SDFGI?
|
||||
mesh_instance->set_gi_mode(GeometryInstance3D::GI_MODE_DYNAMIC);
|
||||
// TODO Colliders? Needs conventions or attributes probably.
|
||||
// But due to the nature of voxels, users may often prefer to place colliders themselves (slopes notably).
|
||||
}
|
||||
|
@ -77,35 +79,33 @@ struct VoxMesh {
|
|||
Vector3 pivot;
|
||||
};
|
||||
|
||||
static Error process_scene_node_recursively(const vox::Data &data, int node_id, Spatial *parent_node,
|
||||
Spatial *&root_node, int depth, const Vector<VoxMesh> &meshes, float scale, bool p_enable_baked_lighting) {
|
||||
static Error process_scene_node_recursively(const vox::Data &data, int node_id, Node3D *parent_node,
|
||||
Node3D *&out_root_node, int depth, const Vector<VoxMesh> &meshes, float scale, bool p_enable_baked_lighting) {
|
||||
//
|
||||
ERR_FAIL_COND_V(depth > 10, ERR_INVALID_DATA);
|
||||
const vox::Node *vox_node = data.get_node(node_id);
|
||||
|
||||
switch (vox_node->type) {
|
||||
case vox::Node::TYPE_TRANSFORM: {
|
||||
Spatial *node = memnew(Spatial);
|
||||
if (root_node == nullptr) {
|
||||
root_node = node;
|
||||
Node3D *node = memnew(Node3D);
|
||||
if (out_root_node == nullptr) {
|
||||
out_root_node = node;
|
||||
} else {
|
||||
ERR_FAIL_COND_V(parent_node == nullptr, ERR_BUG);
|
||||
parent_node->add_child(node);
|
||||
node->set_owner(root_node);
|
||||
node->set_owner(out_root_node);
|
||||
}
|
||||
const vox::TransformNode *vox_transform_node = reinterpret_cast<const vox::TransformNode *>(vox_node);
|
||||
node->set_transform(Transform(
|
||||
vox_transform_node->rotation.basis,
|
||||
vox_transform_node->position.to_vec3() * scale));
|
||||
process_scene_node_recursively(
|
||||
data, vox_transform_node->child_node_id, node, root_node, depth + 1, meshes, scale,
|
||||
p_enable_baked_lighting);
|
||||
node->set_transform(
|
||||
Transform3D(vox_transform_node->rotation.basis, Vector3(vox_transform_node->position) * scale));
|
||||
process_scene_node_recursively(data, vox_transform_node->child_node_id, node, out_root_node, depth + 1,
|
||||
meshes, scale, p_enable_baked_lighting);
|
||||
|
||||
// If the parent isn't anything special and has only one child,
|
||||
// it may be cleaner to flatten the hierarchy. We keep the root node unaffected.
|
||||
// TODO Any way to not need a string to check if a node is a specific class?
|
||||
if (node != root_node && node->get_class() == "Spatial" && node->get_child_count() == 1) {
|
||||
Spatial *child = Object::cast_to<Spatial>(node->get_child(0));
|
||||
if (node != out_root_node && node->get_class() == "Node3D" && node->get_child_count() == 1) {
|
||||
Node3D *child = Object::cast_to<Node3D>(node->get_child(0));
|
||||
if (child != nullptr) {
|
||||
node->remove_child(child);
|
||||
parent_node->remove_child(node);
|
||||
|
@ -113,7 +113,7 @@ static Error process_scene_node_recursively(const vox::Data &data, int node_id,
|
|||
// TODO Would be nice if I could just replace the node without any fuss but `replace_by` is too busy
|
||||
parent_node->add_child(child);
|
||||
// Removal from previous parent unsets the owner, so we have to set it again
|
||||
child->set_owner(root_node);
|
||||
child->set_owner(out_root_node);
|
||||
memdelete(node);
|
||||
}
|
||||
}
|
||||
|
@ -123,19 +123,19 @@ static Error process_scene_node_recursively(const vox::Data &data, int node_id,
|
|||
const vox::GroupNode *vox_group_node = reinterpret_cast<const vox::GroupNode *>(vox_node);
|
||||
for (unsigned int i = 0; i < vox_group_node->child_node_ids.size(); ++i) {
|
||||
const int child_node_id = vox_group_node->child_node_ids[i];
|
||||
process_scene_node_recursively(
|
||||
data, child_node_id, parent_node, root_node, depth + 1, meshes, scale, p_enable_baked_lighting);
|
||||
process_scene_node_recursively(data, child_node_id, parent_node, out_root_node, depth + 1, meshes,
|
||||
scale, p_enable_baked_lighting);
|
||||
}
|
||||
} break;
|
||||
|
||||
case vox::Node::TYPE_SHAPE: {
|
||||
ERR_FAIL_COND_V(parent_node == nullptr, ERR_BUG);
|
||||
ERR_FAIL_COND_V(root_node == nullptr, ERR_BUG);
|
||||
ERR_FAIL_COND_V(out_root_node == nullptr, ERR_BUG);
|
||||
const vox::ShapeNode *vox_shape_node = reinterpret_cast<const vox::ShapeNode *>(vox_node);
|
||||
const VoxMesh &mesh_data = meshes[vox_shape_node->model_id];
|
||||
ERR_FAIL_COND_V(mesh_data.mesh.is_null(), ERR_BUG);
|
||||
const Vector3 offset = -mesh_data.pivot * scale;
|
||||
add_mesh_instance(mesh_data.mesh, parent_node, root_node, offset, p_enable_baked_lighting);
|
||||
add_mesh_instance(mesh_data.mesh, parent_node, out_root_node, offset, p_enable_baked_lighting);
|
||||
} break;
|
||||
|
||||
default:
|
||||
|
@ -250,49 +250,49 @@ Error VoxelVoxImporter::import(const String &p_source_file, const String &p_save
|
|||
|
||||
// Get color palette
|
||||
Ref<VoxelColorPalette> palette;
|
||||
palette.instance();
|
||||
palette.instantiate();
|
||||
for (unsigned int i = 0; i < data.get_palette().size(); ++i) {
|
||||
Color8 color = data.get_palette()[i];
|
||||
palette->set_color8(i, color);
|
||||
}
|
||||
|
||||
Ref<VoxelMesherCubes> mesher;
|
||||
mesher.instance();
|
||||
mesher.instantiate();
|
||||
mesher->set_color_mode(VoxelMesherCubes::COLOR_MESHER_PALETTE);
|
||||
mesher->set_palette(palette);
|
||||
mesher->set_greedy_meshing_enabled(true);
|
||||
mesher->set_store_colors_in_texture(p_store_colors_in_textures);
|
||||
|
||||
FixedArray<Ref<SpatialMaterial>, 2> materials;
|
||||
FixedArray<Ref<StandardMaterial3D>, 2> materials;
|
||||
for (unsigned int i = 0; i < materials.size(); ++i) {
|
||||
Ref<SpatialMaterial> &mat = materials[i];
|
||||
mat.instance();
|
||||
Ref<StandardMaterial3D> &mat = materials[i];
|
||||
mat.instantiate();
|
||||
mat->set_roughness(1.f);
|
||||
if (!p_store_colors_in_textures) {
|
||||
// In this case we store colors in vertices
|
||||
mat->set_flag(SpatialMaterial::FLAG_ALBEDO_FROM_VERTEX_COLOR, true);
|
||||
mat->set_flag(StandardMaterial3D::FLAG_ALBEDO_FROM_VERTEX_COLOR, true);
|
||||
}
|
||||
}
|
||||
materials[1]->set_feature(SpatialMaterial::FEATURE_TRANSPARENT, true);
|
||||
materials[1]->set_transparency(StandardMaterial3D::TRANSPARENCY_ALPHA);
|
||||
|
||||
// Build meshes from voxel models
|
||||
for (unsigned int model_index = 0; model_index < data.get_model_count(); ++model_index) {
|
||||
const vox::Model &model = data.get_model(model_index);
|
||||
|
||||
VoxelBufferInternal voxels;
|
||||
voxels.create(model.size + Vector3i(VoxelMesherCubes::PADDING * 2));
|
||||
voxels.create(model.size + Vector3iUtil::create(VoxelMesherCubes::PADDING * 2));
|
||||
voxels.decompress_channel(VoxelBuffer::CHANNEL_COLOR);
|
||||
|
||||
Span<uint8_t> dst_color_indices;
|
||||
ERR_FAIL_COND_V(!voxels.get_channel_raw(VoxelBuffer::CHANNEL_COLOR, dst_color_indices), ERR_BUG);
|
||||
Span<const uint8_t> src_color_indices = to_span_const(model.color_indexes);
|
||||
copy_3d_region_zxy(dst_color_indices, voxels.get_size(), Vector3i(VoxelMesherCubes::PADDING),
|
||||
copy_3d_region_zxy(dst_color_indices, voxels.get_size(), Vector3iUtil::create(VoxelMesherCubes::PADDING),
|
||||
src_color_indices, model.size, Vector3i(), model.size);
|
||||
|
||||
std::vector<unsigned int> surface_index_to_material;
|
||||
Ref<Image> atlas;
|
||||
Ref<Mesh> mesh = VoxImportUtils::build_mesh(
|
||||
voxels, **mesher, surface_index_to_material, atlas, p_scale, Vector3());
|
||||
Ref<Mesh> mesh =
|
||||
VoxImportUtils::build_mesh(voxels, **mesher, surface_index_to_material, atlas, p_scale, Vector3());
|
||||
|
||||
if (mesh.is_null()) {
|
||||
continue;
|
||||
|
@ -320,16 +320,17 @@ Error VoxelVoxImporter::import(const String &p_source_file, const String &p_save
|
|||
for (unsigned int surface_index = 0; surface_index < surface_index_to_material.size(); ++surface_index) {
|
||||
const unsigned int material_index = surface_index_to_material[surface_index];
|
||||
CRASH_COND(material_index >= materials.size());
|
||||
Ref<SpatialMaterial> material = materials[material_index]->duplicate();
|
||||
Ref<StandardMaterial3D> material = materials[material_index]->duplicate();
|
||||
if (atlas.is_valid()) {
|
||||
// TODO Do I absolutely HAVE to load this texture back to memory AND renderer just so import works??
|
||||
//Ref<Texture> texture = ResourceLoader::load(atlas_path);
|
||||
// TODO THIS IS A WORKAROUND, it is not supposed to be an ImageTexture...
|
||||
// See earlier code, I could not find any way to reference a separate StreamTexture.
|
||||
Ref<ImageTexture> texture;
|
||||
texture.instance();
|
||||
texture->create_from_image(atlas, 0);
|
||||
material->set_texture(SpatialMaterial::TEXTURE_ALBEDO, texture);
|
||||
texture.instantiate();
|
||||
texture->create_from_image(atlas);
|
||||
material->set_texture(StandardMaterial3D::TEXTURE_ALBEDO, texture);
|
||||
material->set_texture_filter(StandardMaterial3D::TEXTURE_FILTER_NEAREST);
|
||||
}
|
||||
mesh->surface_set_material(surface_index, material);
|
||||
}
|
||||
|
@ -344,12 +345,13 @@ Error VoxelVoxImporter::import(const String &p_source_file, const String &p_save
|
|||
VoxMesh mesh_info;
|
||||
mesh_info.mesh = mesh;
|
||||
// In MagicaVoxel scene graph, pivots are at the center of models, not at the lower corner.
|
||||
// TODO I don't know if this is correct, but I could not find a reference saying how that pivot should be calculated
|
||||
mesh_info.pivot = (voxels.get_size() / 2 - Vector3i(1)).to_vec3();
|
||||
// TODO I don't know if this is correct, but I could not find a reference saying how that pivot should be
|
||||
// calculated
|
||||
mesh_info.pivot = (voxels.get_size() / 2 - Vector3iUtil::create(1));
|
||||
meshes.write[model_index] = mesh_info;
|
||||
}
|
||||
|
||||
Spatial *root_node = nullptr;
|
||||
Node3D *root_node = nullptr;
|
||||
if (data.get_root_node_id() != -1) {
|
||||
// Convert scene graph into a node tree
|
||||
process_scene_node_recursively(
|
||||
|
@ -358,7 +360,7 @@ Error VoxelVoxImporter::import(const String &p_source_file, const String &p_save
|
|||
|
||||
} else if (meshes.size() > 0) {
|
||||
// Some vox files don't have a scene graph
|
||||
root_node = memnew(Spatial);
|
||||
root_node = memnew(Node3D);
|
||||
const VoxMesh &mesh0 = meshes[0];
|
||||
add_mesh_instance(mesh0.mesh, root_node, root_node, Vector3(), p_enable_baked_lighting);
|
||||
}
|
||||
|
@ -371,8 +373,8 @@ Error VoxelVoxImporter::import(const String &p_source_file, const String &p_save
|
|||
// `FLAG_CHANGE_PATH` did not do what I thought it did.
|
||||
mesh->set_path(res_save_path);
|
||||
const Error mesh_save_err = ResourceSaver::save(res_save_path, mesh);
|
||||
ERR_FAIL_COND_V_MSG(mesh_save_err != OK, mesh_save_err,
|
||||
String("Failed to save {0}").format(varray(res_save_path)));
|
||||
ERR_FAIL_COND_V_MSG(
|
||||
mesh_save_err != OK, mesh_save_err, String("Failed to save {0}").format(varray(res_save_path)));
|
||||
}
|
||||
|
||||
root_node->set_name(p_save_path.get_file().get_basename());
|
||||
|
@ -381,7 +383,7 @@ Error VoxelVoxImporter::import(const String &p_source_file, const String &p_save
|
|||
{
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
Ref<PackedScene> scene;
|
||||
scene.instance();
|
||||
scene.instantiate();
|
||||
scene->pack(root_node);
|
||||
String scene_save_path = p_save_path + ".tscn";
|
||||
const Error save_err = ResourceSaver::save(scene_save_path, scene);
|
||||
|
|
|
@ -17,8 +17,9 @@ public:
|
|||
String get_resource_type() const override;
|
||||
float get_priority() const override;
|
||||
//int get_import_order() const override;
|
||||
void get_import_options(List<ImportOption> *r_options, int p_preset = 0) const override;
|
||||
bool get_option_visibility(const String &p_option, const Map<StringName, Variant> &p_options) const override;
|
||||
void get_import_options(const String &p_path, List<ImportOption> *r_options, int p_preset = 0) const override;
|
||||
bool get_option_visibility(
|
||||
const String &p_path, const String &p_option, const Map<StringName, Variant> &p_options) const override;
|
||||
|
||||
Error import(const String &p_source_file, const String &p_save_path, const Map<StringName, Variant> &p_options,
|
||||
List<String> *r_platform_variants, List<String> *r_gen_files, Variant *r_metadata = nullptr) override;
|
||||
|
|
|
@ -44,16 +44,16 @@ float VoxelVoxMeshImporter::get_priority() const {
|
|||
// int VoxelVoxMeshImporter::get_import_order() const {
|
||||
// }
|
||||
|
||||
void VoxelVoxMeshImporter::get_import_options(List<ImportOption> *r_options, int p_preset) const {
|
||||
void VoxelVoxMeshImporter::get_import_options(const String &p_path, List<ImportOption> *r_options, int p_preset) const {
|
||||
VoxelStringNames *sn = VoxelStringNames::get_singleton();
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::BOOL, sn->store_colors_in_texture), false));
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::REAL, sn->scale), 1.f));
|
||||
r_options->push_back(ImportOption(PropertyInfo(Variant::FLOAT, sn->scale), 1.f));
|
||||
r_options->push_back(ImportOption(
|
||||
PropertyInfo(Variant::INT, sn->pivot_mode, PROPERTY_HINT_ENUM, "LowerCorner,SceneOrigin,Center"), 1));
|
||||
}
|
||||
|
||||
bool VoxelVoxMeshImporter::get_option_visibility(const String &p_option,
|
||||
const Map<StringName, Variant> &p_options) const {
|
||||
bool VoxelVoxMeshImporter::get_option_visibility(
|
||||
const String &p_path, const String &p_option, const Map<StringName, Variant> &p_options) const {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -66,7 +66,7 @@ struct ForEachModelInstanceArgs {
|
|||
|
||||
template <typename F>
|
||||
static Error for_each_model_instance_in_scene_graph(
|
||||
const vox::Data &data, int node_id, Transform transform, int depth, F f) {
|
||||
const vox::Data &data, int node_id, Transform3D transform, int depth, F f) {
|
||||
//
|
||||
ERR_FAIL_COND_V(depth > 10, ERR_INVALID_DATA);
|
||||
const vox::Node *vox_node = data.get_node(node_id);
|
||||
|
@ -75,9 +75,8 @@ static Error for_each_model_instance_in_scene_graph(
|
|||
case vox::Node::TYPE_TRANSFORM: {
|
||||
const vox::TransformNode *vox_transform_node = reinterpret_cast<const vox::TransformNode *>(vox_node);
|
||||
// Calculate global transform of the child
|
||||
const Transform child_trans(
|
||||
transform.basis * vox_transform_node->rotation.basis,
|
||||
transform.xform(vox_transform_node->position.to_vec3()));
|
||||
const Transform3D child_trans(transform.basis * vox_transform_node->rotation.basis,
|
||||
transform.xform(vox_transform_node->position));
|
||||
for_each_model_instance_in_scene_graph(data, vox_transform_node->child_node_id, child_trans, depth + 1, f);
|
||||
} break;
|
||||
|
||||
|
@ -93,7 +92,7 @@ static Error for_each_model_instance_in_scene_graph(
|
|||
const vox::ShapeNode *vox_shape_node = reinterpret_cast<const vox::ShapeNode *>(vox_node);
|
||||
ForEachModelInstanceArgs args;
|
||||
args.model = &data.get_model(vox_shape_node->model_id);
|
||||
args.position = Vector3i::from_rounded(transform.origin);
|
||||
args.position = Vector3iUtil::from_rounded(transform.origin);
|
||||
args.basis = transform.basis;
|
||||
f(args);
|
||||
} break;
|
||||
|
@ -106,8 +105,7 @@ static Error for_each_model_instance_in_scene_graph(
|
|||
return OK;
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
void for_each_model_instance(const vox::Data &vox_data, F f) {
|
||||
template <typename F> void for_each_model_instance(const vox::Data &vox_data, F f) {
|
||||
if (vox_data.get_model_count() == 0) {
|
||||
return;
|
||||
}
|
||||
|
@ -121,7 +119,7 @@ void for_each_model_instance(const vox::Data &vox_data, F f) {
|
|||
f(args);
|
||||
return;
|
||||
}
|
||||
for_each_model_instance_in_scene_graph(vox_data, vox_data.get_root_node_id(), Transform(), 0, f);
|
||||
for_each_model_instance_in_scene_graph(vox_data, vox_data.get_root_node_id(), Transform3D(), 0, f);
|
||||
}
|
||||
|
||||
// Find intersecting or touching models, merge their voxels into the same grid, mesh the result, then combine meshes.
|
||||
|
@ -150,17 +148,18 @@ static void extract_model_instances(const vox::Data &vox_data, std::vector<Model
|
|||
src_color_indices = to_span_const(model.color_indexes);
|
||||
} else {
|
||||
IntBasis basis;
|
||||
basis.x = Vector3i::from_cast(args.basis.get_axis(Vector3::AXIS_X));
|
||||
basis.y = Vector3i::from_cast(args.basis.get_axis(Vector3::AXIS_Y));
|
||||
basis.z = Vector3i::from_cast(args.basis.get_axis(Vector3::AXIS_Z));
|
||||
basis.x = Vector3iUtil::from_cast(args.basis.get_axis(Vector3::AXIS_X));
|
||||
basis.y = Vector3iUtil::from_cast(args.basis.get_axis(Vector3::AXIS_Y));
|
||||
basis.z = Vector3iUtil::from_cast(args.basis.get_axis(Vector3::AXIS_Z));
|
||||
temp_voxels.resize(model.color_indexes.size());
|
||||
dst_size = transform_3d_array_zxy(
|
||||
to_span_const(model.color_indexes), to_span(temp_voxels), model.size, basis);
|
||||
dst_size =
|
||||
transform_3d_array_zxy(to_span_const(model.color_indexes), to_span(temp_voxels), model.size, basis);
|
||||
src_color_indices = to_span_const(temp_voxels);
|
||||
}
|
||||
|
||||
// TODO Optimization: implement transformation for VoxelBuffers so we can avoid using a temporary copy.
|
||||
// Didn't do it yet because VoxelBuffers also have metadata and the `transform_3d_array_zxy` function only works on arrays.
|
||||
// Didn't do it yet because VoxelBuffers also have metadata and the `transform_3d_array_zxy` function only works
|
||||
// on arrays.
|
||||
std::unique_ptr<VoxelBufferInternal> voxels = std::make_unique<VoxelBufferInternal>();
|
||||
voxels->create(dst_size);
|
||||
voxels->decompress_channel(VoxelBufferInternal::CHANNEL_COLOR);
|
||||
|
@ -178,8 +177,8 @@ static void extract_model_instances(const vox::Data &vox_data, std::vector<Model
|
|||
});
|
||||
}
|
||||
|
||||
static bool make_single_voxel_grid(Span<const ModelInstance> instances, Vector3i &out_origin,
|
||||
VoxelBufferInternal &out_voxels) {
|
||||
static bool make_single_voxel_grid(
|
||||
Span<const ModelInstance> instances, Vector3i &out_origin, VoxelBufferInternal &out_voxels) {
|
||||
// Determine total size
|
||||
const ModelInstance &first_instance = instances[0];
|
||||
Box3i bounding_box(first_instance.position, first_instance.voxels->get_size());
|
||||
|
@ -191,12 +190,12 @@ static bool make_single_voxel_grid(Span<const ModelInstance> instances, Vector3i
|
|||
// Extra sanity check
|
||||
// 3 gigabytes
|
||||
const size_t limit = 3'000'000'000ull;
|
||||
const size_t volume = bounding_box.size.volume();
|
||||
const size_t volume = Vector3iUtil::get_volume(bounding_box.size);
|
||||
ERR_FAIL_COND_V_MSG(volume > limit, false,
|
||||
String("Vox data is too big to be meshed as a single mesh ({0}: {0} bytes)")
|
||||
.format(varray(bounding_box.size.to_vec3(), SIZE_T_TO_VARIANT(volume))));
|
||||
.format(varray(bounding_box.size, SIZE_T_TO_VARIANT(volume))));
|
||||
|
||||
out_voxels.create(bounding_box.size + Vector3i(VoxelMesherCubes::PADDING * 2));
|
||||
out_voxels.create(bounding_box.size + Vector3iUtil::create(VoxelMesherCubes::PADDING * 2));
|
||||
out_voxels.set_channel_depth(VoxelBufferInternal::CHANNEL_COLOR, VoxelBufferInternal::DEPTH_8_BIT);
|
||||
out_voxels.decompress_channel(VoxelBufferInternal::CHANNEL_COLOR);
|
||||
|
||||
|
@ -204,7 +203,7 @@ static bool make_single_voxel_grid(Span<const ModelInstance> instances, Vector3i
|
|||
const ModelInstance &mi = instances[instance_index];
|
||||
ERR_FAIL_COND_V(mi.voxels == nullptr, false);
|
||||
out_voxels.copy_from(*mi.voxels, Vector3i(), mi.voxels->get_size(),
|
||||
mi.position - bounding_box.pos + Vector3i(VoxelMesherCubes::PADDING),
|
||||
mi.position - bounding_box.pos + Vector3iUtil::create(VoxelMesherCubes::PADDING),
|
||||
VoxelBufferInternal::CHANNEL_COLOR);
|
||||
}
|
||||
|
||||
|
@ -228,7 +227,7 @@ Error VoxelVoxMeshImporter::import(const String &p_source_file, const String &p_
|
|||
|
||||
// Get color palette
|
||||
Ref<VoxelColorPalette> palette;
|
||||
palette.instance();
|
||||
palette.instantiate();
|
||||
for (unsigned int i = 0; i < vox_data.get_palette().size(); ++i) {
|
||||
const Color8 color = vox_data.get_palette()[i];
|
||||
palette->set_color8(i, color);
|
||||
|
@ -261,7 +260,7 @@ Error VoxelVoxMeshImporter::import(const String &p_source_file, const String &p_
|
|||
model_instances.clear();
|
||||
|
||||
Ref<VoxelMesherCubes> mesher;
|
||||
mesher.instance();
|
||||
mesher.instantiate();
|
||||
mesher->set_color_mode(VoxelMesherCubes::COLOR_MESHER_PALETTE);
|
||||
mesher->set_palette(palette);
|
||||
mesher->set_greedy_meshing_enabled(true);
|
||||
|
@ -272,10 +271,10 @@ Error VoxelVoxMeshImporter::import(const String &p_source_file, const String &p_
|
|||
case PIVOT_LOWER_CORNER:
|
||||
break;
|
||||
case PIVOT_SCENE_ORIGIN:
|
||||
offset = bounding_box_origin.to_vec3();
|
||||
offset = bounding_box_origin;
|
||||
break;
|
||||
case PIVOT_CENTER:
|
||||
offset = -((voxels.get_size() - Vector3i(1)) / 2).to_vec3();
|
||||
offset = -((voxels.get_size() - Vector3iUtil::create(1)) / 2);
|
||||
break;
|
||||
default:
|
||||
ERR_FAIL_V(ERR_BUG);
|
||||
|
@ -310,17 +309,17 @@ Error VoxelVoxMeshImporter::import(const String &p_source_file, const String &p_
|
|||
// atlas->save_png(String("debug_atlas{0}.png").format(varray(model_index)));
|
||||
// }
|
||||
|
||||
FixedArray<Ref<SpatialMaterial>, 2> materials;
|
||||
FixedArray<Ref<StandardMaterial3D>, 2> materials;
|
||||
for (unsigned int i = 0; i < materials.size(); ++i) {
|
||||
Ref<SpatialMaterial> &mat = materials[i];
|
||||
mat.instance();
|
||||
Ref<StandardMaterial3D> &mat = materials[i];
|
||||
mat.instantiate();
|
||||
mat->set_roughness(1.f);
|
||||
if (!p_store_colors_in_textures) {
|
||||
// In this case we store colors in vertices
|
||||
mat->set_flag(SpatialMaterial::FLAG_ALBEDO_FROM_VERTEX_COLOR, true);
|
||||
mat->set_flag(StandardMaterial3D::FLAG_ALBEDO_FROM_VERTEX_COLOR, true);
|
||||
}
|
||||
}
|
||||
materials[1]->set_feature(SpatialMaterial::FEATURE_TRANSPARENT, true);
|
||||
materials[1]->set_transparency(StandardMaterial3D::TRANSPARENCY_ALPHA);
|
||||
|
||||
// Assign materials
|
||||
if (p_store_colors_in_textures) {
|
||||
|
@ -328,16 +327,17 @@ Error VoxelVoxMeshImporter::import(const String &p_source_file, const String &p_
|
|||
for (unsigned int surface_index = 0; surface_index < surface_index_to_material.size(); ++surface_index) {
|
||||
const unsigned int material_index = surface_index_to_material[surface_index];
|
||||
CRASH_COND(material_index >= materials.size());
|
||||
Ref<SpatialMaterial> material = materials[material_index]->duplicate();
|
||||
Ref<StandardMaterial3D> material = materials[material_index]->duplicate();
|
||||
if (atlas.is_valid()) {
|
||||
// TODO Do I absolutely HAVE to load this texture back to memory AND renderer just so import works??
|
||||
//Ref<Texture> texture = ResourceLoader::load(atlas_path);
|
||||
// TODO THIS IS A WORKAROUND, it is not supposed to be an ImageTexture...
|
||||
// See earlier code, I could not find any way to reference a separate StreamTexture.
|
||||
Ref<ImageTexture> texture;
|
||||
texture.instance();
|
||||
texture->create_from_image(atlas, 0);
|
||||
material->set_texture(SpatialMaterial::TEXTURE_ALBEDO, texture);
|
||||
texture.instantiate();
|
||||
texture->create_from_image(atlas);
|
||||
material->set_texture(StandardMaterial3D::TEXTURE_ALBEDO, texture);
|
||||
material->set_texture_filter(StandardMaterial3D::TEXTURE_FILTER_NEAREST);
|
||||
}
|
||||
mesh->surface_set_material(surface_index, material);
|
||||
}
|
||||
|
@ -354,8 +354,8 @@ Error VoxelVoxMeshImporter::import(const String &p_source_file, const String &p_
|
|||
VOXEL_PROFILE_SCOPE();
|
||||
String mesh_save_path = String("{0}.mesh").format(varray(p_save_path));
|
||||
const Error mesh_save_err = ResourceSaver::save(mesh_save_path, mesh);
|
||||
ERR_FAIL_COND_V_MSG(mesh_save_err != OK, mesh_save_err,
|
||||
String("Failed to save {0}").format(varray(mesh_save_path)));
|
||||
ERR_FAIL_COND_V_MSG(
|
||||
mesh_save_err != OK, mesh_save_err, String("Failed to save {0}").format(varray(mesh_save_path)));
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
|
|
@ -16,13 +16,14 @@ public:
|
|||
String get_resource_type() const override;
|
||||
float get_priority() const override;
|
||||
//int get_import_order() const override;
|
||||
void get_import_options(List<ImportOption> *r_options, int p_preset = 0) const override;
|
||||
bool get_option_visibility(const String &p_option, const Map<StringName, Variant> &p_options) const override;
|
||||
void get_import_options(const String &p_path, List<ImportOption> *r_options, int p_preset = 0) const override;
|
||||
bool get_option_visibility(
|
||||
const String &p_path, const String &p_option, const Map<StringName, Variant> &p_options) const override;
|
||||
|
||||
Error import(const String &p_source_file, const String &p_save_path, const Map<StringName, Variant> &p_options,
|
||||
List<String> *r_platform_variants, List<String> *r_gen_files, Variant *r_metadata = nullptr) override;
|
||||
|
||||
enum PivotMode {
|
||||
enum PivotMode { //
|
||||
PIVOT_LOWER_CORNER,
|
||||
PIVOT_SCENE_ORIGIN,
|
||||
PIVOT_CENTER,
|
||||
|
|
|
@ -10,11 +10,9 @@ namespace VoxelDebug {
|
|||
FixedArray<Ref<Mesh>, ID_COUNT> g_wirecubes;
|
||||
bool g_finalized = false;
|
||||
|
||||
template <typename T>
|
||||
void raw_copy_to(PoolVector<T> &dst, const T *src, unsigned int count) {
|
||||
template <typename T> void raw_copy_to(Vector<T> &dst, const T *src, unsigned int count) {
|
||||
dst.resize(count);
|
||||
typename PoolVector<T>::Write w = dst.write();
|
||||
memcpy(w.ptr(), src, count * sizeof(T));
|
||||
memcpy(dst.ptrw(), src, count * sizeof(T));
|
||||
}
|
||||
|
||||
static Color get_color(ColorID id) {
|
||||
|
@ -39,46 +37,24 @@ Ref<Mesh> get_wirecube(ColorID id) {
|
|||
Ref<Mesh> &wirecube = g_wirecubes[id];
|
||||
|
||||
if (wirecube.is_null()) {
|
||||
const Vector3 positions_raw[] = {
|
||||
Vector3(0, 0, 0),
|
||||
Vector3(1, 0, 0),
|
||||
Vector3(1, 0, 1),
|
||||
Vector3(0, 0, 1),
|
||||
Vector3(0, 1, 0),
|
||||
Vector3(1, 1, 0),
|
||||
Vector3(1, 1, 1),
|
||||
Vector3(0, 1, 1)
|
||||
};
|
||||
PoolVector3Array positions;
|
||||
const Vector3 positions_raw[] = { Vector3(0, 0, 0), Vector3(1, 0, 0), Vector3(1, 0, 1), Vector3(0, 0, 1),
|
||||
Vector3(0, 1, 0), Vector3(1, 1, 0), Vector3(1, 1, 1), Vector3(0, 1, 1) };
|
||||
PackedVector3Array positions;
|
||||
raw_copy_to(positions, positions_raw, 8);
|
||||
|
||||
Color white(1.0, 1.0, 1.0);
|
||||
PoolColorArray colors;
|
||||
PackedColorArray colors;
|
||||
colors.resize(positions.size());
|
||||
{
|
||||
PoolColorArray::Write w = colors.write();
|
||||
for (int i = 0; i < colors.size(); ++i) {
|
||||
w[i] = white;
|
||||
}
|
||||
for (int i = 0; i < colors.size(); ++i) {
|
||||
colors.write[i] = white;
|
||||
}
|
||||
|
||||
const int indices_raw[] = {
|
||||
0, 1,
|
||||
1, 2,
|
||||
2, 3,
|
||||
3, 0,
|
||||
const int indices_raw[] = { 0, 1, 1, 2, 2, 3, 3, 0,
|
||||
|
||||
4, 5,
|
||||
5, 6,
|
||||
6, 7,
|
||||
7, 4,
|
||||
4, 5, 5, 6, 6, 7, 7, 4,
|
||||
|
||||
0, 4,
|
||||
1, 5,
|
||||
2, 6,
|
||||
3, 7
|
||||
};
|
||||
PoolIntArray indices;
|
||||
0, 4, 1, 5, 2, 6, 3, 7 };
|
||||
PackedInt32Array indices;
|
||||
raw_copy_to(indices, indices_raw, 24);
|
||||
|
||||
Array arrays;
|
||||
|
@ -89,10 +65,10 @@ Ref<Mesh> get_wirecube(ColorID id) {
|
|||
Ref<ArrayMesh> mesh = memnew(ArrayMesh);
|
||||
mesh->add_surface_from_arrays(Mesh::PRIMITIVE_LINES, arrays);
|
||||
|
||||
Ref<SpatialMaterial> mat;
|
||||
mat.instance();
|
||||
Ref<StandardMaterial3D> mat;
|
||||
mat.instantiate();
|
||||
mat->set_albedo(get_color(id));
|
||||
mat->set_flag(SpatialMaterial::FLAG_UNSHADED, true);
|
||||
mat->set_shading_mode(StandardMaterial3D::SHADING_MODE_UNSHADED);
|
||||
mesh->surface_set_material(0, mat);
|
||||
|
||||
wirecube = mesh;
|
||||
|
@ -117,7 +93,7 @@ public:
|
|||
// TODO When shadow casting is on, directional shadows completely break.
|
||||
// The reason is still unknown.
|
||||
// It should be off anyways, but it's rather concerning.
|
||||
_mesh_instance.set_cast_shadows_setting(VisualServer::SHADOW_CASTING_SETTING_OFF);
|
||||
_mesh_instance.set_cast_shadows_setting(RenderingServer::SHADOW_CASTING_SETTING_OFF);
|
||||
}
|
||||
|
||||
void set_mesh(Ref<Mesh> mesh) {
|
||||
|
@ -127,7 +103,7 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
void set_transform(Transform t) {
|
||||
void set_transform(Transform3D t) {
|
||||
if (_transform != t) {
|
||||
_transform = t;
|
||||
_mesh_instance.set_transform(t);
|
||||
|
@ -141,12 +117,12 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
void set_world(World *world) {
|
||||
void set_world(World3D *world) {
|
||||
_mesh_instance.set_world(world);
|
||||
}
|
||||
|
||||
private:
|
||||
Transform _transform;
|
||||
Transform3D _transform;
|
||||
bool _visible = true;
|
||||
Ref<Mesh> _mesh;
|
||||
DirectMeshInstance _mesh_instance;
|
||||
|
@ -166,7 +142,7 @@ void DebugRenderer::clear() {
|
|||
_mm_renderer.clear();
|
||||
}
|
||||
|
||||
void DebugRenderer::set_world(World *world) {
|
||||
void DebugRenderer::set_world(World3D *world) {
|
||||
_world = world;
|
||||
for (auto it = _items.begin(); it != _items.end(); ++it) {
|
||||
(*it)->set_world(world);
|
||||
|
@ -182,7 +158,7 @@ void DebugRenderer::begin() {
|
|||
_mm_renderer.begin();
|
||||
}
|
||||
|
||||
void DebugRenderer::draw_box(const Transform &t, ColorID color) {
|
||||
void DebugRenderer::draw_box(const Transform3D &t, ColorID color) {
|
||||
// Pick an existing item, or create one
|
||||
DebugRendererItem *item;
|
||||
if (_current >= _items.size()) {
|
||||
|
@ -200,7 +176,7 @@ void DebugRenderer::draw_box(const Transform &t, ColorID color) {
|
|||
++_current;
|
||||
}
|
||||
|
||||
void DebugRenderer::draw_box_mm(const Transform &t, Color8 color) {
|
||||
void DebugRenderer::draw_box_mm(const Transform3D &t, Color8 color) {
|
||||
_mm_renderer.draw_box(t, color);
|
||||
}
|
||||
|
||||
|
@ -222,21 +198,23 @@ DebugMultiMeshRenderer::DebugMultiMeshRenderer() {
|
|||
// TODO When shadow casting is on, directional shadows completely break.
|
||||
// The reason is still unknown.
|
||||
// It should be off anyways, but it's rather concerning.
|
||||
_multimesh_instance.set_cast_shadows_setting(VisualServer::SHADOW_CASTING_SETTING_OFF);
|
||||
_multimesh.instance();
|
||||
_multimesh_instance.set_cast_shadows_setting(RenderingServer::SHADOW_CASTING_SETTING_OFF);
|
||||
_multimesh.instantiate();
|
||||
Ref<Mesh> wirecube = get_wirecube(ID_WHITE);
|
||||
_multimesh->set_mesh(wirecube);
|
||||
_multimesh->set_transform_format(MultiMesh::TRANSFORM_3D);
|
||||
_multimesh->set_color_format(MultiMesh::COLOR_8BIT);
|
||||
_multimesh->set_custom_data_format(MultiMesh::CUSTOM_DATA_NONE);
|
||||
// TODO Optimize: Godot needs to bring back 8-bit color attributes on multimesh, 32-bit colors are too much
|
||||
//_multimesh->set_color_format(MultiMesh::COLOR_8BIT);
|
||||
_multimesh->set_use_colors(true);
|
||||
_multimesh->set_use_custom_data(false);
|
||||
_multimesh_instance.set_multimesh(_multimesh);
|
||||
_material.instance();
|
||||
_material->set_flag(SpatialMaterial::FLAG_UNSHADED, true);
|
||||
_material->set_flag(SpatialMaterial::FLAG_ALBEDO_FROM_VERTEX_COLOR, true);
|
||||
_material.instantiate();
|
||||
_material->set_shading_mode(StandardMaterial3D::SHADING_MODE_UNSHADED);
|
||||
_material->set_flag(StandardMaterial3D::FLAG_ALBEDO_FROM_VERTEX_COLOR, true);
|
||||
_multimesh_instance.set_material_override(_material);
|
||||
}
|
||||
|
||||
void DebugMultiMeshRenderer::set_world(World *world) {
|
||||
void DebugMultiMeshRenderer::set_world(World3D *world) {
|
||||
_multimesh_instance.set_world(world);
|
||||
_world = world;
|
||||
}
|
||||
|
@ -247,22 +225,23 @@ void DebugMultiMeshRenderer::begin() {
|
|||
_inside_block = true;
|
||||
}
|
||||
|
||||
void DebugMultiMeshRenderer::draw_box(const Transform &t, Color8 color) {
|
||||
_items.push_back(DirectMultiMeshInstance::TransformAndColor8{ t, color });
|
||||
void DebugMultiMeshRenderer::draw_box(const Transform3D &t, Color8 color) {
|
||||
_items.push_back(DirectMultiMeshInstance::TransformAndColor32{ t, color });
|
||||
}
|
||||
|
||||
void DebugMultiMeshRenderer::end() {
|
||||
ERR_FAIL_COND(!_inside_block);
|
||||
_inside_block = false;
|
||||
|
||||
DirectMultiMeshInstance::make_transform_and_color8_3d_bulk_array(to_span_const(_items), _bulk_array);
|
||||
DirectMultiMeshInstance::make_transform_and_color32_3d_bulk_array(to_span_const(_items), _bulk_array);
|
||||
if (_items.size() != static_cast<unsigned int>(_multimesh->get_instance_count())) {
|
||||
_multimesh->set_instance_count(_items.size());
|
||||
}
|
||||
|
||||
// Apparently Godot doesn't like empty bulk arrays, it breaks RasterizerStorageGLES3
|
||||
if (_items.size() > 0) {
|
||||
_multimesh->set_as_bulk_array(_bulk_array);
|
||||
//_multimesh->set_as_bulk_array(_bulk_array);
|
||||
RenderingServer::get_singleton()->multimesh_set_buffer(_multimesh->get_rid(), _bulk_array);
|
||||
}
|
||||
|
||||
_items.clear();
|
||||
|
|
|
@ -2,12 +2,12 @@
|
|||
#define VOXEL_DEBUG_H
|
||||
|
||||
#include "../util/godot/direct_multimesh_instance.h"
|
||||
#include <core/reference.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
#include <vector>
|
||||
|
||||
class Mesh;
|
||||
class DirectMeshInstance;
|
||||
class World;
|
||||
class World3D;
|
||||
|
||||
namespace VoxelDebug {
|
||||
|
||||
|
@ -26,20 +26,20 @@ class DebugMultiMeshRenderer {
|
|||
public:
|
||||
DebugMultiMeshRenderer();
|
||||
|
||||
void set_world(World *world);
|
||||
void set_world(World3D *world);
|
||||
void begin();
|
||||
void draw_box(const Transform &t, Color8 color);
|
||||
void draw_box(const Transform3D &t, Color8 color);
|
||||
void end();
|
||||
void clear();
|
||||
|
||||
private:
|
||||
std::vector<DirectMultiMeshInstance::TransformAndColor8> _items;
|
||||
std::vector<DirectMultiMeshInstance::TransformAndColor32> _items;
|
||||
Ref<MultiMesh> _multimesh;
|
||||
DirectMultiMeshInstance _multimesh_instance;
|
||||
World *_world = nullptr;
|
||||
World3D *_world = nullptr;
|
||||
bool _inside_block = false;
|
||||
PoolRealArray _bulk_array;
|
||||
Ref<SpatialMaterial> _material;
|
||||
PackedFloat32Array _bulk_array;
|
||||
Ref<StandardMaterial3D> _material;
|
||||
};
|
||||
|
||||
class DebugRendererItem;
|
||||
|
@ -48,11 +48,11 @@ class DebugRenderer {
|
|||
public:
|
||||
~DebugRenderer();
|
||||
|
||||
void set_world(World *world);
|
||||
void set_world(World3D *world);
|
||||
|
||||
void begin();
|
||||
void draw_box(const Transform &t, ColorID color);
|
||||
void draw_box_mm(const Transform &t, Color8 color);
|
||||
void draw_box(const Transform3D &t, ColorID color);
|
||||
void draw_box_mm(const Transform3D &t, Color8 color);
|
||||
void end();
|
||||
void clear();
|
||||
|
||||
|
@ -60,7 +60,7 @@ private:
|
|||
std::vector<DebugRendererItem *> _items;
|
||||
unsigned int _current = 0;
|
||||
bool _inside_block = false;
|
||||
World *_world = nullptr;
|
||||
World3D *_world = nullptr;
|
||||
DebugMultiMeshRenderer _mm_renderer;
|
||||
};
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#include "image_range_grid.h"
|
||||
#include "range_utility.h"
|
||||
|
||||
#include <core/image.h>
|
||||
#include <core/io/image.h>
|
||||
|
||||
ImageRangeGrid::~ImageRangeGrid() {
|
||||
clear();
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#include "program_graph.h"
|
||||
#include <core/os/file_access.h>
|
||||
#include <core/resource.h>
|
||||
#include <core/variant.h>
|
||||
#include <core/io/file_access.h>
|
||||
#include <core/io/resource.h>
|
||||
#include <core/variant/variant.h>
|
||||
#include <unordered_set>
|
||||
|
||||
template <typename T>
|
||||
|
@ -429,19 +429,6 @@ uint32_t ProgramGraph::find_node_by_name(StringName name) const {
|
|||
// }
|
||||
//}
|
||||
|
||||
PoolVector<int> ProgramGraph::get_node_ids() const {
|
||||
PoolIntArray ids;
|
||||
ids.resize(_nodes.size());
|
||||
{
|
||||
PoolIntArray::Write w = ids.write();
|
||||
int i = 0;
|
||||
for (auto it = _nodes.begin(); it != _nodes.end(); ++it) {
|
||||
w[i++] = it->first;
|
||||
}
|
||||
}
|
||||
return ids;
|
||||
}
|
||||
|
||||
int ProgramGraph::get_nodes_count() const {
|
||||
return _nodes.size();
|
||||
}
|
||||
|
|
|
@ -1,9 +1,8 @@
|
|||
#ifndef PROGRAM_GRAPH_H
|
||||
#define PROGRAM_GRAPH_H
|
||||
|
||||
#include <core/hashfuncs.h>
|
||||
#include <core/math/vector2.h>
|
||||
#include <core/pool_vector.h>
|
||||
#include <core/templates/hashfuncs.h>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
|
||||
|
@ -67,6 +66,13 @@ public:
|
|||
void find_depth_first(uint32_t start_node_id, std::vector<uint32_t> &order) const;
|
||||
void find_terminal_nodes(std::vector<uint32_t> &node_ids) const;
|
||||
|
||||
template <typename F>
|
||||
inline void for_each_node_id(F f) const {
|
||||
for (auto it = _nodes.begin(); it != _nodes.end(); ++it) {
|
||||
f(it->first);
|
||||
}
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
inline void for_each_node_const(F f) const {
|
||||
for (auto it = _nodes.begin(); it != _nodes.end(); ++it) {
|
||||
|
@ -91,7 +97,6 @@ public:
|
|||
|
||||
uint32_t find_node_by_name(StringName name) const;
|
||||
|
||||
PoolVector<int> get_node_ids() const;
|
||||
uint32_t generate_node_id();
|
||||
|
||||
int get_nodes_count() const;
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#include "../../util/math/sdf.h"
|
||||
#include "../../util/noise/fast_noise_lite.h"
|
||||
|
||||
#include <core/image.h>
|
||||
#include <core/io/image.h>
|
||||
#include <modules/opensimplex/open_simplex_noise.h>
|
||||
#include <scene/resources/curve.h>
|
||||
|
||||
|
@ -21,14 +21,14 @@ inline Interval get_noise_range_2d(Noise_F noise_func, const Interval &x, const
|
|||
|
||||
const float diag = Math::sqrt(squared(x.length()) + squared(y.length()));
|
||||
|
||||
return Interval(
|
||||
return Interval( //
|
||||
::max(mid_value - max_derivative_half_diagonal * diag, -1.f),
|
||||
::min(mid_value + max_derivative_half_diagonal * diag, 1.f));
|
||||
}
|
||||
|
||||
template <typename Noise_F>
|
||||
inline Interval get_noise_range_3d(Noise_F noise_func, const Interval &x, const Interval &y, const Interval &z,
|
||||
float max_derivative) {
|
||||
inline Interval get_noise_range_3d(
|
||||
Noise_F noise_func, const Interval &x, const Interval &y, const Interval &z, float max_derivative) {
|
||||
const float max_derivative_half_diagonal = 0.5f * max_derivative * Math_SQRT2;
|
||||
|
||||
const float mid_x = 0.5 * (x.min + x.max);
|
||||
|
@ -38,22 +38,21 @@ inline Interval get_noise_range_3d(Noise_F noise_func, const Interval &x, const
|
|||
|
||||
const float diag = Math::sqrt(squared(x.length()) + squared(y.length()) + squared(z.length()));
|
||||
|
||||
return Interval(
|
||||
return Interval( //
|
||||
::max(mid_value - max_derivative_half_diagonal * diag, -1.f),
|
||||
::min(mid_value + max_derivative_half_diagonal * diag, 1.f));
|
||||
}
|
||||
|
||||
Interval get_osn_octave_range_2d(OpenSimplexNoise *noise, const Interval &p_x, const Interval &p_y, int octave) {
|
||||
return get_noise_range_2d(
|
||||
[octave, noise](float x, float y) { return noise->_get_octave_noise_2d(octave, x, y); },
|
||||
p_x, p_y, 2.35f);
|
||||
[octave, noise](float x, float y) { return noise->_get_octave_noise_2d(octave, x, y); }, p_x, p_y, 2.35f);
|
||||
}
|
||||
|
||||
Interval get_osn_octave_range_3d(
|
||||
OpenSimplexNoise *noise, const Interval &p_x, const Interval &p_y, const Interval &p_z, int octave) {
|
||||
return get_noise_range_3d(
|
||||
[octave, noise](float x, float y, float z) { return noise->_get_octave_noise_3d(octave, x, y, z); },
|
||||
p_x, p_y, p_z, 2.5f);
|
||||
[octave, noise](float x, float y, float z) { return noise->_get_octave_noise_3d(octave, x, y, z); }, p_x,
|
||||
p_y, p_z, 2.5f);
|
||||
}
|
||||
|
||||
Interval get_osn_range_2d(OpenSimplexNoise *noise, Interval x, Interval y) {
|
||||
|
@ -238,8 +237,6 @@ Interval get_heightmap_range(Image &im, Rect2i rect) {
|
|||
case Image::FORMAT_RGBAF: {
|
||||
Interval r;
|
||||
|
||||
im.lock();
|
||||
|
||||
r.min = im.get_pixel(0, 0).r;
|
||||
r.max = r.min;
|
||||
|
||||
|
@ -252,8 +249,6 @@ Interval get_heightmap_range(Image &im, Rect2i rect) {
|
|||
}
|
||||
}
|
||||
|
||||
im.unlock();
|
||||
|
||||
return r;
|
||||
} break;
|
||||
|
||||
|
@ -314,8 +309,7 @@ SdfAffectingArguments sdf_polynomial_smooth_union_side(Interval a, Interval b, f
|
|||
return SDF_BOTH;
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
inline Interval sdf_smooth_op(Interval b, Interval a, float s, F smooth_op_func) {
|
||||
template <typename F> inline Interval sdf_smooth_op(Interval b, Interval a, float s, F smooth_op_func) {
|
||||
// Smooth union and subtract are a generalization of `min(a, b)` and `max(-a, b)`, with a smooth junction.
|
||||
// That junction runs in a diagonal crossing zero (with equation `y = -x`).
|
||||
// Areas on the two sides of the junction are monotonic, i.e their derivatives should never cross zero,
|
||||
|
@ -526,21 +520,19 @@ void fnl_transform_noise_coordinate(const fast_noise_lite::FastNoiseLite &fn, In
|
|||
}
|
||||
}
|
||||
|
||||
Interval fnl_single_opensimplex2(const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y,
|
||||
Interval p_z) {
|
||||
Interval fnl_single_opensimplex2(
|
||||
const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y, Interval p_z) {
|
||||
// According to OpenSimplex2 author, the 3D version is supposed to have a max derivative around 4.23718
|
||||
// https://www.wolframalpha.com/input/?i=max+d%2Fdx+32.69428253173828125+*+x+*+%28%280.6-x%5E2%29%5E4%29+from+-0.6+to+0.6
|
||||
// But empiric measures have shown it around 8. Discontinuities do exist in this noise though,
|
||||
// which makes this measuring harder
|
||||
return get_noise_range_3d(
|
||||
[&fn, seed](float x, float y, float z) { return fn.SingleOpenSimplex2(seed, x, y, z); },
|
||||
return get_noise_range_3d([&fn, seed](float x, float y, float z) { return fn.SingleOpenSimplex2(seed, x, y, z); },
|
||||
p_x, p_y, p_z, 4.23718f);
|
||||
}
|
||||
|
||||
Interval fnl_single_opensimplex2s(const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y,
|
||||
Interval p_z) {
|
||||
return get_noise_range_3d(
|
||||
[&fn, seed](float x, float y, float z) { return fn.SingleOpenSimplex2(seed, x, y, z); },
|
||||
Interval fnl_single_opensimplex2s(
|
||||
const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y, Interval p_z) {
|
||||
return get_noise_range_3d([&fn, seed](float x, float y, float z) { return fn.SingleOpenSimplex2(seed, x, y, z); },
|
||||
// Max derivative found from empiric tests
|
||||
p_x, p_y, p_z, 2.5f);
|
||||
}
|
||||
|
@ -553,26 +545,23 @@ Interval fnl_single_cellular(const FastNoiseLite *noise, Interval x, Interval y,
|
|||
return get_fnl_cellular_range(noise);
|
||||
}
|
||||
|
||||
Interval fnl_single_perlin(const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y,
|
||||
Interval p_z) {
|
||||
return get_noise_range_3d(
|
||||
[&fn, seed](float x, float y, float z) { return fn.SinglePerlin(seed, x, y, z); },
|
||||
Interval fnl_single_perlin(
|
||||
const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y, Interval p_z) {
|
||||
return get_noise_range_3d([&fn, seed](float x, float y, float z) { return fn.SinglePerlin(seed, x, y, z); },
|
||||
// Max derivative found from empiric tests
|
||||
p_x, p_y, p_z, 3.2f);
|
||||
}
|
||||
|
||||
Interval fnl_single_value_cubic(const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y,
|
||||
Interval p_z) {
|
||||
return get_noise_range_3d(
|
||||
[&fn, seed](float x, float y, float z) { return fn.SingleValueCubic(seed, x, y, z); },
|
||||
Interval fnl_single_value_cubic(
|
||||
const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y, Interval p_z) {
|
||||
return get_noise_range_3d([&fn, seed](float x, float y, float z) { return fn.SingleValueCubic(seed, x, y, z); },
|
||||
// Max derivative found from empiric tests
|
||||
p_x, p_y, p_z, 1.2f);
|
||||
}
|
||||
|
||||
Interval fnl_single_value(const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y,
|
||||
Interval p_z) {
|
||||
return get_noise_range_3d(
|
||||
[&fn, seed](float x, float y, float z) { return fn.SingleValue(seed, x, y, z); },
|
||||
Interval fnl_single_value(
|
||||
const fast_noise_lite::FastNoiseLite &fn, int seed, Interval p_x, Interval p_y, Interval p_z) {
|
||||
return get_noise_range_3d([&fn, seed](float x, float y, float z) { return fn.SingleValue(seed, x, y, z); },
|
||||
// Max derivative found from empiric tests
|
||||
p_x, p_y, p_z, 3.0f);
|
||||
}
|
||||
|
@ -610,9 +599,7 @@ Interval fnl_gen_fractal_fbm(const FastNoiseLite *p_noise, Interval x, Interval
|
|||
for (int i = 0; i < fn.mOctaves; i++) {
|
||||
Interval noise = fnl_gen_noise_single(p_noise, seed++, x, y, z);
|
||||
sum += noise * amp;
|
||||
amp *= lerp(
|
||||
Interval::from_single_value(1.0f),
|
||||
(noise + Interval::from_single_value(1.0f)) * 0.5f,
|
||||
amp *= lerp(Interval::from_single_value(1.0f), (noise + Interval::from_single_value(1.0f)) * 0.5f,
|
||||
Interval::from_single_value(fn.mWeightedStrength));
|
||||
|
||||
x *= fn.mLacunarity;
|
||||
|
@ -635,9 +622,7 @@ Interval fnl_gen_fractal_ridged(const FastNoiseLite *p_noise, Interval x, Interv
|
|||
for (int i = 0; i < fn.mOctaves; i++) {
|
||||
Interval noise = abs(fnl_gen_noise_single(p_noise, seed++, x, y, z));
|
||||
sum += (noise * -2 + 1) * amp;
|
||||
amp *= lerp(
|
||||
Interval::from_single_value(1.0f),
|
||||
Interval::from_single_value(1.0f) - noise,
|
||||
amp *= lerp(Interval::from_single_value(1.0f), Interval::from_single_value(1.0f) - noise,
|
||||
Interval::from_single_value(fn.mWeightedStrength));
|
||||
|
||||
x *= fn.mLacunarity;
|
||||
|
@ -701,18 +686,12 @@ Interval get_fnl_range_3d(const FastNoiseLite *noise, Interval x, Interval y, In
|
|||
Interval2 get_fnl_gradient_range_2d(const FastNoiseLiteGradient *noise, Interval x, Interval y) {
|
||||
// TODO More precise analysis
|
||||
const float amp = Math::abs(noise->get_amplitude());
|
||||
return Interval2{
|
||||
Interval{ x.min - amp, x.max + amp },
|
||||
Interval{ y.min - amp, y.max + amp }
|
||||
};
|
||||
return Interval2{ Interval{ x.min - amp, x.max + amp }, Interval{ y.min - amp, y.max + amp } };
|
||||
}
|
||||
|
||||
Interval3 get_fnl_gradient_range_3d(const FastNoiseLiteGradient *noise, Interval x, Interval y, Interval z) {
|
||||
// TODO More precise analysis
|
||||
const float amp = Math::abs(noise->get_amplitude());
|
||||
return Interval3{
|
||||
Interval{ x.min - amp, x.max + amp },
|
||||
Interval{ y.min - amp, y.max + amp },
|
||||
Interval{ z.min - amp, z.max + amp }
|
||||
};
|
||||
return Interval3{ Interval{ x.min - amp, x.max + amp }, Interval{ y.min - amp, y.max + amp },
|
||||
Interval{ z.min - amp, z.max + amp } };
|
||||
}
|
||||
|
|
|
@ -10,8 +10,7 @@ const char *VoxelGeneratorGraph::SIGNAL_NODE_NAME_CHANGED = "node_name_changed";
|
|||
|
||||
thread_local VoxelGeneratorGraph::Cache VoxelGeneratorGraph::_cache;
|
||||
|
||||
VoxelGeneratorGraph::VoxelGeneratorGraph() {
|
||||
}
|
||||
VoxelGeneratorGraph::VoxelGeneratorGraph() {}
|
||||
|
||||
VoxelGeneratorGraph::~VoxelGeneratorGraph() {
|
||||
clear();
|
||||
|
@ -26,8 +25,8 @@ void VoxelGeneratorGraph::clear() {
|
|||
}
|
||||
}
|
||||
|
||||
static ProgramGraph::Node *create_node_internal(ProgramGraph &graph,
|
||||
VoxelGeneratorGraph::NodeTypeID type_id, Vector2 position, uint32_t id) {
|
||||
static ProgramGraph::Node *create_node_internal(
|
||||
ProgramGraph &graph, VoxelGeneratorGraph::NodeTypeID type_id, Vector2 position, uint32_t id) {
|
||||
const VoxelGraphNodeDB::NodeType &type = VoxelGraphNodeDB::get_singleton()->get_type(type_id);
|
||||
|
||||
ProgramGraph::Node *node = graph.create_node(type_id, id);
|
||||
|
@ -211,8 +210,17 @@ VoxelGeneratorGraph::NodeTypeID VoxelGeneratorGraph::get_node_type_id(uint32_t n
|
|||
return (NodeTypeID)node->type_id;
|
||||
}
|
||||
|
||||
PoolIntArray VoxelGeneratorGraph::get_node_ids() const {
|
||||
return _graph.get_node_ids();
|
||||
PackedInt32Array VoxelGeneratorGraph::get_node_ids() const {
|
||||
PackedInt32Array ids;
|
||||
ids.resize(_graph.get_nodes_count());
|
||||
{
|
||||
int i = 0;
|
||||
_graph.for_each_node_id([&ids, &i](int id) {
|
||||
ids.write[i] = id;
|
||||
++i;
|
||||
});
|
||||
}
|
||||
return ids;
|
||||
}
|
||||
|
||||
int VoxelGeneratorGraph::get_nodes_count() const {
|
||||
|
@ -420,11 +428,10 @@ VoxelGenerator::Result VoxelGeneratorGraph::generate_block(VoxelBlockRequest &in
|
|||
|
||||
// Block size must be a multiple of section size, as all sections must have the same size
|
||||
const bool can_use_subdivision =
|
||||
(bs.x % _subdivision_size == 0) &&
|
||||
(bs.y % _subdivision_size == 0) &&
|
||||
(bs.z % _subdivision_size == 0);
|
||||
(bs.x % _subdivision_size == 0) && (bs.y % _subdivision_size == 0) && (bs.z % _subdivision_size == 0);
|
||||
|
||||
const Vector3i section_size = _use_subdivision && can_use_subdivision ? Vector3i(_subdivision_size) : bs;
|
||||
const Vector3i section_size =
|
||||
_use_subdivision && can_use_subdivision ? Vector3iUtil::create(_subdivision_size) : bs;
|
||||
// ERR_FAIL_COND_V(bs.x % section_size != 0, result);
|
||||
// ERR_FAIL_COND_V(bs.y % section_size != 0, result);
|
||||
// ERR_FAIL_COND_V(bs.z % section_size != 0, result);
|
||||
|
@ -511,8 +518,7 @@ VoxelGenerator::Result VoxelGeneratorGraph::generate_block(VoxelBlockRequest &in
|
|||
y_cache.fill(gy);
|
||||
|
||||
// Full query
|
||||
runtime.generate_set(cache.state, x_cache, y_cache, z_cache,
|
||||
_use_xz_caching && ry != rmin.y,
|
||||
runtime.generate_set(cache.state, x_cache, y_cache, z_cache, _use_xz_caching && ry != rmin.y,
|
||||
_use_optimized_execution_map ? &cache.optimized_execution_map : nullptr);
|
||||
|
||||
{
|
||||
|
@ -560,8 +566,7 @@ VoxelGenerator::Result VoxelGeneratorGraph::generate_block(VoxelBlockRequest &in
|
|||
|
||||
y_cache.fill(gy);
|
||||
|
||||
runtime.generate_set(cache.state, x_cache, y_cache, z_cache,
|
||||
_use_xz_caching && ry != rmin.y,
|
||||
runtime.generate_set(cache.state, x_cache, y_cache, z_cache, _use_xz_caching && ry != rmin.y,
|
||||
_use_optimized_execution_map ? &cache.optimized_execution_map : nullptr);
|
||||
|
||||
gather_indices_and_weights(
|
||||
|
@ -649,8 +654,8 @@ VoxelGraphRuntime::CompilationResult VoxelGeneratorGraph::compile() {
|
|||
if (layer_index >= static_cast<int>(r->weight_outputs.size())) {
|
||||
VoxelGraphRuntime::CompilationResult error;
|
||||
error.success = false;
|
||||
error.message = String(TTR("Weight layers cannot exceed {}"))
|
||||
.format(varray(r->weight_outputs.size()));
|
||||
error.message =
|
||||
String(TTR("Weight layers cannot exceed {}")).format(varray(r->weight_outputs.size()));
|
||||
error.node_id = output.node_id;
|
||||
return error;
|
||||
}
|
||||
|
@ -777,8 +782,7 @@ inline Vector3 get_3d_pos_from_panorama_uv(Vector2 uv) {
|
|||
|
||||
// Subdivides a rectangle in square chunks and runs a function on each of them.
|
||||
// The ref is important to allow re-using functors.
|
||||
template <typename F>
|
||||
inline void for_chunks_2d(int w, int h, int chunk_size, F &f) {
|
||||
template <typename F> inline void for_chunks_2d(int w, int h, int chunk_size, F &f) {
|
||||
const int chunks_x = w / chunk_size;
|
||||
const int chunks_y = h / chunk_size;
|
||||
|
||||
|
@ -824,8 +828,7 @@ void VoxelGeneratorGraph::bake_sphere_bumpmap(Ref<Image> im, float ref_radius, f
|
|||
const float sdf_max;
|
||||
|
||||
ProcessChunk(VoxelGraphRuntime::State &p_state, unsigned int p_sdf_buffer_index,
|
||||
const VoxelGraphRuntime &p_runtime,
|
||||
float p_ref_radius, float p_sdf_min, float p_sdf_max) :
|
||||
const VoxelGraphRuntime &p_runtime, float p_ref_radius, float p_sdf_min, float p_sdf_max) :
|
||||
runtime(p_runtime),
|
||||
state(p_state),
|
||||
sdf_buffer_index(p_sdf_buffer_index),
|
||||
|
@ -842,9 +845,8 @@ void VoxelGeneratorGraph::bake_sphere_bumpmap(Ref<Image> im, float ref_radius, f
|
|||
z_coords.resize(area);
|
||||
runtime.prepare_state(state, area);
|
||||
|
||||
const Vector2 suv = Vector2(
|
||||
1.f / static_cast<float>(im->get_width()),
|
||||
1.f / static_cast<float>(im->get_height()));
|
||||
const Vector2 suv =
|
||||
Vector2(1.f / static_cast<float>(im->get_width()), 1.f / static_cast<float>(im->get_height()));
|
||||
|
||||
const float nr = 1.f / (sdf_max - sdf_min);
|
||||
|
||||
|
@ -867,7 +869,7 @@ void VoxelGeneratorGraph::bake_sphere_bumpmap(Ref<Image> im, float ref_radius, f
|
|||
const VoxelGraphRuntime::Buffer &buffer = state.get_buffer(sdf_buffer_index);
|
||||
|
||||
// Calculate final pixels
|
||||
im->lock();
|
||||
// TODO Optimize: could convert to buffer directly?
|
||||
i = 0;
|
||||
for (int iy = y0; iy < ymax; ++iy) {
|
||||
for (int ix = x0; ix < xmax; ++ix) {
|
||||
|
@ -877,14 +879,13 @@ void VoxelGeneratorGraph::bake_sphere_bumpmap(Ref<Image> im, float ref_radius, f
|
|||
++i;
|
||||
}
|
||||
}
|
||||
im->unlock();
|
||||
}
|
||||
};
|
||||
|
||||
Cache &cache = _cache;
|
||||
|
||||
ProcessChunk pc(cache.state, runtime_ptr->sdf_output_buffer_index, runtime_ptr->runtime,
|
||||
ref_radius, sdf_min, sdf_max);
|
||||
ProcessChunk pc(
|
||||
cache.state, runtime_ptr->sdf_output_buffer_index, runtime_ptr->runtime, ref_radius, sdf_min, sdf_max);
|
||||
pc.im = im;
|
||||
for_chunks_2d(im->get_width(), im->get_height(), 32, pc);
|
||||
}
|
||||
|
@ -920,10 +921,8 @@ void VoxelGeneratorGraph::bake_sphere_normalmap(Ref<Image> im, float ref_radius,
|
|||
const float strength;
|
||||
const float ref_radius;
|
||||
|
||||
ProcessChunk(VoxelGraphRuntime::State &p_state, unsigned int p_sdf_buffer_index,
|
||||
Ref<Image> p_im,
|
||||
const VoxelGraphRuntime &p_runtime,
|
||||
float p_strength, float p_ref_radius) :
|
||||
ProcessChunk(VoxelGraphRuntime::State &p_state, unsigned int p_sdf_buffer_index, Ref<Image> p_im,
|
||||
const VoxelGraphRuntime &p_runtime, float p_strength, float p_ref_radius) :
|
||||
sdf_buffer_index(p_sdf_buffer_index),
|
||||
im(p_im),
|
||||
runtime(p_runtime),
|
||||
|
@ -945,9 +944,8 @@ void VoxelGeneratorGraph::bake_sphere_normalmap(Ref<Image> im, float ref_radius,
|
|||
|
||||
const float ns = 2.f / strength;
|
||||
|
||||
const Vector2 suv = Vector2(
|
||||
1.f / static_cast<float>(im->get_width()),
|
||||
1.f / static_cast<float>(im->get_height()));
|
||||
const Vector2 suv =
|
||||
Vector2(1.f / static_cast<float>(im->get_width()), 1.f / static_cast<float>(im->get_height()));
|
||||
|
||||
const Vector2 normal_step = 0.5f * Vector2(1.f, 1.f) / im->get_size();
|
||||
const Vector2 normal_step_x = Vector2(normal_step.x, 0.f);
|
||||
|
@ -1013,7 +1011,7 @@ void VoxelGeneratorGraph::bake_sphere_normalmap(Ref<Image> im, float ref_radius,
|
|||
// Compute the 3D normal from gradient, then project it?
|
||||
|
||||
// Calculate final pixels
|
||||
im->lock();
|
||||
// TODO Optimize: convert into buffer directly?
|
||||
i = 0;
|
||||
for (int iy = y0; iy < ymax; ++iy) {
|
||||
for (int ix = x0; ix < xmax; ++ix) {
|
||||
|
@ -1022,14 +1020,10 @@ void VoxelGeneratorGraph::bake_sphere_normalmap(Ref<Image> im, float ref_radius,
|
|||
const float h_py = sdf_values_py[i];
|
||||
++i;
|
||||
const Vector3 normal = Vector3(h_px - h, ns, h_py - h).normalized();
|
||||
const Color en(
|
||||
0.5f * normal.x + 0.5f,
|
||||
-0.5f * normal.z + 0.5f,
|
||||
0.5f * normal.y + 0.5f);
|
||||
const Color en(0.5f * normal.x + 0.5f, -0.5f * normal.z + 0.5f, 0.5f * normal.y + 0.5f);
|
||||
im->set_pixel(ix, iy, en);
|
||||
}
|
||||
}
|
||||
im->unlock();
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1065,7 +1059,7 @@ VoxelSingleValue VoxelGeneratorGraph::generate_single(Vector3i position, unsigne
|
|||
Cache &cache = _cache;
|
||||
const VoxelGraphRuntime &runtime = runtime_ptr->runtime;
|
||||
runtime.prepare_state(cache.state, 1);
|
||||
runtime.generate_single(cache.state, position.to_vec3(), nullptr);
|
||||
runtime.generate_single(cache.state, position, nullptr);
|
||||
const VoxelGraphRuntime::Buffer &buffer = cache.state.get_buffer(runtime_ptr->sdf_output_buffer_index);
|
||||
ERR_FAIL_COND_V(buffer.size == 0, v);
|
||||
ERR_FAIL_COND_V(buffer.data == nullptr, v);
|
||||
|
@ -1075,8 +1069,8 @@ VoxelSingleValue VoxelGeneratorGraph::generate_single(Vector3i position, unsigne
|
|||
|
||||
// Note, this wrapper may not be used for main generation tasks.
|
||||
// It is mostly used as a debug tool.
|
||||
Interval VoxelGeneratorGraph::debug_analyze_range(Vector3i min_pos, Vector3i max_pos,
|
||||
bool optimize_execution_map) const {
|
||||
Interval VoxelGeneratorGraph::debug_analyze_range(
|
||||
Vector3i min_pos, Vector3i max_pos, bool optimize_execution_map) const {
|
||||
std::shared_ptr<const Runtime> runtime_ptr;
|
||||
{
|
||||
RWLockRead rlock(_runtime_lock);
|
||||
|
@ -1096,7 +1090,7 @@ Interval VoxelGeneratorGraph::debug_analyze_range(Vector3i min_pos, Vector3i max
|
|||
|
||||
Ref<Resource> VoxelGeneratorGraph::duplicate(bool p_subresources) const {
|
||||
Ref<VoxelGeneratorGraph> d;
|
||||
d.instance();
|
||||
d.instantiate();
|
||||
|
||||
d->_graph.copy_from(_graph, p_subresources);
|
||||
d->register_subresources();
|
||||
|
@ -1107,40 +1101,35 @@ Ref<Resource> VoxelGeneratorGraph::duplicate(bool p_subresources) const {
|
|||
|
||||
static Dictionary get_graph_as_variant_data(const ProgramGraph &graph) {
|
||||
Dictionary nodes_data;
|
||||
PoolVector<int> node_ids = graph.get_node_ids();
|
||||
{
|
||||
PoolVector<int>::Read r = node_ids.read();
|
||||
for (int i = 0; i < node_ids.size(); ++i) {
|
||||
uint32_t node_id = r[i];
|
||||
const ProgramGraph::Node *node = graph.get_node(node_id);
|
||||
ERR_FAIL_COND_V(node == nullptr, Dictionary());
|
||||
graph.for_each_node_id([&graph, &nodes_data](uint32_t node_id) {
|
||||
const ProgramGraph::Node *node = graph.get_node(node_id);
|
||||
ERR_FAIL_COND(node == nullptr);
|
||||
|
||||
Dictionary node_data;
|
||||
Dictionary node_data;
|
||||
|
||||
const VoxelGraphNodeDB::NodeType &type = VoxelGraphNodeDB::get_singleton()->get_type(node->type_id);
|
||||
node_data["type"] = type.name;
|
||||
node_data["gui_position"] = node->gui_position;
|
||||
const VoxelGraphNodeDB::NodeType &type = VoxelGraphNodeDB::get_singleton()->get_type(node->type_id);
|
||||
node_data["type"] = type.name;
|
||||
node_data["gui_position"] = node->gui_position;
|
||||
|
||||
if (node->name != StringName()) {
|
||||
node_data["name"] = node->name;
|
||||
}
|
||||
|
||||
for (size_t j = 0; j < type.params.size(); ++j) {
|
||||
const VoxelGraphNodeDB::Param ¶m = type.params[j];
|
||||
node_data[param.name] = node->params[j];
|
||||
}
|
||||
|
||||
for (size_t j = 0; j < type.inputs.size(); ++j) {
|
||||
if (node->inputs[j].connections.size() == 0) {
|
||||
const VoxelGraphNodeDB::Port &port = type.inputs[j];
|
||||
node_data[port.name] = node->default_inputs[j];
|
||||
}
|
||||
}
|
||||
|
||||
String key = String::num_uint64(node_id);
|
||||
nodes_data[key] = node_data;
|
||||
if (node->name != StringName()) {
|
||||
node_data["name"] = node->name;
|
||||
}
|
||||
}
|
||||
|
||||
for (size_t j = 0; j < type.params.size(); ++j) {
|
||||
const VoxelGraphNodeDB::Param ¶m = type.params[j];
|
||||
node_data[param.name] = node->params[j];
|
||||
}
|
||||
|
||||
for (size_t j = 0; j < type.inputs.size(); ++j) {
|
||||
if (node->inputs[j].connections.size() == 0) {
|
||||
const VoxelGraphNodeDB::Port &port = type.inputs[j];
|
||||
node_data[port.name] = node->default_inputs[j];
|
||||
}
|
||||
}
|
||||
|
||||
String key = String::num_uint64(node_id);
|
||||
nodes_data[key] = node_data;
|
||||
});
|
||||
|
||||
Array connections_data;
|
||||
std::vector<ProgramGraph::Connection> connections;
|
||||
|
@ -1183,7 +1172,7 @@ static bool load_graph_from_variant_data(ProgramGraph &graph, Dictionary data) {
|
|||
const Variant *id_key = nullptr;
|
||||
while ((id_key = nodes_data.next(id_key))) {
|
||||
const String id_str = *id_key;
|
||||
ERR_FAIL_COND_V(!id_str.is_valid_integer(), false);
|
||||
ERR_FAIL_COND_V(!id_str.is_valid_int(), false);
|
||||
const int sid = id_str.to_int();
|
||||
ERR_FAIL_COND_V(sid < static_cast<int>(ProgramGraph::NULL_ID), false);
|
||||
const uint32_t id = sid;
|
||||
|
@ -1251,12 +1240,14 @@ void VoxelGeneratorGraph::load_graph_from_variant_data(Dictionary data) {
|
|||
|
||||
void VoxelGeneratorGraph::register_subresource(Resource &resource) {
|
||||
//print_line(String("{0}: Registering subresource {1}").format(varray(int64_t(this), int64_t(&resource))));
|
||||
resource.connect(CoreStringNames::get_singleton()->changed, this, "_on_subresource_changed");
|
||||
resource.connect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &VoxelGeneratorGraph::_on_subresource_changed));
|
||||
}
|
||||
|
||||
void VoxelGeneratorGraph::unregister_subresource(Resource &resource) {
|
||||
//print_line(String("{0}: Unregistering subresource {1}").format(varray(int64_t(this), int64_t(&resource))));
|
||||
resource.disconnect(CoreStringNames::get_singleton()->changed, this, "_on_subresource_changed");
|
||||
resource.disconnect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &VoxelGeneratorGraph::_on_subresource_changed));
|
||||
}
|
||||
|
||||
void VoxelGeneratorGraph::register_subresources() {
|
||||
|
@ -1311,7 +1302,7 @@ float VoxelGeneratorGraph::debug_measure_microseconds_per_voxel(bool singular) {
|
|||
for (uint32_t z = 0; z < cube_size; ++z) {
|
||||
for (uint32_t y = 0; y < cube_size; ++y) {
|
||||
for (uint32_t x = 0; x < cube_size; ++x) {
|
||||
runtime.generate_single(cache.state, Vector3i(x, y, z).to_vec3(), nullptr);
|
||||
runtime.generate_single(cache.state, Vector3i(x, y, z), nullptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1353,10 +1344,10 @@ void VoxelGeneratorGraph::load_plane_preset() {
|
|||
clear();
|
||||
|
||||
/*
|
||||
* X
|
||||
*
|
||||
* X
|
||||
*
|
||||
* Y --- SdfPlane --- OutputSDF
|
||||
*
|
||||
*
|
||||
* Z
|
||||
*/
|
||||
|
||||
|
@ -1401,7 +1392,7 @@ void VoxelGeneratorGraph::debug_load_waves_preset() {
|
|||
* 1/20 + --- * --- - --- O
|
||||
* \ / /
|
||||
* Z --- * --- sin 10.0
|
||||
*/
|
||||
*/
|
||||
|
||||
add_connection(n_x, 0, n_mul0, 0);
|
||||
add_connection(n_z, 0, n_mul1, 0);
|
||||
|
@ -1453,15 +1444,15 @@ void VoxelGeneratorGraph::_b_set_node_param_null(int node_id, int param_index) {
|
|||
}
|
||||
|
||||
float VoxelGeneratorGraph::_b_generate_single(Vector3 pos) {
|
||||
return generate_single(Vector3i::from_floored(pos), VoxelBufferInternal::CHANNEL_SDF).f;
|
||||
return generate_single(Vector3iUtil::from_floored(pos), VoxelBufferInternal::CHANNEL_SDF).f;
|
||||
}
|
||||
|
||||
Vector2 VoxelGeneratorGraph::_b_debug_analyze_range(Vector3 min_pos, Vector3 max_pos) const {
|
||||
ERR_FAIL_COND_V(min_pos.x > max_pos.x, Vector2());
|
||||
ERR_FAIL_COND_V(min_pos.y > max_pos.y, Vector2());
|
||||
ERR_FAIL_COND_V(min_pos.z > max_pos.z, Vector2());
|
||||
const Interval r = debug_analyze_range(
|
||||
Vector3i::from_floored(min_pos), Vector3i::from_floored(max_pos), false);
|
||||
const Interval r =
|
||||
debug_analyze_range(Vector3iUtil::from_floored(min_pos), Vector3iUtil::from_floored(max_pos), false);
|
||||
return Vector2(r.min, r.max);
|
||||
}
|
||||
|
||||
|
@ -1482,8 +1473,8 @@ void VoxelGeneratorGraph::_on_subresource_changed() {
|
|||
|
||||
void VoxelGeneratorGraph::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("clear"), &VoxelGeneratorGraph::clear);
|
||||
ClassDB::bind_method(D_METHOD("create_node", "type_id", "position", "id"),
|
||||
&VoxelGeneratorGraph::create_node, DEFVAL(ProgramGraph::NULL_ID));
|
||||
ClassDB::bind_method(D_METHOD("create_node", "type_id", "position", "id"), &VoxelGeneratorGraph::create_node,
|
||||
DEFVAL(ProgramGraph::NULL_ID));
|
||||
ClassDB::bind_method(D_METHOD("remove_node", "node_id"), &VoxelGeneratorGraph::remove_node);
|
||||
ClassDB::bind_method(D_METHOD("can_connect", "src_node_id", "src_port_index", "dst_node_id", "dst_port_index"),
|
||||
&VoxelGeneratorGraph::can_connect);
|
||||
|
@ -1498,25 +1489,25 @@ void VoxelGeneratorGraph::_bind_methods() {
|
|||
|
||||
ClassDB::bind_method(D_METHOD("get_node_type_id", "node_id"), &VoxelGeneratorGraph::get_node_type_id);
|
||||
ClassDB::bind_method(D_METHOD("get_node_param", "node_id", "param_index"), &VoxelGeneratorGraph::get_node_param);
|
||||
ClassDB::bind_method(D_METHOD("set_node_param", "node_id", "param_index", "value"),
|
||||
&VoxelGeneratorGraph::set_node_param);
|
||||
ClassDB::bind_method(D_METHOD("get_node_default_input", "node_id", "input_index"),
|
||||
&VoxelGeneratorGraph::get_node_default_input);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_node_param", "node_id", "param_index", "value"), &VoxelGeneratorGraph::set_node_param);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("get_node_default_input", "node_id", "input_index"), &VoxelGeneratorGraph::get_node_default_input);
|
||||
ClassDB::bind_method(D_METHOD("set_node_default_input", "node_id", "input_index", "value"),
|
||||
&VoxelGeneratorGraph::set_node_default_input);
|
||||
ClassDB::bind_method(D_METHOD("set_node_param_null", "node_id", "param_index"),
|
||||
&VoxelGeneratorGraph::_b_set_node_param_null);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_node_param_null", "node_id", "param_index"), &VoxelGeneratorGraph::_b_set_node_param_null);
|
||||
ClassDB::bind_method(D_METHOD("get_node_gui_position", "node_id"), &VoxelGeneratorGraph::get_node_gui_position);
|
||||
ClassDB::bind_method(D_METHOD("set_node_gui_position", "node_id", "position"),
|
||||
&VoxelGeneratorGraph::set_node_gui_position);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_node_gui_position", "node_id", "position"), &VoxelGeneratorGraph::set_node_gui_position);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_sdf_clip_threshold", "threshold"), &VoxelGeneratorGraph::set_sdf_clip_threshold);
|
||||
ClassDB::bind_method(D_METHOD("get_sdf_clip_threshold"), &VoxelGeneratorGraph::get_sdf_clip_threshold);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("is_using_optimized_execution_map"),
|
||||
&VoxelGeneratorGraph::is_using_optimized_execution_map);
|
||||
ClassDB::bind_method(D_METHOD("set_use_optimized_execution_map", "use"),
|
||||
&VoxelGeneratorGraph::set_use_optimized_execution_map);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("is_using_optimized_execution_map"), &VoxelGeneratorGraph::is_using_optimized_execution_map);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_use_optimized_execution_map", "use"), &VoxelGeneratorGraph::set_use_optimized_execution_map);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_use_subdivision", "use"), &VoxelGeneratorGraph::set_use_subdivision);
|
||||
ClassDB::bind_method(D_METHOD("is_using_subdivision"), &VoxelGeneratorGraph::is_using_subdivision);
|
||||
|
@ -1524,8 +1515,8 @@ void VoxelGeneratorGraph::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_subdivision_size", "size"), &VoxelGeneratorGraph::set_subdivision_size);
|
||||
ClassDB::bind_method(D_METHOD("get_subdivision_size"), &VoxelGeneratorGraph::get_subdivision_size);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_debug_clipped_blocks", "enabled"),
|
||||
&VoxelGeneratorGraph::set_debug_clipped_blocks);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_debug_clipped_blocks", "enabled"), &VoxelGeneratorGraph::set_debug_clipped_blocks);
|
||||
ClassDB::bind_method(D_METHOD("is_debug_clipped_blocks"), &VoxelGeneratorGraph::is_debug_clipped_blocks);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_use_xz_caching", "enabled"), &VoxelGeneratorGraph::set_use_xz_caching);
|
||||
|
@ -1537,8 +1528,8 @@ void VoxelGeneratorGraph::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("get_node_type_info", "type_id"), &VoxelGeneratorGraph::_b_get_node_type_info);
|
||||
|
||||
//ClassDB::bind_method(D_METHOD("generate_single"), &VoxelGeneratorGraph::_b_generate_single);
|
||||
ClassDB::bind_method(D_METHOD("debug_analyze_range", "min_pos", "max_pos"),
|
||||
&VoxelGeneratorGraph::_b_debug_analyze_range);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("debug_analyze_range", "min_pos", "max_pos"), &VoxelGeneratorGraph::_b_debug_analyze_range);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("bake_sphere_bumpmap", "im", "ref_radius", "sdf_min", "sdf_max"),
|
||||
&VoxelGeneratorGraph::bake_sphere_bumpmap);
|
||||
|
@ -1555,19 +1546,20 @@ void VoxelGeneratorGraph::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("_on_subresource_changed"), &VoxelGeneratorGraph::_on_subresource_changed);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::DICTIONARY, "graph_data", PROPERTY_HINT_NONE, "",
|
||||
PROPERTY_USAGE_NOEDITOR | PROPERTY_USAGE_INTERNAL),
|
||||
PROPERTY_USAGE_NO_EDITOR | PROPERTY_USAGE_INTERNAL),
|
||||
"_set_graph_data", "_get_graph_data");
|
||||
|
||||
ADD_GROUP("Performance Tuning", "");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "sdf_clip_threshold"), "set_sdf_clip_threshold", "get_sdf_clip_threshold");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "use_optimized_execution_map"),
|
||||
"set_use_optimized_execution_map", "is_using_optimized_execution_map");
|
||||
ADD_PROPERTY(
|
||||
PropertyInfo(Variant::FLOAT, "sdf_clip_threshold"), "set_sdf_clip_threshold", "get_sdf_clip_threshold");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "use_optimized_execution_map"), "set_use_optimized_execution_map",
|
||||
"is_using_optimized_execution_map");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "use_subdivision"), "set_use_subdivision", "is_using_subdivision");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "subdivision_size"), "set_subdivision_size", "get_subdivision_size");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "use_xz_caching"), "set_use_xz_caching", "is_using_xz_caching");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "debug_block_clipping"),
|
||||
"set_debug_clipped_blocks", "is_debug_clipped_blocks");
|
||||
ADD_PROPERTY(
|
||||
PropertyInfo(Variant::BOOL, "debug_block_clipping"), "set_debug_clipped_blocks", "is_debug_clipped_blocks");
|
||||
|
||||
ADD_SIGNAL(MethodInfo(SIGNAL_NODE_NAME_CHANGED, PropertyInfo(Variant::INT, "node_id")));
|
||||
|
||||
|
|
|
@ -94,8 +94,10 @@ public:
|
|||
void set_node_gui_position(uint32_t node_id, Vector2 pos);
|
||||
|
||||
NodeTypeID get_node_type_id(uint32_t node_id) const;
|
||||
PoolIntArray get_node_ids() const;
|
||||
uint32_t generate_node_id() { return _graph.generate_node_id(); }
|
||||
PackedInt32Array get_node_ids() const;
|
||||
uint32_t generate_node_id() {
|
||||
return _graph.generate_node_id();
|
||||
}
|
||||
|
||||
int get_nodes_count() const;
|
||||
|
||||
|
@ -127,7 +129,9 @@ public:
|
|||
|
||||
Result generate_block(VoxelBlockRequest &input) override;
|
||||
//float generate_single(const Vector3i &position);
|
||||
bool supports_single_generation() const override { return true; }
|
||||
bool supports_single_generation() const override {
|
||||
return true;
|
||||
}
|
||||
VoxelSingleValue generate_single(Vector3i position, unsigned int channel) override;
|
||||
|
||||
Ref<Resource> duplicate(bool p_subresources) const override;
|
||||
|
@ -169,7 +173,6 @@ private:
|
|||
|
||||
int _b_get_node_type_count() const;
|
||||
Dictionary _b_get_node_type_info(int type_id) const;
|
||||
PoolIntArray _b_get_node_ids() const;
|
||||
Array _b_get_connections() const;
|
||||
// TODO Only exists because the UndoRedo API is confusing `null` with `absence of argument`...
|
||||
// See https://github.com/godotengine/godot/issues/36895
|
||||
|
|
|
@ -12,8 +12,7 @@ namespace {
|
|||
VoxelGraphNodeDB *g_node_type_db = nullptr;
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
inline void do_monop(VoxelGraphRuntime::ProcessBufferContext &ctx, F f) {
|
||||
template <typename F> inline void do_monop(VoxelGraphRuntime::ProcessBufferContext &ctx, F f) {
|
||||
const VoxelGraphRuntime::Buffer &a = ctx.get_input(0);
|
||||
VoxelGraphRuntime::Buffer &out = ctx.get_output(0);
|
||||
for (uint32_t i = 0; i < a.size; ++i) {
|
||||
|
@ -21,8 +20,7 @@ inline void do_monop(VoxelGraphRuntime::ProcessBufferContext &ctx, F f) {
|
|||
}
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
inline void do_binop(VoxelGraphRuntime::ProcessBufferContext &ctx, F f) {
|
||||
template <typename F> inline void do_binop(VoxelGraphRuntime::ProcessBufferContext &ctx, F f) {
|
||||
const VoxelGraphRuntime::Buffer &a = ctx.get_input(0);
|
||||
const VoxelGraphRuntime::Buffer &b = ctx.get_input(1);
|
||||
VoxelGraphRuntime::Buffer &out = ctx.get_output(0);
|
||||
|
@ -145,8 +143,8 @@ inline Interval skew3(Interval x) {
|
|||
}
|
||||
|
||||
// This is mostly useful for generating planets from an existing heightmap
|
||||
inline float sdf_sphere_heightmap(float x, float y, float z, float r, float m, const Image &im,
|
||||
float min_h, float max_h, float norm_x, float norm_y) {
|
||||
inline float sdf_sphere_heightmap(float x, float y, float z, float r, float m, const Image &im, float min_h,
|
||||
float max_h, float norm_x, float norm_y) {
|
||||
const float d = Math::sqrt(x * x + y * y + z * z) + 0.0001f;
|
||||
const float sd = d - r;
|
||||
// Optimize when far enough from heightmap.
|
||||
|
@ -257,7 +255,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.name = "Constant";
|
||||
t.category = CATEGORY_INPUT;
|
||||
t.outputs.push_back(Port("value"));
|
||||
t.params.push_back(Param("value", Variant::REAL));
|
||||
t.params.push_back(Param("value", Variant::FLOAT));
|
||||
}
|
||||
{
|
||||
NodeType &t = types[VoxelGeneratorGraph::NODE_INPUT_X];
|
||||
|
@ -390,9 +388,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.category = CATEGORY_MATH;
|
||||
t.inputs.push_back(Port("x"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) {
|
||||
do_monop(ctx, [](float a) { return Math::sin(a); });
|
||||
};
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) { do_monop(ctx, [](float a) { return Math::sin(a); }); };
|
||||
t.range_analysis_func = [](RangeAnalysisContext &ctx) {
|
||||
const Interval a = ctx.get_input(0);
|
||||
ctx.set_output(0, sin(a));
|
||||
|
@ -418,9 +414,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.category = CATEGORY_MATH;
|
||||
t.inputs.push_back(Port("x"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) {
|
||||
do_monop(ctx, [](float a) { return Math::abs(a); });
|
||||
};
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) { do_monop(ctx, [](float a) { return Math::abs(a); }); };
|
||||
t.range_analysis_func = [](RangeAnalysisContext &ctx) {
|
||||
const Interval a = ctx.get_input(0);
|
||||
ctx.set_output(0, abs(a));
|
||||
|
@ -432,9 +426,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.category = CATEGORY_MATH;
|
||||
t.inputs.push_back(Port("x"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) {
|
||||
do_monop(ctx, [](float a) { return Math::sqrt(a); });
|
||||
};
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) { do_monop(ctx, [](float a) { return Math::sqrt(a); }); };
|
||||
t.range_analysis_func = [](RangeAnalysisContext &ctx) {
|
||||
const Interval a = ctx.get_input(0);
|
||||
ctx.set_output(0, sqrt(a));
|
||||
|
@ -462,7 +454,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.inputs.push_back(Port("step"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.process_buffer_func = [](ProcessBufferContext &ctx) {
|
||||
do_binop(ctx, [](float a, float b) { return Math::stepify(a, b); });
|
||||
do_binop(ctx, [](float a, float b) { return Math::snapped(a, b); });
|
||||
};
|
||||
t.range_analysis_func = [](RangeAnalysisContext &ctx) {
|
||||
const Interval a = ctx.get_input(0);
|
||||
|
@ -534,9 +526,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
const VoxelGraphRuntime::Buffer &y1 = ctx.get_input(3);
|
||||
VoxelGraphRuntime::Buffer &out = ctx.get_output(0);
|
||||
for (uint32_t i = 0; i < out.size; ++i) {
|
||||
out.data[i] = Math::sqrt(
|
||||
squared(x1.data[i] - x0.data[i]) +
|
||||
squared(y1.data[i] - y0.data[i]));
|
||||
out.data[i] = Math::sqrt(squared(x1.data[i] - x0.data[i]) + squared(y1.data[i] - y0.data[i]));
|
||||
}
|
||||
};
|
||||
t.range_analysis_func = [](RangeAnalysisContext &ctx) {
|
||||
|
@ -570,9 +560,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
const VoxelGraphRuntime::Buffer &z1 = ctx.get_input(5);
|
||||
VoxelGraphRuntime::Buffer &out = ctx.get_output(0);
|
||||
for (uint32_t i = 0; i < out.size; ++i) {
|
||||
out.data[i] = Math::sqrt(
|
||||
squared(x1.data[i] - x0.data[i]) +
|
||||
squared(y1.data[i] - y0.data[i]) +
|
||||
out.data[i] = Math::sqrt(squared(x1.data[i] - x0.data[i]) + squared(y1.data[i] - y0.data[i]) +
|
||||
squared(z1.data[i] - z0.data[i]));
|
||||
}
|
||||
};
|
||||
|
@ -600,8 +588,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.category = CATEGORY_CONVERT;
|
||||
t.inputs.push_back(Port("x"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.params.push_back(Param("min", Variant::REAL, -1.f));
|
||||
t.params.push_back(Param("max", Variant::REAL, 1.f));
|
||||
t.params.push_back(Param("min", Variant::FLOAT, -1.f));
|
||||
t.params.push_back(Param("max", Variant::FLOAT, 1.f));
|
||||
t.compile_func = [](CompileContext &ctx) {
|
||||
Params p;
|
||||
p.min = ctx.get_param(0).operator float();
|
||||
|
@ -716,10 +704,10 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.category = CATEGORY_CONVERT;
|
||||
t.inputs.push_back(Port("x"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.params.push_back(Param("min0", Variant::REAL, -1.f));
|
||||
t.params.push_back(Param("max0", Variant::REAL, 1.f));
|
||||
t.params.push_back(Param("min1", Variant::REAL, -1.f));
|
||||
t.params.push_back(Param("max1", Variant::REAL, 1.f));
|
||||
t.params.push_back(Param("min0", Variant::FLOAT, -1.f));
|
||||
t.params.push_back(Param("max0", Variant::FLOAT, 1.f));
|
||||
t.params.push_back(Param("min1", Variant::FLOAT, -1.f));
|
||||
t.params.push_back(Param("max1", Variant::FLOAT, 1.f));
|
||||
t.compile_func = [](CompileContext &ctx) {
|
||||
Params p;
|
||||
const float min0 = ctx.get_param(0).operator float();
|
||||
|
@ -764,8 +752,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.category = CATEGORY_CONVERT;
|
||||
t.inputs.push_back(Port("x"));
|
||||
t.outputs.push_back(Port("out"));
|
||||
t.params.push_back(Param("edge0", Variant::REAL, 0.f));
|
||||
t.params.push_back(Param("edge1", Variant::REAL, 1.f));
|
||||
t.params.push_back(Param("edge0", Variant::FLOAT, 0.f));
|
||||
t.params.push_back(Param("edge1", Variant::FLOAT, 1.f));
|
||||
t.compile_func = [](CompileContext &ctx) {
|
||||
Params p;
|
||||
p.edge0 = ctx.get_param(0).operator float();
|
||||
|
@ -1006,9 +994,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
const VoxelGraphRuntime::Buffer &sz = ctx.get_input(5);
|
||||
VoxelGraphRuntime::Buffer &out = ctx.get_output(0);
|
||||
for (uint32_t i = 0; i < out.size; ++i) {
|
||||
out.data[i] = sdf_box(
|
||||
Vector3(x.data[i], y.data[i], z.data[i]),
|
||||
Vector3(sx.data[i], sy.data[i], sz.data[i]));
|
||||
out.data[i] =
|
||||
sdf_box(Vector3(x.data[i], y.data[i], z.data[i]), Vector3(sx.data[i], sy.data[i], sz.data[i]));
|
||||
}
|
||||
};
|
||||
t.range_analysis_func = [](RangeAnalysisContext &ctx) {
|
||||
|
@ -1088,7 +1075,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.inputs.push_back(Port("a"));
|
||||
t.inputs.push_back(Port("b"));
|
||||
t.outputs.push_back(Port("sdf"));
|
||||
t.params.push_back(Param("smoothness", Variant::REAL, 0.f));
|
||||
t.params.push_back(Param("smoothness", Variant::FLOAT, 0.f));
|
||||
t.compile_func = [](CompileContext &ctx) {
|
||||
Params p;
|
||||
p.smoothness = ctx.get_param(0).operator float();
|
||||
|
@ -1172,7 +1159,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.inputs.push_back(Port("a"));
|
||||
t.inputs.push_back(Port("b"));
|
||||
t.outputs.push_back(Port("sdf"));
|
||||
t.params.push_back(Param("smoothness", Variant::REAL, 0.f));
|
||||
t.params.push_back(Param("smoothness", Variant::FLOAT, 0.f));
|
||||
t.compile_func = [](CompileContext &ctx) {
|
||||
Params p;
|
||||
p.smoothness = ctx.get_param(0).operator float();
|
||||
|
@ -1251,8 +1238,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.name = "SdfPreview";
|
||||
t.category = CATEGORY_DEBUG;
|
||||
t.inputs.push_back(Port("value"));
|
||||
t.params.push_back(Param("min_value", Variant::REAL, -1.f));
|
||||
t.params.push_back(Param("max_value", Variant::REAL, 1.f));
|
||||
t.params.push_back(Param("min_value", Variant::FLOAT, -1.f));
|
||||
t.params.push_back(Param("max_value", Variant::FLOAT, 1.f));
|
||||
t.debug_only = true;
|
||||
}
|
||||
{
|
||||
|
@ -1315,8 +1302,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
t.inputs.push_back(Port("z"));
|
||||
t.outputs.push_back(Port("sdf"));
|
||||
t.params.push_back(Param("image", "Image"));
|
||||
t.params.push_back(Param("radius", Variant::REAL, 10.f));
|
||||
t.params.push_back(Param("factor", Variant::REAL, 1.f));
|
||||
t.params.push_back(Param("radius", Variant::FLOAT, 10.f));
|
||||
t.params.push_back(Param("factor", Variant::FLOAT, 1.f));
|
||||
|
||||
t.compile_func = [](CompileContext &ctx) {
|
||||
Ref<Image> image = ctx.get_param(0);
|
||||
|
@ -1351,8 +1338,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
const Params p = ctx.get_params<Params>();
|
||||
const Image &im = *p.image;
|
||||
for (uint32_t i = 0; i < out.size; ++i) {
|
||||
out.data[i] = sdf_sphere_heightmap(x.data[i], y.data[i], z.data[i],
|
||||
p.radius, p.factor, im, p.min_height, p.max_height, p.norm_x, p.norm_y);
|
||||
out.data[i] = sdf_sphere_heightmap(x.data[i], y.data[i], z.data[i], p.radius, p.factor, im,
|
||||
p.min_height, p.max_height, p.norm_x, p.norm_y);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1361,8 +1348,8 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
const Interval y = ctx.get_input(1);
|
||||
const Interval z = ctx.get_input(2);
|
||||
const Params p = ctx.get_params<Params>();
|
||||
ctx.set_output(0,
|
||||
sdf_sphere_heightmap(x, y, z, p.radius, p.factor, p.image_range_grid, p.norm_x, p.norm_y));
|
||||
ctx.set_output(
|
||||
0, sdf_sphere_heightmap(x, y, z, p.radius, p.factor, p.image_range_grid, p.norm_x, p.norm_y));
|
||||
};
|
||||
}
|
||||
{
|
||||
|
@ -1619,7 +1606,7 @@ VoxelGraphNodeDB::VoxelGraphNodeDB() {
|
|||
p.index = param_index;
|
||||
|
||||
switch (p.type) {
|
||||
case Variant::REAL:
|
||||
case Variant::FLOAT:
|
||||
if (p.default_value.get_type() == Variant::NIL) {
|
||||
p.default_value = 0.f;
|
||||
}
|
||||
|
|
|
@ -17,27 +17,6 @@
|
|||
//#define VOXEL_DEBUG_GRAPH_PROG_SENTINEL uint16_t(12345) // 48, 57 (base 10)
|
||||
//#endif
|
||||
|
||||
// The Image lock() API prevents us from reading the same image in multiple threads.
|
||||
// Compiling makes a read-only copy of all resources, so we can lock all images up-front if successful.
|
||||
// This might no longer needed in Godot 4.
|
||||
void VoxelGraphRuntime::Program::lock_images() {
|
||||
for (size_t i = 0; i < ref_resources.size(); ++i) {
|
||||
Ref<Image> im = ref_resources[i];
|
||||
if (im.is_valid()) {
|
||||
im->lock();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void VoxelGraphRuntime::Program::unlock_images() {
|
||||
for (size_t i = 0; i < ref_resources.size(); ++i) {
|
||||
Ref<Image> im = ref_resources[i];
|
||||
if (im.is_valid()) {
|
||||
im->unlock();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
VoxelGraphRuntime::VoxelGraphRuntime() {
|
||||
clear();
|
||||
}
|
||||
|
@ -399,8 +378,6 @@ VoxelGraphRuntime::CompilationResult VoxelGraphRuntime::_compile(const ProgramGr
|
|||
SIZE_T_TO_VARIANT(_program.operations.size() * sizeof(uint16_t)),
|
||||
SIZE_T_TO_VARIANT(_program.buffer_count))));
|
||||
|
||||
_program.lock_images();
|
||||
|
||||
CompilationResult result;
|
||||
result.success = true;
|
||||
return result;
|
||||
|
@ -787,13 +764,9 @@ void VoxelGraphRuntime::generate_set(State &state,
|
|||
|
||||
const Span<const uint16_t> operations(_program.operations.data(), 0, _program.operations.size());
|
||||
|
||||
Span<const uint16_t> op_adresses = execution_map != nullptr ?
|
||||
to_span_const(execution_map->operation_adresses) :
|
||||
to_span_const(_program.default_execution_map.operation_adresses);
|
||||
Span<const uint16_t> op_adresses = execution_map != nullptr ? to_span_const(execution_map->operation_adresses) : to_span_const(_program.default_execution_map.operation_adresses);
|
||||
if (skip_xz && op_adresses.size() > 0) {
|
||||
const unsigned int offset = execution_map != nullptr ?
|
||||
execution_map->xzy_start_index :
|
||||
_program.default_execution_map.xzy_start_index;
|
||||
const unsigned int offset = execution_map != nullptr ? execution_map->xzy_start_index : _program.default_execution_map.xzy_start_index;
|
||||
op_adresses = op_adresses.sub(offset);
|
||||
}
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
#include "../../util/span.h"
|
||||
#include "program_graph.h"
|
||||
|
||||
#include <core/reference.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
|
||||
// CPU VM to execute a voxel graph generator.
|
||||
// This is a more generic class implementing the core of a 3D expression processing system.
|
||||
|
@ -435,7 +435,7 @@ private:
|
|||
|
||||
// Heap-allocated parameters data, when too large to fit in `operations`.
|
||||
// We keep a reference to them so they won't be freed until the program is cleared.
|
||||
std::vector<Ref<Reference>> ref_resources;
|
||||
std::vector<Ref<RefCounted>> ref_resources;
|
||||
|
||||
// Describes the list of buffers to prepare in `State` before the program can be run
|
||||
std::vector<BufferSpec> buffer_specs;
|
||||
|
@ -489,13 +489,9 @@ private:
|
|||
r.deleter(r.ptr);
|
||||
}
|
||||
heap_resources.clear();
|
||||
unlock_images();
|
||||
ref_resources.clear();
|
||||
buffer_count = 0;
|
||||
}
|
||||
|
||||
void lock_images();
|
||||
void unlock_images();
|
||||
};
|
||||
|
||||
Program _program;
|
||||
|
|
|
@ -1,10 +1,8 @@
|
|||
#include "voxel_generator_flat.h"
|
||||
|
||||
VoxelGeneratorFlat::VoxelGeneratorFlat() {
|
||||
}
|
||||
VoxelGeneratorFlat::VoxelGeneratorFlat() {}
|
||||
|
||||
VoxelGeneratorFlat::~VoxelGeneratorFlat() {
|
||||
}
|
||||
VoxelGeneratorFlat::~VoxelGeneratorFlat() {}
|
||||
|
||||
void VoxelGeneratorFlat::set_channel(VoxelBuffer::ChannelId p_channel) {
|
||||
const VoxelBufferInternal::ChannelId channel = VoxelBufferInternal::ChannelId(p_channel);
|
||||
|
@ -130,7 +128,9 @@ void VoxelGeneratorFlat::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_height", "h"), &VoxelGeneratorFlat::set_height);
|
||||
ClassDB::bind_method(D_METHOD("get_height"), &VoxelGeneratorFlat::get_height);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "channel", PROPERTY_HINT_ENUM, VoxelBuffer::CHANNEL_ID_HINT_STRING), "set_channel", "get_channel");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "height"), "set_height", "get_height");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "voxel_type", PROPERTY_HINT_RANGE, "0,65536,1"), "set_voxel_type", "get_voxel_type");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "channel", PROPERTY_HINT_ENUM, VoxelBuffer::CHANNEL_ID_HINT_STRING),
|
||||
"set_channel", "get_channel");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "height"), "set_height", "get_height");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "voxel_type", PROPERTY_HINT_RANGE, "0,65536,1"), "set_voxel_type",
|
||||
"get_voxel_type");
|
||||
}
|
||||
|
|
|
@ -2,11 +2,9 @@
|
|||
#include "../../util/fixed_array.h"
|
||||
#include "../../util/span.h"
|
||||
|
||||
VoxelGeneratorHeightmap::VoxelGeneratorHeightmap() {
|
||||
}
|
||||
VoxelGeneratorHeightmap::VoxelGeneratorHeightmap() {}
|
||||
|
||||
VoxelGeneratorHeightmap::~VoxelGeneratorHeightmap() {
|
||||
}
|
||||
VoxelGeneratorHeightmap::~VoxelGeneratorHeightmap() {}
|
||||
|
||||
void VoxelGeneratorHeightmap::set_channel(VoxelBuffer::ChannelId p_channel) {
|
||||
const VoxelBufferInternal::ChannelId channel = VoxelBufferInternal::ChannelId(p_channel);
|
||||
|
@ -77,8 +75,9 @@ void VoxelGeneratorHeightmap::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_iso_scale", "scale"), &VoxelGeneratorHeightmap::set_iso_scale);
|
||||
ClassDB::bind_method(D_METHOD("get_iso_scale"), &VoxelGeneratorHeightmap::get_iso_scale);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "channel", PROPERTY_HINT_ENUM, VoxelBuffer::CHANNEL_ID_HINT_STRING), "set_channel", "get_channel");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "height_start"), "set_height_start", "get_height_start");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "height_range"), "set_height_range", "get_height_range");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "iso_scale"), "set_iso_scale", "get_iso_scale");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "channel", PROPERTY_HINT_ENUM, VoxelBuffer::CHANNEL_ID_HINT_STRING),
|
||||
"set_channel", "get_channel");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "height_start"), "set_height_start", "get_height_start");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "height_range"), "set_height_range", "get_height_range");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "iso_scale"), "set_iso_scale", "get_iso_scale");
|
||||
}
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
|
||||
#include "../../storage/voxel_buffer.h"
|
||||
#include "../voxel_generator.h"
|
||||
#include <core/image.h>
|
||||
#include <core/io/image.h>
|
||||
|
||||
class VoxelGeneratorHeightmap : public VoxelGenerator {
|
||||
GDCLASS(VoxelGeneratorHeightmap, VoxelGenerator)
|
||||
|
|
|
@ -19,14 +19,9 @@ inline float get_height_blurred(const Image &im, int x, int y) {
|
|||
|
||||
} // namespace
|
||||
|
||||
VoxelGeneratorImage::VoxelGeneratorImage() {
|
||||
}
|
||||
VoxelGeneratorImage::VoxelGeneratorImage() {}
|
||||
|
||||
VoxelGeneratorImage::~VoxelGeneratorImage() {
|
||||
if (_parameters.image.is_valid()) {
|
||||
_parameters.image->unlock();
|
||||
}
|
||||
}
|
||||
VoxelGeneratorImage::~VoxelGeneratorImage() {}
|
||||
|
||||
void VoxelGeneratorImage::set_image(Ref<Image> im) {
|
||||
if (im == _image) {
|
||||
|
@ -38,15 +33,7 @@ void VoxelGeneratorImage::set_image(Ref<Image> im) {
|
|||
copy = im->duplicate();
|
||||
}
|
||||
RWLockWrite wlock(_parameters_lock);
|
||||
// lock() prevents us from reading the same image from multiple threads, so we lock it up-front.
|
||||
// This might no longer be needed in Godot 4.
|
||||
if (_parameters.image.is_valid()) {
|
||||
_parameters.image->unlock();
|
||||
}
|
||||
_parameters.image = copy;
|
||||
if (_parameters.image.is_valid()) {
|
||||
_parameters.image->lock();
|
||||
}
|
||||
}
|
||||
|
||||
Ref<Image> VoxelGeneratorImage::get_image() const {
|
||||
|
@ -79,14 +66,12 @@ VoxelGenerator::Result VoxelGeneratorImage::generate_block(VoxelBlockRequest &in
|
|||
|
||||
if (params.blur_enabled) {
|
||||
result = VoxelGeneratorHeightmap::generate(
|
||||
out_buffer,
|
||||
[&image](int x, int z) { return get_height_blurred(image, x, z); },
|
||||
input.origin_in_voxels, input.lod);
|
||||
out_buffer, [&image](int x, int z) { return get_height_blurred(image, x, z); }, input.origin_in_voxels,
|
||||
input.lod);
|
||||
} else {
|
||||
result = VoxelGeneratorHeightmap::generate(
|
||||
out_buffer,
|
||||
[&image](int x, int z) { return get_height_repeat(image, x, z); },
|
||||
input.origin_in_voxels, input.lod);
|
||||
out_buffer, [&image](int x, int z) { return get_height_repeat(image, x, z); }, input.origin_in_voxels,
|
||||
input.lod);
|
||||
}
|
||||
|
||||
out_buffer.compress_uniform_channels();
|
||||
|
@ -100,6 +85,7 @@ void VoxelGeneratorImage::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_blur_enabled", "enable"), &VoxelGeneratorImage::set_blur_enabled);
|
||||
ClassDB::bind_method(D_METHOD("is_blur_enabled"), &VoxelGeneratorImage::is_blur_enabled);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "image", PROPERTY_HINT_RESOURCE_TYPE, "Image"), "set_image", "get_image");
|
||||
ADD_PROPERTY(
|
||||
PropertyInfo(Variant::OBJECT, "image", PROPERTY_HINT_RESOURCE_TYPE, "Image"), "set_image", "get_image");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "blur_enabled"), "set_blur_enabled", "is_blur_enabled");
|
||||
}
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#define HEADER_VOXEL_GENERATOR_IMAGE
|
||||
|
||||
#include "voxel_generator_heightmap.h"
|
||||
#include <core/image.h>
|
||||
#include <core/io/image.h>
|
||||
|
||||
// Provides infinite tiling heightmap based on an image
|
||||
class VoxelGeneratorImage : public VoxelGeneratorHeightmap {
|
||||
|
|
|
@ -1,32 +1,33 @@
|
|||
#include "voxel_generator_noise.h"
|
||||
#include <core/config/engine.h>
|
||||
#include <core/core_string_names.h>
|
||||
#include <core/engine.h>
|
||||
|
||||
VoxelGeneratorNoise::VoxelGeneratorNoise() {
|
||||
#ifdef TOOLS_ENABLED
|
||||
if (Engine::get_singleton()->is_editor_hint()) {
|
||||
// Have one by default in editor
|
||||
Ref<OpenSimplexNoise> noise;
|
||||
noise.instance();
|
||||
noise.instantiate();
|
||||
set_noise(noise);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
VoxelGeneratorNoise::~VoxelGeneratorNoise() {
|
||||
}
|
||||
VoxelGeneratorNoise::~VoxelGeneratorNoise() {}
|
||||
|
||||
void VoxelGeneratorNoise::set_noise(Ref<OpenSimplexNoise> noise) {
|
||||
if (_noise == noise) {
|
||||
return;
|
||||
}
|
||||
if (_noise.is_valid()) {
|
||||
_noise->disconnect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise->disconnect(
|
||||
CoreStringNames::get_singleton()->changed, callable_mp(this, &VoxelGeneratorNoise::_on_noise_changed));
|
||||
}
|
||||
_noise = noise;
|
||||
Ref<OpenSimplexNoise> copy;
|
||||
if (_noise.is_valid()) {
|
||||
_noise->connect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise->connect(
|
||||
CoreStringNames::get_singleton()->changed, callable_mp(this, &VoxelGeneratorNoise::_on_noise_changed));
|
||||
// The OpenSimplexNoise resource is not thread-safe so we make a copy of it for use in threads
|
||||
copy = _noise->duplicate();
|
||||
}
|
||||
|
@ -249,8 +250,10 @@ void VoxelGeneratorNoise::_bind_methods() {
|
|||
|
||||
ClassDB::bind_method(D_METHOD("_on_noise_changed"), &VoxelGeneratorNoise::_on_noise_changed);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "channel", PROPERTY_HINT_ENUM, VoxelBuffer::CHANNEL_ID_HINT_STRING), "set_channel", "get_channel");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "noise", PROPERTY_HINT_RESOURCE_TYPE, "OpenSimplexNoise"), "set_noise", "get_noise");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "height_start"), "set_height_start", "get_height_start");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "height_range"), "set_height_range", "get_height_range");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "channel", PROPERTY_HINT_ENUM, VoxelBuffer::CHANNEL_ID_HINT_STRING),
|
||||
"set_channel", "get_channel");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "noise", PROPERTY_HINT_RESOURCE_TYPE, "OpenSimplexNoise"), "set_noise",
|
||||
"get_noise");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "height_start"), "set_height_start", "get_height_start");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "height_range"), "set_height_range", "get_height_range");
|
||||
}
|
||||
|
|
|
@ -1,32 +1,33 @@
|
|||
#include "voxel_generator_noise_2d.h"
|
||||
#include <core/config/engine.h>
|
||||
#include <core/core_string_names.h>
|
||||
#include <core/engine.h>
|
||||
|
||||
VoxelGeneratorNoise2D::VoxelGeneratorNoise2D() {
|
||||
#ifdef TOOLS_ENABLED
|
||||
if (Engine::get_singleton()->is_editor_hint()) {
|
||||
// Have one by default in editor
|
||||
Ref<OpenSimplexNoise> noise;
|
||||
noise.instance();
|
||||
noise.instantiate();
|
||||
set_noise(noise);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
VoxelGeneratorNoise2D::~VoxelGeneratorNoise2D() {
|
||||
}
|
||||
VoxelGeneratorNoise2D::~VoxelGeneratorNoise2D() {}
|
||||
|
||||
void VoxelGeneratorNoise2D::set_noise(Ref<OpenSimplexNoise> noise) {
|
||||
if (_noise == noise) {
|
||||
return;
|
||||
}
|
||||
if (_noise.is_valid()) {
|
||||
_noise->disconnect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise->disconnect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &VoxelGeneratorNoise2D::_on_noise_changed));
|
||||
}
|
||||
_noise = noise;
|
||||
Ref<OpenSimplexNoise> copy;
|
||||
if (_noise.is_valid()) {
|
||||
_noise->connect(CoreStringNames::get_singleton()->changed, this, "_on_noise_changed");
|
||||
_noise->connect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &VoxelGeneratorNoise2D::_on_noise_changed));
|
||||
// The OpenSimplexNoise resource is not thread-safe so we make a copy of it for use in threads
|
||||
copy = _noise->duplicate();
|
||||
}
|
||||
|
@ -43,12 +44,14 @@ void VoxelGeneratorNoise2D::set_curve(Ref<Curve> curve) {
|
|||
return;
|
||||
}
|
||||
if (_curve.is_valid()) {
|
||||
_curve->disconnect(CoreStringNames::get_singleton()->changed, this, "_on_curve_changed");
|
||||
_curve->disconnect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &VoxelGeneratorNoise2D::_on_curve_changed));
|
||||
}
|
||||
_curve = curve;
|
||||
RWLockWrite wlock(_parameters_lock);
|
||||
if (_curve.is_valid()) {
|
||||
_curve->connect(CoreStringNames::get_singleton()->changed, this, "_on_curve_changed");
|
||||
_curve->connect(CoreStringNames::get_singleton()->changed,
|
||||
callable_mp(this, &VoxelGeneratorNoise2D::_on_curve_changed));
|
||||
// The Curve resource is not thread-safe so we make a copy of it for use in threads
|
||||
_parameters.curve = _curve->duplicate();
|
||||
_parameters.curve->bake();
|
||||
|
@ -77,16 +80,14 @@ VoxelGenerator::Result VoxelGeneratorNoise2D::generate_block(VoxelBlockRequest &
|
|||
|
||||
if (_curve.is_null()) {
|
||||
result = VoxelGeneratorHeightmap::generate(
|
||||
out_buffer,
|
||||
[&noise](int x, int z) { return 0.5 + 0.5 * noise.get_noise_2d(x, z); },
|
||||
out_buffer, [&noise](int x, int z) { return 0.5 + 0.5 * noise.get_noise_2d(x, z); },
|
||||
input.origin_in_voxels, input.lod);
|
||||
} else {
|
||||
Curve &curve = **params.curve;
|
||||
result = VoxelGeneratorHeightmap::generate(
|
||||
out_buffer,
|
||||
[&noise, &curve](int x, int z) {
|
||||
return curve.interpolate_baked(0.5 + 0.5 * noise.get_noise_2d(x, z));
|
||||
},
|
||||
[&noise, &curve](
|
||||
int x, int z) { return curve.interpolate_baked(0.5 + 0.5 * noise.get_noise_2d(x, z)); },
|
||||
input.origin_in_voxels, input.lod);
|
||||
}
|
||||
|
||||
|
@ -114,9 +115,11 @@ void VoxelGeneratorNoise2D::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_curve", "curve"), &VoxelGeneratorNoise2D::set_curve);
|
||||
ClassDB::bind_method(D_METHOD("get_curve"), &VoxelGeneratorNoise2D::get_curve);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("_on_noise_changed"), &VoxelGeneratorNoise2D::_on_noise_changed);
|
||||
ClassDB::bind_method(D_METHOD("_on_curve_changed"), &VoxelGeneratorNoise2D::_on_curve_changed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_noise_changed"), &VoxelGeneratorNoise2D::_on_noise_changed);
|
||||
// ClassDB::bind_method(D_METHOD("_on_curve_changed"), &VoxelGeneratorNoise2D::_on_curve_changed);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "noise", PROPERTY_HINT_RESOURCE_TYPE, "OpenSimplexNoise"), "set_noise", "get_noise");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "curve", PROPERTY_HINT_RESOURCE_TYPE, "Curve"), "set_curve", "get_curve");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "noise", PROPERTY_HINT_RESOURCE_TYPE, "OpenSimplexNoise"), "set_noise",
|
||||
"get_noise");
|
||||
ADD_PROPERTY(
|
||||
PropertyInfo(Variant::OBJECT, "curve", PROPERTY_HINT_RESOURCE_TYPE, "Curve"), "set_curve", "get_curve");
|
||||
}
|
||||
|
|
|
@ -1,8 +1,7 @@
|
|||
#include "voxel_generator.h"
|
||||
#include "../constants/voxel_string_names.h"
|
||||
|
||||
VoxelGenerator::VoxelGenerator() {
|
||||
}
|
||||
VoxelGenerator::VoxelGenerator() {}
|
||||
|
||||
VoxelGenerator::Result VoxelGenerator::generate_block(VoxelBlockRequest &input) {
|
||||
return Result();
|
||||
|
@ -30,11 +29,11 @@ VoxelSingleValue VoxelGenerator::generate_single(Vector3i pos, unsigned int chan
|
|||
void VoxelGenerator::_b_generate_block(Ref<VoxelBuffer> out_buffer, Vector3 origin_in_voxels, int lod) {
|
||||
ERR_FAIL_COND(lod < 0);
|
||||
ERR_FAIL_COND(out_buffer.is_null());
|
||||
VoxelBlockRequest r = { out_buffer->get_buffer(), Vector3i::from_floored(origin_in_voxels), lod };
|
||||
VoxelBlockRequest r = { out_buffer->get_buffer(), Vector3iUtil::from_floored(origin_in_voxels), lod };
|
||||
generate_block(r);
|
||||
}
|
||||
|
||||
void VoxelGenerator::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("generate_block", "out_buffer", "origin_in_voxels", "lod"),
|
||||
&VoxelGenerator::_b_generate_block);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("generate_block", "out_buffer", "origin_in_voxels", "lod"), &VoxelGenerator::_b_generate_block);
|
||||
}
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#define VOXEL_GENERATOR_H
|
||||
|
||||
#include "../streams/voxel_block_request.h"
|
||||
#include <core/resource.h>
|
||||
#include <core/io/resource.h>
|
||||
|
||||
union VoxelSingleValue {
|
||||
uint64_t i;
|
||||
|
|
|
@ -2,19 +2,21 @@
|
|||
#include "../constants/voxel_string_names.h"
|
||||
#include "../util/godot/funcs.h"
|
||||
|
||||
VoxelGeneratorScript::VoxelGeneratorScript() {
|
||||
}
|
||||
VoxelGeneratorScript::VoxelGeneratorScript() {}
|
||||
|
||||
VoxelGenerator::Result VoxelGeneratorScript::generate_block(VoxelBlockRequest &input) {
|
||||
Result result;
|
||||
Variant ret;
|
||||
|
||||
// Create a temporary wrapper so Godot can pass it to scripts
|
||||
Ref<VoxelBuffer> buffer_wrapper;
|
||||
buffer_wrapper.instance();
|
||||
buffer_wrapper.instantiate();
|
||||
buffer_wrapper->get_buffer().copy_format(input.voxel_buffer);
|
||||
buffer_wrapper->get_buffer().create(input.voxel_buffer.get_size());
|
||||
try_call_script(this, VoxelStringNames::get_singleton()->_generate_block,
|
||||
buffer_wrapper, input.origin_in_voxels.to_vec3(), input.lod, &ret);
|
||||
|
||||
if (!GDVIRTUAL_CALL(_generate_block, buffer_wrapper, input.origin_in_voxels, input.lod)) {
|
||||
WARN_PRINT_ONCE("VoxelGeneratorScript::_generate_block is unimplemented!");
|
||||
}
|
||||
|
||||
// The wrapper is discarded
|
||||
buffer_wrapper->get_buffer().move_to(input.voxel_buffer);
|
||||
|
||||
|
@ -28,18 +30,21 @@ VoxelGenerator::Result VoxelGeneratorScript::generate_block(VoxelBlockRequest &i
|
|||
}
|
||||
|
||||
int VoxelGeneratorScript::get_used_channels_mask() const {
|
||||
Variant ret;
|
||||
if (try_call_script(this, VoxelStringNames::get_singleton()->_get_used_channels_mask, nullptr, 0, &ret)) {
|
||||
return ret;
|
||||
int mask = 0;
|
||||
if (!GDVIRTUAL_CALL(_get_used_channels_mask, mask)) {
|
||||
WARN_PRINT_ONCE("VoxelGeneratorScript::_get_used_channels_mask is unimplemented!");
|
||||
}
|
||||
return 0;
|
||||
return mask;
|
||||
}
|
||||
|
||||
void VoxelGeneratorScript::_bind_methods() {
|
||||
BIND_VMETHOD(MethodInfo("_generate_block",
|
||||
PropertyInfo(Variant::OBJECT, "out_buffer", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_DEFAULT, "VoxelBuffer"),
|
||||
PropertyInfo(Variant::VECTOR3, "origin_in_voxels"),
|
||||
PropertyInfo(Variant::INT, "lod")));
|
||||
// TODO Test if GDVIRTUAL can print errors properly when GDScript fails inside a different thread.
|
||||
GDVIRTUAL_BIND(_generate_block, "out_buffer", "origin_in_voxels", "lod");
|
||||
GDVIRTUAL_BIND(_get_used_channels_mask);
|
||||
|
||||
BIND_VMETHOD(MethodInfo(Variant::INT, "_get_used_channels_mask"));
|
||||
// BIND_VMETHOD(MethodInfo("_generate_block",
|
||||
// PropertyInfo(Variant::OBJECT, "out_buffer", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_DEFAULT, "VoxelBuffer"),
|
||||
// PropertyInfo(Variant::VECTOR3, "origin_in_voxels"), PropertyInfo(Variant::INT, "lod")));
|
||||
|
||||
// BIND_VMETHOD(MethodInfo(Variant::INT, "_get_used_channels_mask"));
|
||||
}
|
||||
|
|
|
@ -2,6 +2,8 @@
|
|||
#define VOXEL_GENERATOR_SCRIPT_H
|
||||
|
||||
#include "voxel_generator.h"
|
||||
#include <core/object/script_language.h> // needed for GDVIRTUAL macro
|
||||
#include <core/object/gdvirtual.gen.inc> // Also needed for GDVIRTUAL macro...
|
||||
|
||||
// Generator based on a script, like GDScript, C# or NativeScript.
|
||||
// The script is expected to properly handle multithreading.
|
||||
|
@ -13,6 +15,10 @@ public:
|
|||
Result generate_block(VoxelBlockRequest &input) override;
|
||||
int get_used_channels_mask() const override;
|
||||
|
||||
protected:
|
||||
GDVIRTUAL3(_generate_block, Ref<VoxelBuffer>, Vector3i, int)
|
||||
GDVIRTUAL0RC(int, _get_used_channels_mask) // I think `C` means `const`?
|
||||
|
||||
private:
|
||||
static void _bind_methods();
|
||||
};
|
||||
|
|
|
@ -6,12 +6,7 @@
|
|||
#define STRLEN(x) (sizeof(x) / sizeof(x[0]))
|
||||
|
||||
Voxel::Voxel() :
|
||||
_id(-1),
|
||||
_material_id(0),
|
||||
_transparency_index(0),
|
||||
_color(1.f, 1.f, 1.f),
|
||||
_geometry_type(GEOMETRY_NONE) {
|
||||
}
|
||||
_id(-1), _material_id(0), _transparency_index(0), _color(1.f, 1.f, 1.f), _geometry_type(GEOMETRY_NONE) {}
|
||||
|
||||
static Cube::Side name_to_side(const String &s) {
|
||||
if (s == "left") {
|
||||
|
@ -69,7 +64,7 @@ bool Voxel::_get(const StringName &p_name, Variant &r_ret) const {
|
|||
|
||||
void Voxel::_get_property_list(List<PropertyInfo> *p_list) const {
|
||||
if (_geometry_type == GEOMETRY_CUBE) {
|
||||
p_list->push_back(PropertyInfo(Variant::REAL, "cube_geometry/padding_y"));
|
||||
p_list->push_back(PropertyInfo(Variant::FLOAT, "cube_geometry/padding_y"));
|
||||
p_list->push_back(PropertyInfo(Variant::VECTOR2, "cube_tiles/left"));
|
||||
p_list->push_back(PropertyInfo(Variant::VECTOR2, "cube_tiles/right"));
|
||||
p_list->push_back(PropertyInfo(Variant::VECTOR2, "cube_tiles/bottom"));
|
||||
|
@ -139,7 +134,7 @@ void Voxel::set_geometry_type(GeometryType type) {
|
|||
break;
|
||||
}
|
||||
#ifdef TOOLS_ENABLED
|
||||
property_list_changed_notify();
|
||||
notify_property_list_changed();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -151,8 +146,7 @@ void Voxel::set_custom_mesh(Ref<Mesh> mesh) {
|
|||
_custom_mesh = mesh;
|
||||
}
|
||||
|
||||
void Voxel::set_cube_geometry() {
|
||||
}
|
||||
void Voxel::set_cube_geometry() {}
|
||||
|
||||
void Voxel::set_random_tickable(bool rt) {
|
||||
_random_tickable = rt;
|
||||
|
@ -164,7 +158,7 @@ void Voxel::set_cube_uv_side(int side, Vector2 tile_pos) {
|
|||
|
||||
Ref<Resource> Voxel::duplicate(bool p_subresources) const {
|
||||
Ref<Voxel> d_ref;
|
||||
d_ref.instance();
|
||||
d_ref.instantiate();
|
||||
Voxel &d = **d_ref;
|
||||
|
||||
d._id = -1;
|
||||
|
@ -262,13 +256,13 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
|
||||
ERR_FAIL_COND(arrays.size() == 0);
|
||||
|
||||
PoolIntArray indices = arrays[Mesh::ARRAY_INDEX];
|
||||
PackedInt32Array indices = arrays[Mesh::ARRAY_INDEX];
|
||||
ERR_FAIL_COND_MSG(indices.size() % 3 != 0, "Mesh is empty or does not contain triangles");
|
||||
|
||||
PoolVector3Array positions = arrays[Mesh::ARRAY_VERTEX];
|
||||
PoolVector3Array normals = arrays[Mesh::ARRAY_NORMAL];
|
||||
PoolVector2Array uvs = arrays[Mesh::ARRAY_TEX_UV];
|
||||
PoolVector<float> tangents = arrays[Mesh::ARRAY_TANGENT];
|
||||
PackedVector3Array positions = arrays[Mesh::ARRAY_VERTEX];
|
||||
PackedVector3Array normals = arrays[Mesh::ARRAY_NORMAL];
|
||||
PackedVector2Array uvs = arrays[Mesh::ARRAY_TEX_UV];
|
||||
PackedFloat32Array tangents = arrays[Mesh::ARRAY_TANGENT];
|
||||
|
||||
baked_data.empty = positions.size() == 0;
|
||||
|
||||
|
@ -307,7 +301,7 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
|
||||
if (uvs.size() == 0) {
|
||||
// TODO Properly generate UVs if there arent any
|
||||
uvs = PoolVector2Array();
|
||||
uvs = PackedVector2Array();
|
||||
uvs.resize(positions.size());
|
||||
}
|
||||
|
||||
|
@ -324,11 +318,11 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
|
||||
// Separate triangles belonging to faces of the cube
|
||||
{
|
||||
PoolIntArray::Read indices_read = indices.read();
|
||||
PoolVector3Array::Read positions_read = positions.read();
|
||||
PoolVector3Array::Read normals_read = normals.read();
|
||||
PoolVector2Array::Read uvs_read = uvs.read();
|
||||
PoolVector<float>::Read tangents_read = tangents.read();
|
||||
// PackedInt32Array::Read indices_read = indices.read();
|
||||
// PackedVector3Array::Read positions_read = positions.read();
|
||||
// PackedVector3Array::Read normals_read = normals.read();
|
||||
// PackedVector2Array::Read uvs_read = uvs.read();
|
||||
// PackedFloat32Array::Read tangents_read = tangents.read();
|
||||
|
||||
FixedArray<HashMap<int, int>, Cube::SIDE_COUNT> added_side_indices;
|
||||
HashMap<int, int> added_regular_indices;
|
||||
|
@ -339,16 +333,16 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
for (int i = 0; i < indices.size(); i += 3) {
|
||||
Cube::SideAxis side;
|
||||
|
||||
tri_positions[0] = positions_read[indices_read[i]];
|
||||
tri_positions[1] = positions_read[indices_read[i + 1]];
|
||||
tri_positions[2] = positions_read[indices_read[i + 2]];
|
||||
tri_positions[0] = positions[indices[i]];
|
||||
tri_positions[1] = positions[indices[i + 1]];
|
||||
tri_positions[2] = positions[indices[i + 2]];
|
||||
|
||||
FixedArray<float, 4> tangent;
|
||||
|
||||
if (tangents_empty && bake_tangents) {
|
||||
//If tangents are empty then we calculate them
|
||||
Vector2 delta_uv1 = uvs_read[indices_read[i + 1]] - uvs_read[indices_read[i]];
|
||||
Vector2 delta_uv2 = uvs_read[indices_read[i + 2]] - uvs_read[indices_read[i]];
|
||||
Vector2 delta_uv1 = uvs[indices[i + 1]] - uvs[indices[i]];
|
||||
Vector2 delta_uv2 = uvs[indices[i + 2]] - uvs[indices[i]];
|
||||
Vector3 delta_pos1 = tri_positions[1] - tri_positions[0];
|
||||
Vector3 delta_pos2 = tri_positions[2] - tri_positions[0];
|
||||
float r = 1.0f / (delta_uv1[0] * delta_uv2[1] - delta_uv1[1] * delta_uv2[0]);
|
||||
|
@ -357,7 +351,7 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
tangent[0] = t[0];
|
||||
tangent[1] = t[1];
|
||||
tangent[2] = t[2];
|
||||
tangent[3] = (bt.dot(normals_read[indices_read[i]].cross(t))) < 0 ? -1.0f : 1.0f;
|
||||
tangent[3] = (bt.dot(normals[indices[i]].cross(t))) < 0 ? -1.0f : 1.0f;
|
||||
}
|
||||
|
||||
if (L::get_triangle_side(tri_positions[0], tri_positions[1], tri_positions[2], side)) {
|
||||
|
@ -366,7 +360,7 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
int next_side_index = model.side_positions[side].size();
|
||||
|
||||
for (int j = 0; j < 3; ++j) {
|
||||
int src_index = indices_read[i + j];
|
||||
int src_index = indices[i + j];
|
||||
const int *existing_dst_index = added_side_indices[side].getptr(src_index);
|
||||
|
||||
if (existing_dst_index == nullptr) {
|
||||
|
@ -374,7 +368,7 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
|
||||
model.side_indices[side].push_back(next_side_index);
|
||||
model.side_positions[side].push_back(tri_positions[j]);
|
||||
model.side_uvs[side].push_back(uvs_read[indices_read[i + j]]);
|
||||
model.side_uvs[side].push_back(uvs[indices[i + j]]);
|
||||
|
||||
if (bake_tangents) {
|
||||
if (tangents_empty) {
|
||||
|
@ -387,10 +381,10 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
// i is the first vertex of each triangle which increments by steps of 3.
|
||||
// There are 4 floats per tangent.
|
||||
int ti = (i / 3) * 4;
|
||||
model.side_tangents[side].push_back(tangents_read[ti]);
|
||||
model.side_tangents[side].push_back(tangents_read[ti + 1]);
|
||||
model.side_tangents[side].push_back(tangents_read[ti + 2]);
|
||||
model.side_tangents[side].push_back(tangents_read[ti + 3]);
|
||||
model.side_tangents[side].push_back(tangents[ti]);
|
||||
model.side_tangents[side].push_back(tangents[ti + 1]);
|
||||
model.side_tangents[side].push_back(tangents[ti + 2]);
|
||||
model.side_tangents[side].push_back(tangents[ti + 3]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -409,14 +403,14 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
int next_regular_index = model.positions.size();
|
||||
|
||||
for (int j = 0; j < 3; ++j) {
|
||||
int src_index = indices_read[i + j];
|
||||
int src_index = indices[i + j];
|
||||
const int *existing_dst_index = added_regular_indices.getptr(src_index);
|
||||
|
||||
if (existing_dst_index == nullptr) {
|
||||
model.indices.push_back(next_regular_index);
|
||||
model.positions.push_back(tri_positions[j]);
|
||||
model.normals.push_back(normals_read[indices_read[i + j]]);
|
||||
model.uvs.push_back(uvs_read[indices_read[i + j]]);
|
||||
model.normals.push_back(normals[indices[i + j]]);
|
||||
model.uvs.push_back(uvs[indices[i + j]]);
|
||||
|
||||
if (bake_tangents) {
|
||||
if (tangents_empty) {
|
||||
|
@ -429,10 +423,10 @@ static void bake_mesh_geometry(Voxel &config, Voxel::BakedData &baked_data, bool
|
|||
// i is the first vertex of each triangle which increments by steps of 3.
|
||||
// There are 4 floats per tangent.
|
||||
int ti = (i / 3) * 4;
|
||||
model.tangents.push_back(tangents_read[ti]);
|
||||
model.tangents.push_back(tangents_read[ti + 1]);
|
||||
model.tangents.push_back(tangents_read[ti + 2]);
|
||||
model.tangents.push_back(tangents_read[ti + 3]);
|
||||
model.tangents.push_back(tangents[ti]);
|
||||
model.tangents.push_back(tangents[ti + 1]);
|
||||
model.tangents.push_back(tangents[ti + 2]);
|
||||
model.tangents.push_back(tangents[ti + 3]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -524,12 +518,12 @@ void Voxel::_bind_methods() {
|
|||
ADD_PROPERTY(PropertyInfo(Variant::INT, "material_id"), "set_material_id", "get_material_id");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "geometry_type", PROPERTY_HINT_ENUM, "None,Cube,CustomMesh"),
|
||||
"set_geometry_type", "get_geometry_type");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "custom_mesh", PROPERTY_HINT_RESOURCE_TYPE, "Mesh"),
|
||||
"set_custom_mesh", "get_custom_mesh");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "custom_mesh", PROPERTY_HINT_RESOURCE_TYPE, "Mesh"), "set_custom_mesh",
|
||||
"get_custom_mesh");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::ARRAY, "collision_aabbs", PROPERTY_HINT_TYPE_STRING, itos(Variant::AABB) + ":"),
|
||||
"set_collision_aabbs", "get_collision_aabbs");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "collision_mask", PROPERTY_HINT_LAYERS_3D_PHYSICS),
|
||||
"set_collision_mask", "get_collision_mask");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "collision_mask", PROPERTY_HINT_LAYERS_3D_PHYSICS), "set_collision_mask",
|
||||
"get_collision_mask");
|
||||
|
||||
BIND_ENUM_CONSTANT(GEOMETRY_NONE);
|
||||
BIND_ENUM_CONSTANT(GEOMETRY_CUBE);
|
||||
|
|
|
@ -1,12 +1,11 @@
|
|||
#include "voxel_library.h"
|
||||
#include "../../util/macros.h"
|
||||
#include <core/math/geometry_2d.h>
|
||||
#include <bitset>
|
||||
|
||||
VoxelLibrary::VoxelLibrary() {
|
||||
}
|
||||
VoxelLibrary::VoxelLibrary() {}
|
||||
|
||||
VoxelLibrary::~VoxelLibrary() {
|
||||
}
|
||||
VoxelLibrary::~VoxelLibrary() {}
|
||||
|
||||
unsigned int VoxelLibrary::get_voxel_count() const {
|
||||
return _voxel_types.size();
|
||||
|
@ -19,7 +18,7 @@ void VoxelLibrary::set_voxel_count(unsigned int type_count) {
|
|||
}
|
||||
// Note: a smaller size may cause a loss of data
|
||||
_voxel_types.resize(type_count);
|
||||
_change_notify();
|
||||
notify_property_list_changed();
|
||||
_needs_baking = true;
|
||||
}
|
||||
|
||||
|
@ -128,8 +127,7 @@ void VoxelLibrary::set_voxel(unsigned int idx, Ref<Voxel> voxel) {
|
|||
_needs_baking = true;
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
static void rasterize_triangle_barycentric(Vector2 a, Vector2 b, Vector2 c, F output_func) {
|
||||
template <typename F> static void rasterize_triangle_barycentric(Vector2 a, Vector2 b, Vector2 c, F output_func) {
|
||||
// Slower than scanline method, but looks better
|
||||
|
||||
// Grow the triangle a tiny bit, to help against floating point error
|
||||
|
@ -148,7 +146,7 @@ static void rasterize_triangle_barycentric(Vector2 a, Vector2 b, Vector2 c, F ou
|
|||
|
||||
for (int y = min_y; y < max_y; ++y) {
|
||||
for (int x = min_x; x < max_x; ++x) {
|
||||
if (Geometry::is_point_in_triangle(Vector2(x, y) + offset, a, b, c)) {
|
||||
if (Geometry2D::is_point_in_triangle(Vector2(x, y) + offset, a, b, c)) {
|
||||
output_func(x, y);
|
||||
}
|
||||
}
|
||||
|
@ -407,7 +405,8 @@ void VoxelLibrary::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("bake"), &VoxelLibrary::bake);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "atlas_size"), "set_atlas_size", "get_atlas_size");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "voxel_count", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_EDITOR), "set_voxel_count", "get_voxel_count");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "voxel_count", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_EDITOR),
|
||||
"set_voxel_count", "get_voxel_count");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "bake_tangents"), "set_bake_tangents", "get_bake_tangents");
|
||||
|
||||
BIND_CONSTANT(MAX_VOXEL_TYPES);
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
|
||||
#include "../../util/dynamic_bitset.h"
|
||||
#include "voxel.h"
|
||||
#include <core/resource.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
|
||||
// TODO Rename VoxelBlockyLibrary
|
||||
|
||||
|
|
|
@ -8,23 +8,17 @@
|
|||
// Utility functions
|
||||
namespace {
|
||||
|
||||
template <typename T>
|
||||
void raw_copy_to(PoolVector<T> &to, const Vector<T> &from) {
|
||||
to.resize(from.size());
|
||||
typename PoolVector<T>::Write w = to.write();
|
||||
memcpy(w.ptr(), from.ptr(), from.size() * sizeof(T));
|
||||
}
|
||||
|
||||
const int g_opposite_side[6] = {
|
||||
Cube::SIDE_NEGATIVE_X,
|
||||
Cube::SIDE_POSITIVE_X,
|
||||
Cube::SIDE_POSITIVE_Y,
|
||||
Cube::SIDE_NEGATIVE_Y,
|
||||
Cube::SIDE_POSITIVE_Z,
|
||||
Cube::SIDE_NEGATIVE_Z
|
||||
Cube::SIDE_NEGATIVE_X, //
|
||||
Cube::SIDE_POSITIVE_X, //
|
||||
Cube::SIDE_POSITIVE_Y, //
|
||||
Cube::SIDE_NEGATIVE_Y, //
|
||||
Cube::SIDE_POSITIVE_Z, //
|
||||
Cube::SIDE_NEGATIVE_Z //
|
||||
};
|
||||
|
||||
inline bool is_face_visible(const VoxelLibrary::BakedData &lib, const Voxel::BakedData &vt, uint32_t other_voxel_id, int side) {
|
||||
inline bool is_face_visible(
|
||||
const VoxelLibrary::BakedData &lib, const Voxel::BakedData &vt, uint32_t other_voxel_id, int side) {
|
||||
if (other_voxel_id < lib.models.size()) {
|
||||
const Voxel::BakedData &other_vt = lib.models[other_voxel_id];
|
||||
if (other_vt.empty || (other_vt.transparency_index > vt.transparency_index)) {
|
||||
|
@ -52,13 +46,11 @@ inline bool contributes_to_ao(const VoxelLibrary::BakedData &lib, uint32_t voxel
|
|||
template <typename Type_T>
|
||||
static void generate_blocky_mesh(
|
||||
FixedArray<VoxelMesherBlocky::Arrays, VoxelMesherBlocky::MAX_MATERIALS> &out_arrays_per_material,
|
||||
const Span<Type_T> type_buffer,
|
||||
const Vector3i block_size,
|
||||
const VoxelLibrary::BakedData &library,
|
||||
const Span<Type_T> type_buffer, const Vector3i block_size, const VoxelLibrary::BakedData &library,
|
||||
bool bake_occlusion, float baked_occlusion_darkness) {
|
||||
ERR_FAIL_COND(block_size.x < static_cast<int>(2 * VoxelMesherBlocky::PADDING) ||
|
||||
block_size.y < static_cast<int>(2 * VoxelMesherBlocky::PADDING) ||
|
||||
block_size.z < static_cast<int>(2 * VoxelMesherBlocky::PADDING));
|
||||
block_size.y < static_cast<int>(2 * VoxelMesherBlocky::PADDING) ||
|
||||
block_size.z < static_cast<int>(2 * VoxelMesherBlocky::PADDING));
|
||||
|
||||
// Build lookup tables so to speed up voxel access.
|
||||
// These are values to add to an address in order to get given neighbor.
|
||||
|
@ -67,8 +59,8 @@ static void generate_blocky_mesh(
|
|||
const int deck_size = block_size.x * row_size;
|
||||
|
||||
// Data must be padded, hence the off-by-one
|
||||
const Vector3i min = Vector3i(VoxelMesherBlocky::PADDING);
|
||||
const Vector3i max = block_size - Vector3i(VoxelMesherBlocky::PADDING);
|
||||
const Vector3i min = Vector3iUtil::create(VoxelMesherBlocky::PADDING);
|
||||
const Vector3i max = block_size - Vector3iUtil::create(VoxelMesherBlocky::PADDING);
|
||||
|
||||
int index_offsets[VoxelMesherBlocky::MAX_MATERIALS] = { 0 };
|
||||
|
||||
|
@ -81,14 +73,19 @@ static void generate_blocky_mesh(
|
|||
side_neighbor_lut[Cube::SIDE_TOP] = 1;
|
||||
|
||||
FixedArray<int, Cube::EDGE_COUNT> edge_neighbor_lut;
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_BACK] = side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_BACK];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_FRONT] = side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_FRONT];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_LEFT] = side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_RIGHT] = side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_BACK] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_BACK];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_FRONT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_FRONT];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_LEFT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
edge_neighbor_lut[Cube::EDGE_BOTTOM_RIGHT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
edge_neighbor_lut[Cube::EDGE_BACK_LEFT] = side_neighbor_lut[Cube::SIDE_BACK] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
edge_neighbor_lut[Cube::EDGE_BACK_RIGHT] = side_neighbor_lut[Cube::SIDE_BACK] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
edge_neighbor_lut[Cube::EDGE_FRONT_LEFT] = side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
edge_neighbor_lut[Cube::EDGE_FRONT_RIGHT] = side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
edge_neighbor_lut[Cube::EDGE_FRONT_RIGHT] =
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
edge_neighbor_lut[Cube::EDGE_TOP_BACK] = side_neighbor_lut[Cube::SIDE_TOP] + side_neighbor_lut[Cube::SIDE_BACK];
|
||||
edge_neighbor_lut[Cube::EDGE_TOP_FRONT] = side_neighbor_lut[Cube::SIDE_TOP] + side_neighbor_lut[Cube::SIDE_FRONT];
|
||||
edge_neighbor_lut[Cube::EDGE_TOP_LEFT] = side_neighbor_lut[Cube::SIDE_TOP] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
|
@ -96,45 +93,29 @@ static void generate_blocky_mesh(
|
|||
|
||||
FixedArray<int, Cube::CORNER_COUNT> corner_neighbor_lut;
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_BACK_LEFT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] +
|
||||
side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_BACK_LEFT] = side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_BACK_RIGHT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] +
|
||||
side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_BACK_RIGHT] = side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_FRONT_RIGHT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] +
|
||||
side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_FRONT_RIGHT] = side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_FRONT_LEFT] =
|
||||
side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] +
|
||||
side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
corner_neighbor_lut[Cube::CORNER_BOTTOM_FRONT_LEFT] = side_neighbor_lut[Cube::SIDE_BOTTOM] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_BACK_LEFT] =
|
||||
side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] +
|
||||
side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
side_neighbor_lut[Cube::SIDE_TOP] + side_neighbor_lut[Cube::SIDE_BACK] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_BACK_RIGHT] =
|
||||
side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] +
|
||||
side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_BACK_RIGHT] = side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_BACK] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_FRONT_RIGHT] =
|
||||
side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] +
|
||||
side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_FRONT_RIGHT] = side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_RIGHT];
|
||||
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_FRONT_LEFT] =
|
||||
side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] +
|
||||
side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
corner_neighbor_lut[Cube::CORNER_TOP_FRONT_LEFT] = side_neighbor_lut[Cube::SIDE_TOP] +
|
||||
side_neighbor_lut[Cube::SIDE_FRONT] + side_neighbor_lut[Cube::SIDE_LEFT];
|
||||
|
||||
//uint64_t time_prep = OS::get_singleton()->get_ticks_usec() - time_before;
|
||||
//time_before = OS::get_singleton()->get_ticks_usec();
|
||||
|
@ -142,7 +123,8 @@ static void generate_blocky_mesh(
|
|||
for (unsigned int z = min.z; z < (unsigned int)max.z; ++z) {
|
||||
for (unsigned int x = min.x; x < (unsigned int)max.x; ++x) {
|
||||
for (unsigned int y = min.y; y < (unsigned int)max.y; ++y) {
|
||||
// min and max are chosen such that you can visit 1 neighbor away from the current voxel without size check
|
||||
// min and max are chosen such that you can visit 1 neighbor away from the current voxel without size
|
||||
// check
|
||||
|
||||
const int voxel_index = y + x * row_size + z * deck_size;
|
||||
const int voxel_id = type_buffer[voxel_index];
|
||||
|
@ -176,8 +158,8 @@ static void generate_blocky_mesh(
|
|||
int shaded_corner[8] = { 0 };
|
||||
|
||||
if (bake_occlusion) {
|
||||
// Combinatory solution for https://0fps.net/2013/07/03/ambient-occlusion-for-minecraft-like-worlds/
|
||||
// (inverted)
|
||||
// Combinatory solution for
|
||||
// https://0fps.net/2013/07/03/ambient-occlusion-for-minecraft-like-worlds/ (inverted)
|
||||
// function vertexAO(side1, side2, corner) {
|
||||
// if(side1 && side2) {
|
||||
// return 0
|
||||
|
@ -198,7 +180,8 @@ static void generate_blocky_mesh(
|
|||
if (shaded_corner[corner] == 2) {
|
||||
shaded_corner[corner] = 3;
|
||||
} else {
|
||||
const int corner_neigbor_id = type_buffer[voxel_index + corner_neighbor_lut[corner]];
|
||||
const int corner_neigbor_id =
|
||||
type_buffer[voxel_index + corner_neighbor_lut[corner]];
|
||||
if (contributes_to_ao(library, corner_neigbor_id)) {
|
||||
++shaded_corner[corner];
|
||||
}
|
||||
|
@ -241,7 +224,7 @@ static void generate_blocky_mesh(
|
|||
arrays.normals.resize(arrays.normals.size() + vertex_count);
|
||||
Vector3 *w = arrays.normals.data() + append_index;
|
||||
for (unsigned int i = 0; i < vertex_count; ++i) {
|
||||
w[i] = Cube::g_side_normals[side].to_vec3();
|
||||
w[i] = Cube::g_side_normals[side];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -257,12 +240,14 @@ static void generate_blocky_mesh(
|
|||
|
||||
// General purpose occlusion colouring.
|
||||
// TODO Optimize for cubes
|
||||
// TODO Fix occlusion inconsistency caused by triangles orientation? Not sure if worth it
|
||||
// TODO Fix occlusion inconsistency caused by triangles orientation? Not sure if
|
||||
// worth it
|
||||
float shade = 0;
|
||||
for (unsigned int j = 0; j < 4; ++j) {
|
||||
unsigned int corner = Cube::g_side_corners[side][j];
|
||||
if (shaded_corner[corner]) {
|
||||
float s = baked_occlusion_darkness * static_cast<float>(shaded_corner[corner]);
|
||||
float s = baked_occlusion_darkness *
|
||||
static_cast<float>(shaded_corner[corner]);
|
||||
//float k = 1.f - Cube::g_corner_position[corner].distance_to(v);
|
||||
float k = 1.f - Cube::g_corner_position[corner].distance_squared_to(v);
|
||||
if (k < 0.0) {
|
||||
|
@ -351,13 +336,12 @@ VoxelMesherBlocky::VoxelMesherBlocky() {
|
|||
|
||||
// Default library, less steps to setup in editor
|
||||
Ref<VoxelLibrary> library;
|
||||
library.instance();
|
||||
library.instantiate();
|
||||
library->load_default();
|
||||
_parameters.library = library;
|
||||
}
|
||||
|
||||
VoxelMesherBlocky::~VoxelMesherBlocky() {
|
||||
}
|
||||
VoxelMesherBlocky::~VoxelMesherBlocky() {}
|
||||
|
||||
void VoxelMesherBlocky::set_library(Ref<VoxelLibrary> library) {
|
||||
RWLockWrite wlock(_parameters_lock);
|
||||
|
@ -437,8 +421,8 @@ void VoxelMesherBlocky::build(VoxelMesher::Output &output, const VoxelMesher::In
|
|||
// All voxels have the same type.
|
||||
// If it's all air, nothing to do. If it's all cubes, nothing to do either.
|
||||
// TODO Handle edge case of uniform block with non-cubic voxels!
|
||||
// If the type of voxel still produces geometry in this situation (which is an absurd use case but not an error),
|
||||
// decompress into a backing array to still allow the use of the same algorithm.
|
||||
// If the type of voxel still produces geometry in this situation (which is an absurd use case but not an
|
||||
// error), decompress into a backing array to still allow the use of the same algorithm.
|
||||
return;
|
||||
|
||||
} else if (voxels.get_channel_compression(channel) != VoxelBufferInternal::COMPRESSION_NONE) {
|
||||
|
@ -474,13 +458,13 @@ void VoxelMesherBlocky::build(VoxelMesher::Output &output, const VoxelMesher::In
|
|||
|
||||
switch (channel_depth) {
|
||||
case VoxelBufferInternal::DEPTH_8_BIT:
|
||||
generate_blocky_mesh(cache.arrays_per_material, raw_channel,
|
||||
block_size, library_baked_data, params.bake_occlusion, baked_occlusion_darkness);
|
||||
generate_blocky_mesh(cache.arrays_per_material, raw_channel, block_size, library_baked_data,
|
||||
params.bake_occlusion, baked_occlusion_darkness);
|
||||
break;
|
||||
|
||||
case VoxelBufferInternal::DEPTH_16_BIT:
|
||||
generate_blocky_mesh(cache.arrays_per_material, raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size, library_baked_data, params.bake_occlusion, baked_occlusion_darkness);
|
||||
generate_blocky_mesh(cache.arrays_per_material, raw_channel.reinterpret_cast_to<uint16_t>(), block_size,
|
||||
library_baked_data, params.bake_occlusion, baked_occlusion_darkness);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -498,11 +482,11 @@ void VoxelMesherBlocky::build(VoxelMesher::Output &output, const VoxelMesher::In
|
|||
mesh_arrays.resize(Mesh::ARRAY_MAX);
|
||||
|
||||
{
|
||||
PoolVector<Vector3> positions;
|
||||
PoolVector<Vector2> uvs;
|
||||
PoolVector<Vector3> normals;
|
||||
PoolVector<Color> colors;
|
||||
PoolVector<int> indices;
|
||||
PackedVector3Array positions;
|
||||
PackedVector2Array uvs;
|
||||
PackedVector3Array normals;
|
||||
PackedColorArray colors;
|
||||
PackedInt32Array indices;
|
||||
|
||||
raw_copy_to(positions, arrays.positions);
|
||||
raw_copy_to(uvs, arrays.uvs);
|
||||
|
@ -516,7 +500,7 @@ void VoxelMesherBlocky::build(VoxelMesher::Output &output, const VoxelMesher::In
|
|||
mesh_arrays[Mesh::ARRAY_COLOR] = colors;
|
||||
mesh_arrays[Mesh::ARRAY_INDEX] = indices;
|
||||
if (arrays.tangents.size() > 0) {
|
||||
PoolVector<float> tangents;
|
||||
PackedFloat32Array tangents;
|
||||
raw_copy_to(tangents, arrays.tangents);
|
||||
mesh_arrays[Mesh::ARRAY_TANGENT] = tangents;
|
||||
}
|
||||
|
@ -563,9 +547,9 @@ void VoxelMesherBlocky::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_occlusion_darkness", "value"), &VoxelMesherBlocky::set_occlusion_darkness);
|
||||
ClassDB::bind_method(D_METHOD("get_occlusion_darkness"), &VoxelMesherBlocky::get_occlusion_darkness);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "library", PROPERTY_HINT_RESOURCE_TYPE, "VoxelLibrary"),
|
||||
"set_library", "get_library");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "library", PROPERTY_HINT_RESOURCE_TYPE, "VoxelLibrary"), "set_library",
|
||||
"get_library");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "occlusion_enabled"), "set_occlusion_enabled", "get_occlusion_enabled");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "occlusion_darkness", PROPERTY_HINT_RANGE, "0,1,0.01"),
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "occlusion_darkness", PROPERTY_HINT_RANGE, "0,1,0.01"),
|
||||
"set_occlusion_darkness", "get_occlusion_darkness");
|
||||
}
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
|
||||
#include "../voxel_mesher.h"
|
||||
#include "voxel_library.h"
|
||||
#include <core/reference.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
#include <scene/resources/mesh.h>
|
||||
#include <vector>
|
||||
|
||||
|
|
|
@ -19,26 +19,20 @@ Color VoxelColorPalette::get_color(int index) const {
|
|||
return _colors[index];
|
||||
}
|
||||
|
||||
PoolColorArray VoxelColorPalette::get_colors() const {
|
||||
PoolColorArray colors;
|
||||
PackedColorArray VoxelColorPalette::get_colors() const {
|
||||
PackedColorArray colors;
|
||||
colors.resize(_colors.size());
|
||||
{
|
||||
PoolColorArray::Write w = colors.write();
|
||||
for (unsigned int i = 0; i < _colors.size(); ++i) {
|
||||
w[i] = _colors[i];
|
||||
}
|
||||
for (unsigned int i = 0; i < _colors.size(); ++i) {
|
||||
colors.write[i] = _colors[i];
|
||||
}
|
||||
return colors;
|
||||
}
|
||||
|
||||
void VoxelColorPalette::set_colors(PoolColorArray colors) {
|
||||
void VoxelColorPalette::set_colors(PackedColorArray colors) {
|
||||
// Color count is fixed, but we can't easily prevent Godot from allowing users to set a dynamic array
|
||||
ERR_FAIL_COND(colors.size() != static_cast<int>(_colors.size()));
|
||||
{
|
||||
PoolColorArray::Read r = colors.read();
|
||||
for (unsigned int i = 0; i < _colors.size(); ++i) {
|
||||
_colors[i] = Color8(r[i]);
|
||||
}
|
||||
for (unsigned int i = 0; i < _colors.size(); ++i) {
|
||||
_colors[i] = Color8(colors[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -48,23 +42,19 @@ void VoxelColorPalette::clear() {
|
|||
}
|
||||
}
|
||||
|
||||
PoolIntArray VoxelColorPalette::_b_get_data() const {
|
||||
PoolIntArray colors;
|
||||
PackedInt32Array VoxelColorPalette::_b_get_data() const {
|
||||
PackedInt32Array colors;
|
||||
colors.resize(_colors.size());
|
||||
{
|
||||
PoolIntArray::Write w = colors.write();
|
||||
for (size_t i = 0; i < _colors.size(); ++i) {
|
||||
w[i] = _colors[i].to_u32();
|
||||
}
|
||||
for (size_t i = 0; i < _colors.size(); ++i) {
|
||||
colors.write[i] = _colors[i].to_u32();
|
||||
}
|
||||
return colors;
|
||||
}
|
||||
|
||||
void VoxelColorPalette::_b_set_data(PoolIntArray colors) {
|
||||
void VoxelColorPalette::_b_set_data(PackedInt32Array colors) {
|
||||
ERR_FAIL_COND(colors.size() > static_cast<int>(_colors.size()));
|
||||
PoolIntArray::Read r = colors.read();
|
||||
for (int i = 0; i < colors.size(); ++i) {
|
||||
_colors[i] = Color8::from_u32(r[i]);
|
||||
_colors[i] = Color8::from_u32(colors[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -79,10 +69,10 @@ void VoxelColorPalette::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("get_data"), &VoxelColorPalette::_b_get_data);
|
||||
|
||||
// This is just to allow editing colors in the editor
|
||||
ADD_PROPERTY(PropertyInfo(Variant::POOL_COLOR_ARRAY, "colors", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_EDITOR),
|
||||
ADD_PROPERTY(PropertyInfo(Variant::PACKED_COLOR_ARRAY, "colors", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_EDITOR),
|
||||
"set_colors", "get_colors");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::POOL_INT_ARRAY, "data", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_STORAGE),
|
||||
ADD_PROPERTY(PropertyInfo(Variant::PACKED_INT32_ARRAY, "data", PROPERTY_HINT_NONE, "", PROPERTY_USAGE_STORAGE),
|
||||
"set_data", "get_data");
|
||||
|
||||
BIND_CONSTANT(MAX_COLORS);
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
|
||||
#include "../../util/fixed_array.h"
|
||||
#include "../../util/math/color8.h"
|
||||
#include <core/resource.h>
|
||||
#include <core/io/resource.h>
|
||||
|
||||
// Associates small numbers to colors, so colored voxels can be specified using less memory.
|
||||
class VoxelColorPalette : public Resource {
|
||||
|
@ -16,8 +16,8 @@ public:
|
|||
void set_color(int index, Color color);
|
||||
Color get_color(int index) const;
|
||||
|
||||
PoolColorArray get_colors() const;
|
||||
void set_colors(PoolColorArray colors);
|
||||
PackedColorArray get_colors() const;
|
||||
void set_colors(PackedColorArray colors);
|
||||
|
||||
void clear();
|
||||
|
||||
|
@ -32,8 +32,8 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
PoolIntArray _b_get_data() const;
|
||||
void _b_set_data(PoolIntArray colors);
|
||||
PackedInt32Array _b_get_data() const;
|
||||
void _b_set_data(PackedInt32Array colors);
|
||||
|
||||
static void _bind_methods();
|
||||
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
#include "../../storage/voxel_buffer.h"
|
||||
#include "../../util/funcs.h"
|
||||
#include "../../util/profiling.h"
|
||||
#include <core/math/geometry_2d.h>
|
||||
|
||||
namespace {
|
||||
// Table of indices for vertices of cube faces
|
||||
|
@ -34,7 +35,7 @@ const uint8_t g_indices_lut[3][2][6] = {
|
|||
}
|
||||
};
|
||||
|
||||
const uint8_t g_face_axes_lut[Vector3i::AXIS_COUNT][2] = {
|
||||
const uint8_t g_face_axes_lut[Vector3iUtil::AXIS_COUNT][2] = {
|
||||
// X
|
||||
{ Vector3i::AXIS_Y, Vector3i::AXIS_Z },
|
||||
// Y
|
||||
|
@ -43,10 +44,11 @@ const uint8_t g_face_axes_lut[Vector3i::AXIS_COUNT][2] = {
|
|||
{ Vector3i::AXIS_X, Vector3i::AXIS_Y }
|
||||
};
|
||||
|
||||
enum Side {
|
||||
SIDE_FRONT = 0,
|
||||
SIDE_BACK,
|
||||
SIDE_NONE // Either means there is no face, or it was consumed
|
||||
// Not named `Side` because Godot already defines that in global space
|
||||
enum FaceSide {
|
||||
FACE_SIDE_FRONT = 0,
|
||||
FACE_SIDE_BACK,
|
||||
FACE_SIDE_NONE // Either means there is no face, or it was consumed
|
||||
};
|
||||
|
||||
} // namespace
|
||||
|
@ -62,21 +64,19 @@ inline uint8_t get_alpha_index(Color8 c) {
|
|||
template <typename Voxel_T, typename Color_F>
|
||||
void build_voxel_mesh_as_simple_cubes(
|
||||
FixedArray<VoxelMesherCubes::Arrays, VoxelMesherCubes::MATERIAL_COUNT> &out_arrays_per_material,
|
||||
const Span<Voxel_T> voxel_buffer,
|
||||
const Vector3i block_size,
|
||||
Color_F color_func) {
|
||||
const Span<Voxel_T> voxel_buffer, const Vector3i block_size, Color_F color_func) {
|
||||
//
|
||||
ERR_FAIL_COND(block_size.x < static_cast<int>(2 * VoxelMesherCubes::PADDING) ||
|
||||
block_size.y < static_cast<int>(2 * VoxelMesherCubes::PADDING) ||
|
||||
block_size.z < static_cast<int>(2 * VoxelMesherCubes::PADDING));
|
||||
|
||||
const Vector3i min_pos = Vector3i(VoxelMesherCubes::PADDING);
|
||||
const Vector3i max_pos = block_size - Vector3i(VoxelMesherCubes::PADDING);
|
||||
const Vector3i min_pos = Vector3iUtil::create(VoxelMesherCubes::PADDING);
|
||||
const Vector3i max_pos = block_size - Vector3iUtil::create(VoxelMesherCubes::PADDING);
|
||||
const unsigned int row_size = block_size.y;
|
||||
const unsigned int deck_size = block_size.x * row_size;
|
||||
|
||||
// Note: voxel buffers are indexed in ZXY order
|
||||
FixedArray<uint32_t, Vector3i::AXIS_COUNT> neighbor_offset_d_lut;
|
||||
FixedArray<uint32_t, Vector3iUtil::AXIS_COUNT> neighbor_offset_d_lut;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_X] = block_size.y;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_Y] = 1;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_Z] = block_size.x * block_size.y;
|
||||
|
@ -84,7 +84,7 @@ void build_voxel_mesh_as_simple_cubes(
|
|||
FixedArray<uint32_t, VoxelMesherCubes::MATERIAL_COUNT> index_offsets(0);
|
||||
|
||||
// For each axis
|
||||
for (unsigned int za = 0; za < Vector3i::AXIS_COUNT; ++za) {
|
||||
for (unsigned int za = 0; za < Vector3iUtil::AXIS_COUNT; ++za) {
|
||||
const unsigned int xa = g_face_axes_lut[za][0];
|
||||
const unsigned int ya = g_face_axes_lut[za][1];
|
||||
|
||||
|
@ -93,13 +93,12 @@ void build_voxel_mesh_as_simple_cubes(
|
|||
// For each cell of the deck, gather face info
|
||||
for (unsigned int fy = min_pos[ya]; fy < (unsigned int)max_pos[ya]; ++fy) {
|
||||
for (unsigned int fx = min_pos[xa]; fx < (unsigned int)max_pos[xa]; ++fx) {
|
||||
FixedArray<unsigned int, Vector3i::AXIS_COUNT> pos;
|
||||
FixedArray<unsigned int, Vector3iUtil::AXIS_COUNT> pos;
|
||||
pos[xa] = fx;
|
||||
pos[ya] = fy;
|
||||
pos[za] = d;
|
||||
|
||||
const unsigned int voxel_index = pos[Vector3i::AXIS_Y] +
|
||||
pos[Vector3i::AXIS_X] * row_size +
|
||||
const unsigned int voxel_index = pos[Vector3i::AXIS_Y] + pos[Vector3i::AXIS_X] * row_size +
|
||||
pos[Vector3i::AXIS_Z] * deck_size;
|
||||
|
||||
const Voxel_T raw_color0 = voxel_buffer[voxel_index];
|
||||
|
@ -113,15 +112,15 @@ void build_voxel_mesh_as_simple_cubes(
|
|||
const uint8_t ai1 = get_alpha_index(color1);
|
||||
|
||||
Color8 color;
|
||||
Side side;
|
||||
FaceSide side;
|
||||
if (ai0 == ai1) {
|
||||
continue;
|
||||
} else if (ai0 > ai1) {
|
||||
color = color0;
|
||||
side = SIDE_BACK;
|
||||
side = FACE_SIDE_BACK;
|
||||
} else {
|
||||
color = color1;
|
||||
side = SIDE_FRONT;
|
||||
side = FACE_SIDE_FRONT;
|
||||
}
|
||||
|
||||
// Commit face to the mesh
|
||||
|
@ -155,7 +154,7 @@ void build_voxel_mesh_as_simple_cubes(
|
|||
v3[za] = d;
|
||||
|
||||
Vector3 n;
|
||||
n[za] = side == SIDE_FRONT ? -1 : 1;
|
||||
n[za] = side == FACE_SIDE_FRONT ? -1 : 1;
|
||||
|
||||
// 2-----3
|
||||
// | |
|
||||
|
@ -195,9 +194,7 @@ void build_voxel_mesh_as_simple_cubes(
|
|||
template <typename Voxel_T, typename Color_F>
|
||||
void build_voxel_mesh_as_greedy_cubes(
|
||||
FixedArray<VoxelMesherCubes::Arrays, VoxelMesherCubes::MATERIAL_COUNT> &out_arrays_per_material,
|
||||
const Span<Voxel_T> voxel_buffer,
|
||||
const Vector3i block_size,
|
||||
std::vector<uint8_t> &mask_memory_pool,
|
||||
const Span<Voxel_T> voxel_buffer, const Vector3i block_size, std::vector<uint8_t> &mask_memory_pool,
|
||||
Color_F color_func) {
|
||||
//
|
||||
ERR_FAIL_COND(block_size.x < static_cast<int>(2 * VoxelMesherCubes::PADDING) ||
|
||||
|
@ -217,13 +214,13 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
}
|
||||
};
|
||||
|
||||
const Vector3i min_pos = Vector3i(VoxelMesherCubes::PADDING);
|
||||
const Vector3i max_pos = block_size - Vector3i(VoxelMesherCubes::PADDING);
|
||||
const Vector3i min_pos = Vector3iUtil::create(VoxelMesherCubes::PADDING);
|
||||
const Vector3i max_pos = block_size - Vector3iUtil::create(VoxelMesherCubes::PADDING);
|
||||
const unsigned int row_size = block_size.y;
|
||||
const unsigned int deck_size = block_size.x * row_size;
|
||||
|
||||
// Note: voxel buffers are indexed in ZXY order
|
||||
FixedArray<uint32_t, Vector3i::AXIS_COUNT> neighbor_offset_d_lut;
|
||||
FixedArray<uint32_t, Vector3iUtil::AXIS_COUNT> neighbor_offset_d_lut;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_X] = block_size.y;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_Y] = 1;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_Z] = block_size.x * block_size.y;
|
||||
|
@ -231,7 +228,7 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
FixedArray<uint32_t, VoxelMesherCubes::MATERIAL_COUNT> index_offsets(0);
|
||||
|
||||
// For each axis
|
||||
for (unsigned int za = 0; za < Vector3i::AXIS_COUNT; ++za) {
|
||||
for (unsigned int za = 0; za < Vector3iUtil::AXIS_COUNT; ++za) {
|
||||
const unsigned int xa = g_face_axes_lut[za][0];
|
||||
const unsigned int ya = g_face_axes_lut[za][1];
|
||||
|
||||
|
@ -247,13 +244,12 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
// For each cell of the deck, gather face info
|
||||
for (unsigned int fy = min_pos[ya]; fy < (unsigned int)max_pos[ya]; ++fy) {
|
||||
for (unsigned int fx = min_pos[xa]; fx < (unsigned int)max_pos[xa]; ++fx) {
|
||||
FixedArray<unsigned int, Vector3i::AXIS_COUNT> pos;
|
||||
FixedArray<unsigned int, Vector3iUtil::AXIS_COUNT> pos;
|
||||
pos[xa] = fx;
|
||||
pos[ya] = fy;
|
||||
pos[za] = d;
|
||||
|
||||
const unsigned int voxel_index = pos[Vector3i::AXIS_Y] +
|
||||
pos[Vector3i::AXIS_X] * row_size +
|
||||
const unsigned int voxel_index = pos[Vector3i::AXIS_Y] + pos[Vector3i::AXIS_X] * row_size +
|
||||
pos[Vector3i::AXIS_Z] * deck_size;
|
||||
|
||||
const Voxel_T raw_color0 = voxel_buffer[voxel_index];
|
||||
|
@ -267,13 +263,13 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
|
||||
MaskValue mv;
|
||||
if (ai0 == ai1) {
|
||||
mv.side = SIDE_NONE;
|
||||
mv.side = FACE_SIDE_NONE;
|
||||
} else if (ai0 > ai1) {
|
||||
mv.color = raw_color0;
|
||||
mv.side = SIDE_BACK;
|
||||
mv.side = FACE_SIDE_BACK;
|
||||
} else {
|
||||
mv.color = raw_color1;
|
||||
mv.side = SIDE_FRONT;
|
||||
mv.side = FACE_SIDE_FRONT;
|
||||
}
|
||||
|
||||
mask[(fx - VoxelMesherCubes::PADDING) + (fy - VoxelMesherCubes::PADDING) * mask_size_x] = mv;
|
||||
|
@ -298,7 +294,7 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
const unsigned int mask_index = fx + fy * mask_size_x;
|
||||
const MaskValue m = mask[mask_index];
|
||||
|
||||
if (m.side == SIDE_NONE) {
|
||||
if (m.side == FACE_SIDE_NONE) {
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -311,9 +307,7 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
// Check if the next rows of faces are the same along Y
|
||||
unsigned int ry = fy + 1;
|
||||
while (ry < mask_size_y &&
|
||||
L::is_range_equal(mask,
|
||||
fx + ry * mask_size_x,
|
||||
rx + ry * mask_size_x, m)) {
|
||||
L::is_range_equal(mask, fx + ry * mask_size_x, rx + ry * mask_size_x, m)) {
|
||||
++ry;
|
||||
}
|
||||
|
||||
|
@ -344,7 +338,7 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
v3[za] = d;
|
||||
|
||||
Vector3 n;
|
||||
n[za] = m.side == SIDE_FRONT ? -1 : 1;
|
||||
n[za] = m.side == FACE_SIDE_FRONT ? -1 : 1;
|
||||
|
||||
// 2-----3
|
||||
// | |
|
||||
|
@ -376,7 +370,7 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
|
||||
for (unsigned int j = fy; j < ry; ++j) {
|
||||
for (unsigned int i = fx; i < rx; ++i) {
|
||||
mask[i + j * mask_size_x].side = SIDE_NONE;
|
||||
mask[i + j * mask_size_x].side = FACE_SIDE_NONE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -388,11 +382,8 @@ void build_voxel_mesh_as_greedy_cubes(
|
|||
template <typename Voxel_T, typename Color_F>
|
||||
void build_voxel_mesh_as_greedy_cubes_atlased(
|
||||
FixedArray<VoxelMesherCubes::Arrays, VoxelMesherCubes::MATERIAL_COUNT> &out_arrays_per_material,
|
||||
VoxelMesherCubes::GreedyAtlasData &out_greedy_atlas_data,
|
||||
const Span<Voxel_T> voxel_buffer,
|
||||
const Vector3i block_size,
|
||||
std::vector<uint8_t> &mask_memory_pool,
|
||||
Color_F color_func) {
|
||||
VoxelMesherCubes::GreedyAtlasData &out_greedy_atlas_data, const Span<Voxel_T> voxel_buffer,
|
||||
const Vector3i block_size, std::vector<uint8_t> &mask_memory_pool, Color_F color_func) {
|
||||
//
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
ERR_FAIL_COND(block_size.x < static_cast<int>(2 * VoxelMesherCubes::PADDING) ||
|
||||
|
@ -414,13 +405,13 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
|
||||
out_greedy_atlas_data.clear();
|
||||
|
||||
const Vector3i min_pos = Vector3i(VoxelMesherCubes::PADDING);
|
||||
const Vector3i max_pos = block_size - Vector3i(VoxelMesherCubes::PADDING);
|
||||
const Vector3i min_pos = Vector3iUtil::create(VoxelMesherCubes::PADDING);
|
||||
const Vector3i max_pos = block_size - Vector3iUtil::create(VoxelMesherCubes::PADDING);
|
||||
const unsigned int row_size = block_size.y;
|
||||
const unsigned int deck_size = block_size.x * row_size;
|
||||
|
||||
// Note: voxel buffers are indexed in ZXY order
|
||||
FixedArray<uint32_t, Vector3i::AXIS_COUNT> neighbor_offset_d_lut;
|
||||
FixedArray<uint32_t, Vector3iUtil::AXIS_COUNT> neighbor_offset_d_lut;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_X] = block_size.y;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_Y] = 1;
|
||||
neighbor_offset_d_lut[Vector3i::AXIS_Z] = block_size.x * block_size.y;
|
||||
|
@ -428,7 +419,7 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
FixedArray<uint32_t, VoxelMesherCubes::MATERIAL_COUNT> index_offsets(0);
|
||||
|
||||
// For each axis
|
||||
for (unsigned int za = 0; za < Vector3i::AXIS_COUNT; ++za) {
|
||||
for (unsigned int za = 0; za < Vector3iUtil::AXIS_COUNT; ++za) {
|
||||
const unsigned int xa = g_face_axes_lut[za][0];
|
||||
const unsigned int ya = g_face_axes_lut[za][1];
|
||||
|
||||
|
@ -447,13 +438,12 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
// For each cell of the deck, gather face info
|
||||
for (unsigned int fy = min_pos[ya]; fy < (unsigned int)max_pos[ya]; ++fy) {
|
||||
for (unsigned int fx = min_pos[xa]; fx < (unsigned int)max_pos[xa]; ++fx) {
|
||||
FixedArray<unsigned int, Vector3i::AXIS_COUNT> pos;
|
||||
FixedArray<unsigned int, Vector3iUtil::AXIS_COUNT> pos;
|
||||
pos[xa] = fx;
|
||||
pos[ya] = fy;
|
||||
pos[za] = d;
|
||||
|
||||
const unsigned int voxel_index = pos[Vector3i::AXIS_Y] +
|
||||
pos[Vector3i::AXIS_X] * row_size +
|
||||
const unsigned int voxel_index = pos[Vector3i::AXIS_Y] + pos[Vector3i::AXIS_X] * row_size +
|
||||
pos[Vector3i::AXIS_Z] * deck_size;
|
||||
|
||||
const Voxel_T raw_color0 = voxel_buffer[voxel_index];
|
||||
|
@ -468,14 +458,14 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
MaskValue mv;
|
||||
Color8 color;
|
||||
if (ai0 == ai1) {
|
||||
mv.side = SIDE_NONE;
|
||||
mv.side = FACE_SIDE_NONE;
|
||||
} else if (ai0 > ai1) {
|
||||
color = color0;
|
||||
mv.side = SIDE_BACK;
|
||||
mv.side = FACE_SIDE_BACK;
|
||||
mv.material_index = color.a < 0.999f;
|
||||
} else {
|
||||
color = color1;
|
||||
mv.side = SIDE_FRONT;
|
||||
mv.side = FACE_SIDE_FRONT;
|
||||
mv.material_index = color.a < 0.999f;
|
||||
}
|
||||
|
||||
|
@ -504,7 +494,7 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
const unsigned int mask_index = fx + fy * mask_size_x;
|
||||
const MaskValue m = mask[mask_index];
|
||||
|
||||
if (m.side == SIDE_NONE) {
|
||||
if (m.side == FACE_SIDE_NONE) {
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -517,9 +507,7 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
// Check if the next rows of faces are the same along Y
|
||||
unsigned int ry = fy + 1;
|
||||
while (ry < mask_size_y &&
|
||||
L::is_range_equal(mask,
|
||||
fx + ry * mask_size_x,
|
||||
rx + ry * mask_size_x, m)) {
|
||||
L::is_range_equal(mask, fx + ry * mask_size_x, rx + ry * mask_size_x, m)) {
|
||||
++ry;
|
||||
}
|
||||
|
||||
|
@ -549,7 +537,7 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
v3[za] = d;
|
||||
|
||||
Vector3 n;
|
||||
n[za] = m.side == SIDE_FRONT ? -1 : 1;
|
||||
n[za] = m.side == FACE_SIDE_FRONT ? -1 : 1;
|
||||
|
||||
// 2-----3
|
||||
// | |
|
||||
|
@ -590,7 +578,7 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
{
|
||||
unsigned int i = i0;
|
||||
for (unsigned int mx = fx; mx < rx; ++mx) {
|
||||
mask[i].side = SIDE_NONE;
|
||||
mask[i].side = FACE_SIDE_NONE;
|
||||
++i;
|
||||
}
|
||||
}
|
||||
|
@ -620,8 +608,8 @@ void build_voxel_mesh_as_greedy_cubes_atlased(
|
|||
}
|
||||
}
|
||||
|
||||
static Ref<Image> make_greedy_atlas(const VoxelMesherCubes::GreedyAtlasData &atlas_data,
|
||||
Span<VoxelMesherCubes::Arrays> surfaces) {
|
||||
static Ref<Image> make_greedy_atlas(
|
||||
const VoxelMesherCubes::GreedyAtlasData &atlas_data, Span<VoxelMesherCubes::Arrays> surfaces) {
|
||||
//
|
||||
ERR_FAIL_COND_V(atlas_data.images.size() == 0, Ref<Image>());
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
@ -637,7 +625,7 @@ static Ref<Image> make_greedy_atlas(const VoxelMesherCubes::GreedyAtlasData &atl
|
|||
const VoxelMesherCubes::GreedyAtlasData::ImageInfo &im = atlas_data.images[i];
|
||||
sizes.write[i] = Vector2i(im.size_x, im.size_y);
|
||||
}
|
||||
Geometry::make_atlas(sizes, result_points, result_size);
|
||||
Geometry2D::make_atlas(sizes, result_points, result_size);
|
||||
}
|
||||
|
||||
// DEBUG
|
||||
|
@ -675,11 +663,10 @@ static Ref<Image> make_greedy_atlas(const VoxelMesherCubes::GreedyAtlasData &atl
|
|||
}
|
||||
|
||||
// Create image
|
||||
PoolVector<uint8_t> im_data;
|
||||
im_data.resize(result_size.x * result_size.y * 4 * sizeof(uint8_t));
|
||||
PackedByteArray im_data;
|
||||
im_data.resize(result_size.x * result_size.y * sizeof(Color8));
|
||||
{
|
||||
PoolVector<uint8_t>::Write w = im_data.write();
|
||||
Span<Color8> dst_data = Span<Color8>(reinterpret_cast<Color8 *>(w.ptr()), result_size.x * result_size.y);
|
||||
Span<Color8> dst_data = Span<Color8>(reinterpret_cast<Color8 *>(im_data.ptrw()), result_size.x * result_size.y);
|
||||
|
||||
// For all rectangles
|
||||
for (unsigned int i = 0; i < atlas_data.images.size(); ++i) {
|
||||
|
@ -699,7 +686,7 @@ static Ref<Image> make_greedy_atlas(const VoxelMesherCubes::GreedyAtlasData &atl
|
|||
}
|
||||
}
|
||||
Ref<Image> image;
|
||||
image.instance();
|
||||
image.instantiate();
|
||||
image->create(result_size.x, result_size.y, false, Image::FORMAT_RGBA8, im_data);
|
||||
|
||||
return image;
|
||||
|
@ -713,8 +700,7 @@ VoxelMesherCubes::VoxelMesherCubes() {
|
|||
set_padding(PADDING, PADDING);
|
||||
}
|
||||
|
||||
VoxelMesherCubes::~VoxelMesherCubes() {
|
||||
}
|
||||
VoxelMesherCubes::~VoxelMesherCubes() {}
|
||||
|
||||
void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Input &input) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
@ -770,35 +756,22 @@ void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Inp
|
|||
switch (channel_depth) {
|
||||
case VoxelBuffer::DEPTH_8_BIT:
|
||||
if (params.greedy_meshing) {
|
||||
build_voxel_mesh_as_greedy_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel,
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
Color8::from_u8);
|
||||
build_voxel_mesh_as_greedy_cubes(cache.arrays_per_material, raw_channel, block_size,
|
||||
cache.mask_memory_pool, Color8::from_u8);
|
||||
} else {
|
||||
build_voxel_mesh_as_simple_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel,
|
||||
block_size,
|
||||
Color8::from_u8);
|
||||
cache.arrays_per_material, raw_channel, block_size, Color8::from_u8);
|
||||
}
|
||||
break;
|
||||
|
||||
case VoxelBuffer::DEPTH_16_BIT:
|
||||
if (params.greedy_meshing) {
|
||||
build_voxel_mesh_as_greedy_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
build_voxel_mesh_as_greedy_cubes(cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(), block_size, cache.mask_memory_pool,
|
||||
Color8::from_u16);
|
||||
} else {
|
||||
build_voxel_mesh_as_simple_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size,
|
||||
Color8::from_u16);
|
||||
build_voxel_mesh_as_simple_cubes(cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(), block_size, Color8::from_u16);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -826,46 +799,28 @@ void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Inp
|
|||
case VoxelBuffer::DEPTH_8_BIT:
|
||||
if (params.greedy_meshing) {
|
||||
if (params.store_colors_in_texture) {
|
||||
build_voxel_mesh_as_greedy_cubes_atlased(
|
||||
cache.arrays_per_material,
|
||||
cache.greedy_atlas_data,
|
||||
raw_channel,
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
get_color_from_palette);
|
||||
atlas_image = make_greedy_atlas(
|
||||
cache.greedy_atlas_data, to_span(cache.arrays_per_material));
|
||||
build_voxel_mesh_as_greedy_cubes_atlased(cache.arrays_per_material, cache.greedy_atlas_data,
|
||||
raw_channel, block_size, cache.mask_memory_pool, get_color_from_palette);
|
||||
atlas_image =
|
||||
make_greedy_atlas(cache.greedy_atlas_data, to_span(cache.arrays_per_material));
|
||||
} else {
|
||||
build_voxel_mesh_as_greedy_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel,
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
get_color_from_palette);
|
||||
build_voxel_mesh_as_greedy_cubes(cache.arrays_per_material, raw_channel, block_size,
|
||||
cache.mask_memory_pool, get_color_from_palette);
|
||||
}
|
||||
} else {
|
||||
build_voxel_mesh_as_simple_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel,
|
||||
block_size,
|
||||
get_color_from_palette);
|
||||
cache.arrays_per_material, raw_channel, block_size, get_color_from_palette);
|
||||
}
|
||||
break;
|
||||
|
||||
case VoxelBuffer::DEPTH_16_BIT:
|
||||
if (params.greedy_meshing) {
|
||||
build_voxel_mesh_as_greedy_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
build_voxel_mesh_as_greedy_cubes(cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(), block_size, cache.mask_memory_pool,
|
||||
get_color_from_palette);
|
||||
} else {
|
||||
build_voxel_mesh_as_simple_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size,
|
||||
get_color_from_palette);
|
||||
build_voxel_mesh_as_simple_cubes(cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(), block_size, get_color_from_palette);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -890,35 +845,22 @@ void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Inp
|
|||
switch (channel_depth) {
|
||||
case VoxelBuffer::DEPTH_8_BIT:
|
||||
if (params.greedy_meshing) {
|
||||
build_voxel_mesh_as_greedy_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel,
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
get_index_from_palette);
|
||||
build_voxel_mesh_as_greedy_cubes(cache.arrays_per_material, raw_channel, block_size,
|
||||
cache.mask_memory_pool, get_index_from_palette);
|
||||
} else {
|
||||
build_voxel_mesh_as_simple_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel,
|
||||
block_size,
|
||||
get_index_from_palette);
|
||||
cache.arrays_per_material, raw_channel, block_size, get_index_from_palette);
|
||||
}
|
||||
break;
|
||||
|
||||
case VoxelBuffer::DEPTH_16_BIT:
|
||||
if (params.greedy_meshing) {
|
||||
build_voxel_mesh_as_greedy_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size,
|
||||
cache.mask_memory_pool,
|
||||
build_voxel_mesh_as_greedy_cubes(cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(), block_size, cache.mask_memory_pool,
|
||||
get_index_from_palette);
|
||||
} else {
|
||||
build_voxel_mesh_as_simple_cubes(
|
||||
cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(),
|
||||
block_size,
|
||||
get_index_from_palette);
|
||||
build_voxel_mesh_as_simple_cubes(cache.arrays_per_material,
|
||||
raw_channel.reinterpret_cast_to<uint16_t>(), block_size, get_index_from_palette);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -955,9 +897,9 @@ void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Inp
|
|||
mesh_arrays.resize(Mesh::ARRAY_MAX);
|
||||
|
||||
{
|
||||
PoolVector<Vector3> positions;
|
||||
PoolVector<Vector3> normals;
|
||||
PoolVector<int> indices;
|
||||
PackedVector3Array positions;
|
||||
PackedVector3Array normals;
|
||||
PackedInt32Array indices;
|
||||
|
||||
raw_copy_to(positions, arrays.positions);
|
||||
raw_copy_to(normals, arrays.normals);
|
||||
|
@ -968,12 +910,12 @@ void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Inp
|
|||
mesh_arrays[Mesh::ARRAY_INDEX] = indices;
|
||||
|
||||
if (arrays.colors.size() > 0) {
|
||||
PoolVector<Color> colors;
|
||||
PackedColorArray colors;
|
||||
raw_copy_to(colors, arrays.colors);
|
||||
mesh_arrays[Mesh::ARRAY_COLOR] = colors;
|
||||
}
|
||||
if (arrays.uvs.size() > 0) {
|
||||
PoolVector<Vector2> uvs;
|
||||
PackedVector2Array uvs;
|
||||
raw_copy_to(uvs, arrays.uvs);
|
||||
mesh_arrays[Mesh::ARRAY_TEX_UV] = uvs;
|
||||
}
|
||||
|
@ -990,10 +932,10 @@ void VoxelMesherCubes::build(VoxelMesher::Output &output, const VoxelMesher::Inp
|
|||
output.primitive_type = Mesh::PRIMITIVE_TRIANGLES;
|
||||
output.atlas_image = atlas_image;
|
||||
|
||||
if (params.store_colors_in_texture) {
|
||||
// Don't compress UVs, they need to be precise. Not doing this causes noticeable offsets.
|
||||
output.compression_flags = Mesh::ARRAY_COMPRESS_DEFAULT & ~Mesh::ARRAY_COMPRESS_TEX_UV;
|
||||
}
|
||||
// if (params.store_colors_in_texture) {
|
||||
// // Don't compress UVs, they need to be precise. Not doing this causes noticeable offsets.
|
||||
// output.compression_flags = Mesh::ARRAY_COMPRESS_FLAGS_BASE & ~Mesh::ARRAY_FORMAT_TEX_UV;
|
||||
// }
|
||||
//output.compression_flags = Mesh::ARRAY_COMPRESS_COLOR;
|
||||
}
|
||||
|
||||
|
@ -1059,8 +1001,8 @@ int VoxelMesherCubes::get_used_channels_mask() const {
|
|||
}
|
||||
|
||||
void VoxelMesherCubes::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("set_greedy_meshing_enabled", "enable"),
|
||||
&VoxelMesherCubes::set_greedy_meshing_enabled);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_greedy_meshing_enabled", "enable"), &VoxelMesherCubes::set_greedy_meshing_enabled);
|
||||
ClassDB::bind_method(D_METHOD("is_greedy_meshing_enabled"), &VoxelMesherCubes::is_greedy_meshing_enabled);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_palette", "palette"), &VoxelMesherCubes::set_palette);
|
||||
|
@ -1069,8 +1011,8 @@ void VoxelMesherCubes::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_color_mode", "mode"), &VoxelMesherCubes::set_color_mode);
|
||||
ClassDB::bind_method(D_METHOD("get_color_mode"), &VoxelMesherCubes::get_color_mode);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "greedy_meshing_enabled"),
|
||||
"set_greedy_meshing_enabled", "is_greedy_meshing_enabled");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "greedy_meshing_enabled"), "set_greedy_meshing_enabled",
|
||||
"is_greedy_meshing_enabled");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "color_mode"), "set_color_mode", "get_color_mode");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::OBJECT, "palette", PROPERTY_HINT_RESOURCE_TYPE, "VoxelColorPalette"),
|
||||
"set_palette", "get_palette");
|
||||
|
|
|
@ -7,6 +7,8 @@ namespace MarchingCubes {
|
|||
// in http://paulbourke.net/geometry/polygonise/marchingsource.cpp
|
||||
// Thanks!
|
||||
|
||||
// clang-format off
|
||||
|
||||
// Edges table
|
||||
int mc_edges[256] = {
|
||||
0x000, 0x109, 0x203, 0x30a, 0x406, 0x50f, 0x605, 0x70c, 0x80c, 0x905, 0xa0f, 0xb06, 0xc0a, 0xd03, 0xe09, 0xf00,
|
||||
|
@ -345,6 +347,8 @@ int ms_triangles[18][13] = {
|
|||
{ 1, 3, 2, 1, 5, 3, 1, 6, 5, 1, 7, 6, -1 } // 1 3 alternative
|
||||
};
|
||||
|
||||
// clang-format on
|
||||
|
||||
} // namespace MarchingCubes
|
||||
|
||||
#endif // MARCHING_CUBES_TABLES_H
|
||||
|
|
|
@ -5,7 +5,6 @@
|
|||
namespace dmc {
|
||||
|
||||
Array MeshBuilder::commit(bool wireframe) {
|
||||
|
||||
if (_positions.size() == 0) {
|
||||
return Array();
|
||||
}
|
||||
|
@ -13,12 +12,10 @@ Array MeshBuilder::commit(bool wireframe) {
|
|||
ERR_FAIL_COND_V(_indices.size() % 3 != 0, Array());
|
||||
|
||||
if (wireframe) {
|
||||
|
||||
// Debug purpose, no effort to be fast here
|
||||
std::vector<int> wireframe_indices;
|
||||
|
||||
for (unsigned int i = 0; i < _indices.size(); i += 3) {
|
||||
|
||||
wireframe_indices.push_back(_indices[i]);
|
||||
wireframe_indices.push_back(_indices[i + 1]);
|
||||
|
||||
|
@ -32,9 +29,9 @@ Array MeshBuilder::commit(bool wireframe) {
|
|||
_indices = wireframe_indices;
|
||||
}
|
||||
|
||||
PoolVector3Array positions;
|
||||
PoolVector3Array normals;
|
||||
PoolIntArray indices;
|
||||
PackedVector3Array positions;
|
||||
PackedVector3Array normals;
|
||||
PackedInt32Array indices;
|
||||
|
||||
raw_copy_to(positions, _positions);
|
||||
raw_copy_to(normals, _normals);
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#ifndef MESH_BUILDER_H
|
||||
#define MESH_BUILDER_H
|
||||
|
||||
#include <core/map.h>
|
||||
#include <core/math/vector3.h>
|
||||
#include <core/templates/map.h>
|
||||
#include <vector>
|
||||
|
||||
namespace dmc {
|
||||
|
@ -14,18 +14,15 @@ public:
|
|||
_reused_vertices(0) {}
|
||||
|
||||
inline void add_vertex(Vector3 position, Vector3 normal) {
|
||||
|
||||
int i = 0;
|
||||
|
||||
Map<Vector3, int>::Element *e = _position_to_index.find(position);
|
||||
|
||||
if (e) {
|
||||
|
||||
i = e->get();
|
||||
++_reused_vertices;
|
||||
|
||||
} else {
|
||||
|
||||
i = _positions.size();
|
||||
_position_to_index.insert(position, i);
|
||||
|
||||
|
|
|
@ -22,9 +22,7 @@ struct VoxelAccess {
|
|||
const VoxelBufferInternal &buffer;
|
||||
const Vector3i offset;
|
||||
|
||||
VoxelAccess(const VoxelBufferInternal &p_buffer, Vector3i p_offset) :
|
||||
buffer(p_buffer),
|
||||
offset(p_offset) {}
|
||||
VoxelAccess(const VoxelBufferInternal &p_buffer, Vector3i p_offset) : buffer(p_buffer), offset(p_offset) {}
|
||||
|
||||
inline HermiteValue get_hermite_value(int x, int y, int z) const {
|
||||
return dmc::get_hermite_value(buffer, x + offset.x, y + offset.y, z + offset.z);
|
||||
|
@ -49,7 +47,7 @@ bool can_split(Vector3i node_origin, int node_size, const VoxelAccess &voxels, f
|
|||
int channel = VoxelBufferInternal::CHANNEL_SDF;
|
||||
|
||||
// Don't split if nothing is inside, i.e isolevel distance is greater than the size of the cube we are in
|
||||
Vector3i center_pos = node_origin + Vector3i(node_size / 2);
|
||||
Vector3i center_pos = node_origin + Vector3iUtil::create(node_size / 2);
|
||||
HermiteValue center_value = voxels.get_hermite_value(center_pos.x, center_pos.y, center_pos.z);
|
||||
if (Math::abs(center_value.sdf) > SQRT3 * (float)node_size) {
|
||||
return false;
|
||||
|
@ -95,30 +93,28 @@ bool can_split(Vector3i node_origin, int node_size, const VoxelAccess &voxels, f
|
|||
Vector3i(origin.x + hstep, /**/ origin.y + hstep, /**/ origin.z + hstep) // 26
|
||||
};
|
||||
|
||||
Vector3 positions_ratio[19] = {
|
||||
Vector3(0.5, 0.0, 0.0),
|
||||
Vector3(1.0, 0.0, 0.5),
|
||||
Vector3(0.5, 0.0, 1.0),
|
||||
Vector3(0.0, 0.0, 0.5),
|
||||
Vector3 positions_ratio[19] = { Vector3(0.5, 0.0, 0.0), //
|
||||
Vector3(1.0, 0.0, 0.5), //
|
||||
Vector3(0.5, 0.0, 1.0), //
|
||||
Vector3(0.0, 0.0, 0.5), //
|
||||
|
||||
Vector3(0.0, 0.5, 0.0),
|
||||
Vector3(1.0, 0.5, 0.0),
|
||||
Vector3(1.0, 0.5, 1.0),
|
||||
Vector3(0.0, 0.5, 1.0),
|
||||
Vector3(0.0, 0.5, 0.0), //
|
||||
Vector3(1.0, 0.5, 0.0), //
|
||||
Vector3(1.0, 0.5, 1.0), //
|
||||
Vector3(0.0, 0.5, 1.0), //
|
||||
|
||||
Vector3(0.5, 1.0, 0.0),
|
||||
Vector3(1.0, 1.0, 0.5),
|
||||
Vector3(0.5, 1.0, 1.0),
|
||||
Vector3(0.0, 1.0, 0.5),
|
||||
Vector3(0.5, 1.0, 0.0), //
|
||||
Vector3(1.0, 1.0, 0.5), //
|
||||
Vector3(0.5, 1.0, 1.0), //
|
||||
Vector3(0.0, 1.0, 0.5), //
|
||||
|
||||
Vector3(0.5, 0.0, 0.5),
|
||||
Vector3(0.5, 0.5, 0.0),
|
||||
Vector3(1.0, 0.5, 0.5),
|
||||
Vector3(0.5, 0.5, 1.0),
|
||||
Vector3(0.0, 0.5, 0.5),
|
||||
Vector3(0.5, 1.0, 0.5),
|
||||
Vector3(0.5, 0.5, 0.5)
|
||||
};
|
||||
Vector3(0.5, 0.0, 0.5), //
|
||||
Vector3(0.5, 0.5, 0.0), //
|
||||
Vector3(1.0, 0.5, 0.5), //
|
||||
Vector3(0.5, 0.5, 1.0), //
|
||||
Vector3(0.0, 0.5, 0.5), //
|
||||
Vector3(0.5, 1.0, 0.5), //
|
||||
Vector3(0.5, 0.5, 0.5) };
|
||||
|
||||
float error = 0.0;
|
||||
|
||||
|
@ -143,16 +139,13 @@ bool can_split(Vector3i node_origin, int node_size, const VoxelAccess &voxels, f
|
|||
}
|
||||
|
||||
inline Vector3 get_center(const OctreeNode *node) {
|
||||
return node->origin.to_vec3() + 0.5 * Vector3(node->size, node->size, node->size);
|
||||
return Vector3(node->origin) + 0.5 * Vector3(node->size, node->size, node->size);
|
||||
}
|
||||
|
||||
class OctreeBuilderTopDown {
|
||||
public:
|
||||
OctreeBuilderTopDown(const VoxelAccess &voxels, float geometry_error, OctreeNodePool &pool) :
|
||||
_voxels(voxels),
|
||||
_geometry_error(geometry_error),
|
||||
_pool(pool) {
|
||||
}
|
||||
_voxels(voxels), _geometry_error(geometry_error), _pool(pool) {}
|
||||
|
||||
OctreeNode *build(Vector3i origin, int size) {
|
||||
OctreeNode *root = _pool.create();
|
||||
|
@ -198,10 +191,7 @@ private:
|
|||
class OctreeBuilderBottomUp {
|
||||
public:
|
||||
OctreeBuilderBottomUp(const VoxelAccess &voxels, float geometry_error, OctreeNodePool &pool) :
|
||||
_voxels(voxels),
|
||||
_geometry_error(geometry_error),
|
||||
_pool(pool) {
|
||||
}
|
||||
_voxels(voxels), _geometry_error(geometry_error), _pool(pool) {}
|
||||
|
||||
OctreeNode *build(Vector3i node_origin, int node_size) const {
|
||||
OctreeNode *children[8] = { nullptr };
|
||||
|
@ -271,8 +261,7 @@ private:
|
|||
OctreeNodePool &_pool;
|
||||
};
|
||||
|
||||
template <typename Action_T>
|
||||
void foreach_node(OctreeNode *root, Action_T &a, int depth = 0) {
|
||||
template <typename Action_T> void foreach_node(OctreeNode *root, Action_T &a, int depth = 0) {
|
||||
a(root, depth);
|
||||
for (int i = 0; i < 8; ++i) {
|
||||
if (root->children[i]) {
|
||||
|
@ -281,11 +270,10 @@ void foreach_node(OctreeNode *root, Action_T &a, int depth = 0) {
|
|||
}
|
||||
}
|
||||
|
||||
inline void scale_positions(PoolVector3Array &positions, float scale) {
|
||||
PoolVector3Array::Write w = positions.write();
|
||||
inline void scale_positions(PackedVector3Array &positions, float scale) {
|
||||
const uint32_t size = positions.size();
|
||||
for (unsigned int i = 0; i < size; ++i) {
|
||||
w[i] *= scale;
|
||||
positions.write[i] *= scale;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -300,9 +288,9 @@ Array generate_debug_octree_mesh(OctreeNode *root, int scale) {
|
|||
};
|
||||
|
||||
struct Arrays {
|
||||
PoolVector3Array positions;
|
||||
PoolColorArray colors;
|
||||
PoolIntArray indices;
|
||||
PackedVector3Array positions;
|
||||
PackedColorArray colors;
|
||||
PackedInt32Array indices;
|
||||
};
|
||||
|
||||
struct AddCube {
|
||||
|
@ -311,7 +299,7 @@ Array generate_debug_octree_mesh(OctreeNode *root, int scale) {
|
|||
|
||||
void operator()(OctreeNode *node, int depth) {
|
||||
float shrink = depth * 0.005;
|
||||
Vector3 o = node->origin.to_vec3() + Vector3(shrink, shrink, shrink);
|
||||
Vector3 o = Vector3(node->origin) + Vector3(shrink, shrink, shrink);
|
||||
float s = node->size - 2.0 * shrink;
|
||||
|
||||
Color col(1.0, (float)depth / (float)max_depth, 0.0);
|
||||
|
@ -357,8 +345,8 @@ Array generate_debug_octree_mesh(OctreeNode *root, int scale) {
|
|||
}
|
||||
|
||||
Array generate_debug_dual_grid_mesh(const DualGrid &grid, int scale) {
|
||||
PoolVector3Array positions;
|
||||
PoolIntArray indices;
|
||||
PackedVector3Array positions;
|
||||
PackedInt32Array indices;
|
||||
|
||||
for (unsigned int i = 0; i < grid.cells.size(); ++i) {
|
||||
const DualCell &cell = grid.cells[i];
|
||||
|
@ -418,14 +406,14 @@ inline bool is_border_front(const OctreeNode *node, int root_size) {
|
|||
}
|
||||
|
||||
inline Vector3 get_center_back(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.y += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_front(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.y += node->size * 0.5;
|
||||
p.z += node->size;
|
||||
|
@ -433,14 +421,14 @@ inline Vector3 get_center_front(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_center_left(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.y += node->size * 0.5;
|
||||
p.z += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_right(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.y += node->size * 0.5;
|
||||
p.z += node->size * 0.5;
|
||||
|
@ -448,7 +436,7 @@ inline Vector3 get_center_right(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_center_top(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.y += node->size;
|
||||
p.z += node->size * 0.5;
|
||||
|
@ -456,27 +444,27 @@ inline Vector3 get_center_top(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_center_bottom(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.z += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_back_top(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.y += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_back_bottom(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_front_top(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.y += node->size;
|
||||
p.z += node->size;
|
||||
|
@ -484,27 +472,27 @@ inline Vector3 get_center_front_top(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_center_front_bottom(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size * 0.5;
|
||||
p.z += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_left_top(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.y += node->size;
|
||||
p.z += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_left_bottom(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.z += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_right_top(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.y += node->size;
|
||||
p.z += node->size * 0.5;
|
||||
|
@ -512,34 +500,34 @@ inline Vector3 get_center_right_top(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_center_right_bottom(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.z += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_back_left(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.y += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_front_left(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.y += node->size * 0.5;
|
||||
p.z += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_back_right(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.y += node->size * 0.5;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_center_front_right(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.y += node->size * 0.5;
|
||||
p.z += node->size;
|
||||
|
@ -547,39 +535,39 @@ inline Vector3 get_center_front_right(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_corner1(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_corner2(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.z += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_corner3(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.z += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_corner4(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.y += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_corner5(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.y += node->size;
|
||||
return p;
|
||||
}
|
||||
|
||||
inline Vector3 get_corner6(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.x += node->size;
|
||||
p.y += node->size;
|
||||
p.z += node->size;
|
||||
|
@ -587,7 +575,7 @@ inline Vector3 get_corner6(const OctreeNode *node) {
|
|||
}
|
||||
|
||||
inline Vector3 get_corner7(const OctreeNode *node) {
|
||||
Vector3 p = node->origin.to_vec3();
|
||||
Vector3 p = node->origin;
|
||||
p.y += node->size;
|
||||
p.z += node->size;
|
||||
return p;
|
||||
|
@ -595,9 +583,7 @@ inline Vector3 get_corner7(const OctreeNode *node) {
|
|||
|
||||
class DualGridGenerator {
|
||||
public:
|
||||
DualGridGenerator(DualGrid &grid, int octree_root_size) :
|
||||
_grid(grid),
|
||||
_octree_root_size(octree_root_size) {}
|
||||
DualGridGenerator(DualGrid &grid, int octree_root_size) : _grid(grid), _octree_root_size(octree_root_size) {}
|
||||
|
||||
void node_proc(OctreeNode *node);
|
||||
|
||||
|
@ -605,17 +591,11 @@ private:
|
|||
DualGrid &_grid;
|
||||
int _octree_root_size;
|
||||
|
||||
void create_border_cells(
|
||||
const OctreeNode *n0,
|
||||
const OctreeNode *n1,
|
||||
const OctreeNode *n2,
|
||||
const OctreeNode *n3,
|
||||
const OctreeNode *n4,
|
||||
const OctreeNode *n5,
|
||||
const OctreeNode *n6,
|
||||
const OctreeNode *n7);
|
||||
void create_border_cells(const OctreeNode *n0, const OctreeNode *n1, const OctreeNode *n2, const OctreeNode *n3,
|
||||
const OctreeNode *n4, const OctreeNode *n5, const OctreeNode *n6, const OctreeNode *n7);
|
||||
|
||||
void vert_proc(OctreeNode *n0, OctreeNode *n1, OctreeNode *n2, OctreeNode *n3, OctreeNode *n4, OctreeNode *n5, OctreeNode *n6, OctreeNode *n7);
|
||||
void vert_proc(OctreeNode *n0, OctreeNode *n1, OctreeNode *n2, OctreeNode *n3, OctreeNode *n4, OctreeNode *n5,
|
||||
OctreeNode *n6, OctreeNode *n7);
|
||||
|
||||
void edge_proc_x(OctreeNode *n0, OctreeNode *n1, OctreeNode *n2, OctreeNode *n3);
|
||||
void edge_proc_y(OctreeNode *n0, OctreeNode *n1, OctreeNode *n2, OctreeNode *n3);
|
||||
|
@ -626,15 +606,8 @@ private:
|
|||
void face_proc_xz(OctreeNode *n0, OctreeNode *n1);
|
||||
};
|
||||
|
||||
inline void add_cell(DualGrid &grid,
|
||||
const Vector3 c0,
|
||||
const Vector3 c1,
|
||||
const Vector3 c2,
|
||||
const Vector3 c3,
|
||||
const Vector3 c4,
|
||||
const Vector3 c5,
|
||||
const Vector3 c6,
|
||||
const Vector3 c7) {
|
||||
inline void add_cell(DualGrid &grid, const Vector3 c0, const Vector3 c1, const Vector3 c2, const Vector3 c3,
|
||||
const Vector3 c4, const Vector3 c5, const Vector3 c6, const Vector3 c7) {
|
||||
DualCell cell;
|
||||
cell.corners[0] = c0;
|
||||
cell.corners[1] = c1;
|
||||
|
@ -648,185 +621,155 @@ inline void add_cell(DualGrid &grid,
|
|||
grid.cells.push_back(cell);
|
||||
}
|
||||
|
||||
void DualGridGenerator::create_border_cells(
|
||||
const OctreeNode *n0,
|
||||
const OctreeNode *n1,
|
||||
const OctreeNode *n2,
|
||||
const OctreeNode *n3,
|
||||
const OctreeNode *n4,
|
||||
const OctreeNode *n5,
|
||||
const OctreeNode *n6,
|
||||
const OctreeNode *n7) {
|
||||
void DualGridGenerator::create_border_cells(const OctreeNode *n0, const OctreeNode *n1, const OctreeNode *n2,
|
||||
const OctreeNode *n3, const OctreeNode *n4, const OctreeNode *n5, const OctreeNode *n6, const OctreeNode *n7) {
|
||||
DualGrid &grid = _grid;
|
||||
|
||||
// Most boring function ever
|
||||
|
||||
if (is_border_back(n0) && is_border_back(n1) && is_border_back(n4) && is_border_back(n5)) {
|
||||
add_cell(grid,
|
||||
get_center_back(n0), get_center_back(n1), get_center(n1), get_center(n0),
|
||||
get_center_back(n4), get_center_back(n5), get_center(n5), get_center(n4));
|
||||
add_cell(grid, get_center_back(n0), get_center_back(n1), get_center(n1), get_center(n0), get_center_back(n4),
|
||||
get_center_back(n5), get_center(n5), get_center(n4));
|
||||
|
||||
// Generate back edge border cells
|
||||
if (is_border_top(n4, _octree_root_size) && is_border_top(n5, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center_back(n4), get_center_back(n5), get_center(n5), get_center(n4),
|
||||
add_cell(grid, get_center_back(n4), get_center_back(n5), get_center(n5), get_center(n4),
|
||||
get_center_back_top(n4), get_center_back_top(n5), get_center_top(n5), get_center_top(n4));
|
||||
|
||||
// Generate back top corner cells
|
||||
if (is_border_left(n4)) {
|
||||
add_cell(grid,
|
||||
get_center_back_left(n4), get_center_back(n4), get_center(n4), get_center_left(n4),
|
||||
add_cell(grid, get_center_back_left(n4), get_center_back(n4), get_center(n4), get_center_left(n4),
|
||||
get_corner4(n4), get_center_back_top(n4), get_center_top(n4), get_center_left_top(n4));
|
||||
}
|
||||
|
||||
if (is_border_right(n4, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center_back(n5), get_center_back_right(n5), get_center_right(n5), get_center(n5),
|
||||
add_cell(grid, get_center_back(n5), get_center_back_right(n5), get_center_right(n5), get_center(n5),
|
||||
get_center_back_top(n5), get_corner5(n5), get_center_right_top(n5), get_center_top(n5));
|
||||
}
|
||||
}
|
||||
|
||||
if (is_border_bottom(n0) && is_border_bottom(n1)) {
|
||||
add_cell(grid,
|
||||
get_center_back_bottom(n0), get_center_back_bottom(n1), get_center_bottom(n1), get_center_bottom(n0),
|
||||
get_center_back(n0), get_center_back(n1), get_center(n1), get_center(n0));
|
||||
add_cell(grid, get_center_back_bottom(n0), get_center_back_bottom(n1), get_center_bottom(n1),
|
||||
get_center_bottom(n0), get_center_back(n0), get_center_back(n1), get_center(n1), get_center(n0));
|
||||
|
||||
// Generate back bottom corner cells
|
||||
if (is_border_left(n0)) {
|
||||
add_cell(grid, n0->origin.to_vec3(), get_center_back_bottom(n0), get_center_bottom(n0), get_center_left_bottom(n0),
|
||||
get_center_back_left(n0), get_center_back(n0), get_center(n0), get_center_left(n0));
|
||||
add_cell(grid, n0->origin, get_center_back_bottom(n0), get_center_bottom(n0),
|
||||
get_center_left_bottom(n0), get_center_back_left(n0), get_center_back(n0), get_center(n0),
|
||||
get_center_left(n0));
|
||||
}
|
||||
|
||||
if (is_border_right(n1, _octree_root_size)) {
|
||||
add_cell(grid, get_center_back_bottom(n1), get_corner1(n1), get_center_right_bottom(n1), get_center_bottom(n1),
|
||||
get_center_back(n1), get_center_back_right(n1), get_center_right(n1), get_center(n1));
|
||||
add_cell(grid, get_center_back_bottom(n1), get_corner1(n1), get_center_right_bottom(n1),
|
||||
get_center_bottom(n1), get_center_back(n1), get_center_back_right(n1), get_center_right(n1),
|
||||
get_center(n1));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (is_border_front(n2, _octree_root_size) &&
|
||||
is_border_front(n3, _octree_root_size) &&
|
||||
is_border_front(n6, _octree_root_size) &&
|
||||
is_border_front(n7, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n3), get_center(n2), get_center_front(n2), get_center_front(n3),
|
||||
get_center(n7), get_center(n6), get_center_front(n6), get_center_front(n7));
|
||||
if (is_border_front(n2, _octree_root_size) && is_border_front(n3, _octree_root_size) &&
|
||||
is_border_front(n6, _octree_root_size) && is_border_front(n7, _octree_root_size)) {
|
||||
add_cell(grid, get_center(n3), get_center(n2), get_center_front(n2), get_center_front(n3), get_center(n7),
|
||||
get_center(n6), get_center_front(n6), get_center_front(n7));
|
||||
|
||||
// Generate front edge border cells
|
||||
if (is_border_top(n6, _octree_root_size) && is_border_top(n7, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n7), get_center(n6), get_center_front(n6), get_center_front(n7),
|
||||
add_cell(grid, get_center(n7), get_center(n6), get_center_front(n6), get_center_front(n7),
|
||||
get_center_top(n7), get_center_top(n6), get_center_front_top(n6), get_center_front_top(n7));
|
||||
|
||||
// Generate back bottom corner cells
|
||||
if (is_border_left(n7)) {
|
||||
add_cell(grid,
|
||||
get_center_left(n7), get_center(n7), get_center_front(n7), get_center_front_left(n7),
|
||||
add_cell(grid, get_center_left(n7), get_center(n7), get_center_front(n7), get_center_front_left(n7),
|
||||
get_center_left_top(n7), get_center_top(n7), get_center_front_top(n7), get_corner7(n7));
|
||||
}
|
||||
|
||||
if (is_border_right(n6, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n6), get_center_right(n6), get_center_front_right(n6), get_center_front(n6),
|
||||
add_cell(grid, get_center(n6), get_center_right(n6), get_center_front_right(n6), get_center_front(n6),
|
||||
get_center_top(n6), get_center_right_top(n6), get_corner6(n6), get_center_front_top(n6));
|
||||
}
|
||||
}
|
||||
|
||||
if (is_border_bottom(n3) && is_border_bottom(n2)) {
|
||||
add_cell(grid,
|
||||
get_center_bottom(n3), get_center_bottom(n2), get_center_front_bottom(n2), get_center_front_bottom(n3),
|
||||
get_center(n3), get_center(n2), get_center_front(n2), get_center_front(n3));
|
||||
add_cell(grid, get_center_bottom(n3), get_center_bottom(n2), get_center_front_bottom(n2),
|
||||
get_center_front_bottom(n3), get_center(n3), get_center(n2), get_center_front(n2),
|
||||
get_center_front(n3));
|
||||
|
||||
// Generate back bottom corner cells
|
||||
if (is_border_left(n3)) {
|
||||
add_cell(grid,
|
||||
get_center_left_bottom(n3), get_center_bottom(n3), get_center_front_bottom(n3), get_corner3(n3),
|
||||
get_center_left(n3), get_center(n3), get_center_front(n3), get_center_front_left(n3));
|
||||
add_cell(grid, get_center_left_bottom(n3), get_center_bottom(n3), get_center_front_bottom(n3),
|
||||
get_corner3(n3), get_center_left(n3), get_center(n3), get_center_front(n3),
|
||||
get_center_front_left(n3));
|
||||
}
|
||||
if (is_border_right(n2, _octree_root_size)) {
|
||||
add_cell(grid, get_center_bottom(n2), get_center_right_bottom(n2), get_corner2(n2), get_center_front_bottom(n2),
|
||||
get_center(n2), get_center_right(n2), get_center_front_right(n2), get_center_front(n2));
|
||||
add_cell(grid, get_center_bottom(n2), get_center_right_bottom(n2), get_corner2(n2),
|
||||
get_center_front_bottom(n2), get_center(n2), get_center_right(n2), get_center_front_right(n2),
|
||||
get_center_front(n2));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (is_border_left(n0) && is_border_left(n3) && is_border_left(n4) && is_border_left(n7)) {
|
||||
add_cell(grid,
|
||||
get_center_left(n0), get_center(n0), get_center(n3), get_center_left(n3),
|
||||
get_center_left(n4), get_center(n4), get_center(n7), get_center_left(n7));
|
||||
add_cell(grid, get_center_left(n0), get_center(n0), get_center(n3), get_center_left(n3), get_center_left(n4),
|
||||
get_center(n4), get_center(n7), get_center_left(n7));
|
||||
|
||||
// Generate left edge border cells
|
||||
if (is_border_top(n4, _octree_root_size) && is_border_top(n7, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center_left(n4), get_center(n4), get_center(n7), get_center_left(n7),
|
||||
add_cell(grid, get_center_left(n4), get_center(n4), get_center(n7), get_center_left(n7),
|
||||
get_center_left_top(n4), get_center_top(n4), get_center_top(n7), get_center_left_top(n7));
|
||||
}
|
||||
|
||||
if (is_border_bottom(n0) && is_border_bottom(n3)) {
|
||||
add_cell(grid,
|
||||
get_center_left_bottom(n0), get_center_bottom(n0), get_center_bottom(n3), get_center_left_bottom(n3),
|
||||
get_center_left(n0), get_center(n0), get_center(n3), get_center_left(n3));
|
||||
add_cell(grid, get_center_left_bottom(n0), get_center_bottom(n0), get_center_bottom(n3),
|
||||
get_center_left_bottom(n3), get_center_left(n0), get_center(n0), get_center(n3),
|
||||
get_center_left(n3));
|
||||
}
|
||||
|
||||
if (is_border_back(n0) && is_border_back(n4)) {
|
||||
add_cell(grid,
|
||||
get_center_back_left(n0), get_center_back(n0), get_center(n0), get_center_left(n0),
|
||||
add_cell(grid, get_center_back_left(n0), get_center_back(n0), get_center(n0), get_center_left(n0),
|
||||
get_center_back_left(n4), get_center_back(n4), get_center(n4), get_center_left(n4));
|
||||
}
|
||||
|
||||
if (is_border_front(n3, _octree_root_size) && is_border_front(n7, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center_left(n3), get_center(n3), get_center_front(n3), get_center_front_left(n3),
|
||||
add_cell(grid, get_center_left(n3), get_center(n3), get_center_front(n3), get_center_front_left(n3),
|
||||
get_center_left(n7), get_center(n7), get_center_front(n7), get_center_front_left(n7));
|
||||
}
|
||||
}
|
||||
|
||||
if (is_border_right(n1, _octree_root_size) &&
|
||||
is_border_right(n2, _octree_root_size) &&
|
||||
is_border_right(n5, _octree_root_size) &&
|
||||
is_border_right(n6, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n1), get_center_right(n1), get_center_right(n2), get_center(n2),
|
||||
get_center(n5), get_center_right(n5), get_center_right(n6), get_center(n6));
|
||||
if (is_border_right(n1, _octree_root_size) && is_border_right(n2, _octree_root_size) &&
|
||||
is_border_right(n5, _octree_root_size) && is_border_right(n6, _octree_root_size)) {
|
||||
add_cell(grid, get_center(n1), get_center_right(n1), get_center_right(n2), get_center(n2), get_center(n5),
|
||||
get_center_right(n5), get_center_right(n6), get_center(n6));
|
||||
|
||||
// Generate right edge border cells
|
||||
if (is_border_top(n5, _octree_root_size) && is_border_top(n6, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n5), get_center_right(n5), get_center_right(n6), get_center(n6),
|
||||
add_cell(grid, get_center(n5), get_center_right(n5), get_center_right(n6), get_center(n6),
|
||||
get_center_top(n5), get_center_right_top(n5), get_center_right_top(n6), get_center_top(n6));
|
||||
}
|
||||
|
||||
if (is_border_bottom(n1) && is_border_bottom(n2)) {
|
||||
add_cell(grid,
|
||||
get_center_bottom(n1), get_center_right_bottom(n1), get_center_right_bottom(n2), get_center_bottom(n2),
|
||||
get_center(n1), get_center_right(n1), get_center_right(n2), get_center(n2));
|
||||
add_cell(grid, get_center_bottom(n1), get_center_right_bottom(n1), get_center_right_bottom(n2),
|
||||
get_center_bottom(n2), get_center(n1), get_center_right(n1), get_center_right(n2), get_center(n2));
|
||||
}
|
||||
|
||||
if (is_border_back(n1) && is_border_back(n5)) {
|
||||
add_cell(grid,
|
||||
get_center_back(n1), get_center_back_right(n1), get_center_right(n1), get_center(n1),
|
||||
add_cell(grid, get_center_back(n1), get_center_back_right(n1), get_center_right(n1), get_center(n1),
|
||||
get_center_back(n5), get_center_back_right(n5), get_center_right(n5), get_center(n5));
|
||||
}
|
||||
|
||||
if (is_border_front(n2, _octree_root_size) && is_border_front(n6, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n2), get_center_right(n2), get_center_front_right(n2), get_center_front(n2),
|
||||
add_cell(grid, get_center(n2), get_center_right(n2), get_center_front_right(n2), get_center_front(n2),
|
||||
get_center(n6), get_center_right(n6), get_center_front_right(n6), get_center_front(n6));
|
||||
}
|
||||
}
|
||||
|
||||
if (is_border_top(n4, _octree_root_size) &&
|
||||
is_border_top(n5, _octree_root_size) &&
|
||||
is_border_top(n6, _octree_root_size) &&
|
||||
is_border_top(n7, _octree_root_size)) {
|
||||
add_cell(grid,
|
||||
get_center(n4), get_center(n5), get_center(n6), get_center(n7),
|
||||
get_center_top(n4), get_center_top(n5), get_center_top(n6), get_center_top(n7));
|
||||
if (is_border_top(n4, _octree_root_size) && is_border_top(n5, _octree_root_size) &&
|
||||
is_border_top(n6, _octree_root_size) && is_border_top(n7, _octree_root_size)) {
|
||||
add_cell(grid, get_center(n4), get_center(n5), get_center(n6), get_center(n7), get_center_top(n4),
|
||||
get_center_top(n5), get_center_top(n6), get_center_top(n7));
|
||||
}
|
||||
|
||||
if (is_border_bottom(n0) && is_border_bottom(n1) && is_border_bottom(n2) && is_border_bottom(n3)) {
|
||||
add_cell(grid,
|
||||
get_center_bottom(n0), get_center_bottom(n1), get_center_bottom(n2), get_center_bottom(n3),
|
||||
add_cell(grid, get_center_bottom(n0), get_center_bottom(n1), get_center_bottom(n2), get_center_bottom(n3),
|
||||
get_center(n0), get_center(n1), get_center(n2), get_center(n3));
|
||||
}
|
||||
}
|
||||
|
@ -838,15 +781,8 @@ inline bool is_surface_near(OctreeNode *node) {
|
|||
return Math::abs(node->center_value.sdf) < node->size * SQRT3 * NEAR_SURFACE_FACTOR;
|
||||
}
|
||||
|
||||
void DualGridGenerator::vert_proc(
|
||||
OctreeNode *n0,
|
||||
OctreeNode *n1,
|
||||
OctreeNode *n2,
|
||||
OctreeNode *n3,
|
||||
OctreeNode *n4,
|
||||
OctreeNode *n5,
|
||||
OctreeNode *n6,
|
||||
OctreeNode *n7) {
|
||||
void DualGridGenerator::vert_proc(OctreeNode *n0, OctreeNode *n1, OctreeNode *n2, OctreeNode *n3, OctreeNode *n4,
|
||||
OctreeNode *n5, OctreeNode *n6, OctreeNode *n7) {
|
||||
const bool n0_has_children = n0->has_children();
|
||||
const bool n1_has_children = n1->has_children();
|
||||
const bool n2_has_children = n2->has_children();
|
||||
|
@ -856,9 +792,8 @@ void DualGridGenerator::vert_proc(
|
|||
const bool n6_has_children = n6->has_children();
|
||||
const bool n7_has_children = n7->has_children();
|
||||
|
||||
if (
|
||||
n0_has_children || n1_has_children || n2_has_children || n3_has_children ||
|
||||
n4_has_children || n5_has_children || n6_has_children || n7_has_children) {
|
||||
if (n0_has_children || n1_has_children || n2_has_children || n3_has_children || n4_has_children ||
|
||||
n5_has_children || n6_has_children || n7_has_children) {
|
||||
OctreeNode *c0 = n0_has_children ? n0->children[6] : n0;
|
||||
OctreeNode *c1 = n1_has_children ? n1->children[7] : n1;
|
||||
OctreeNode *c2 = n2_has_children ? n2->children[4] : n2;
|
||||
|
@ -871,15 +806,8 @@ void DualGridGenerator::vert_proc(
|
|||
vert_proc(c0, c1, c2, c3, c4, c5, c6, c7);
|
||||
|
||||
} else {
|
||||
if (!(
|
||||
is_surface_near(n0) ||
|
||||
is_surface_near(n1) ||
|
||||
is_surface_near(n2) ||
|
||||
is_surface_near(n3) ||
|
||||
is_surface_near(n4) ||
|
||||
is_surface_near(n5) ||
|
||||
is_surface_near(n6) ||
|
||||
is_surface_near(n7))) {
|
||||
if (!(is_surface_near(n0) || is_surface_near(n1) || is_surface_near(n2) || is_surface_near(n3) ||
|
||||
is_surface_near(n4) || is_surface_near(n5) || is_surface_near(n6) || is_surface_near(n7))) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1103,7 +1031,8 @@ void DualGridGenerator::node_proc(OctreeNode *node) {
|
|||
vert_proc(children[0], children[1], children[2], children[3], children[4], children[5], children[6], children[7]);
|
||||
}
|
||||
|
||||
inline Vector3 interpolate(const Vector3 &v0, const Vector3 &v1, const HermiteValue &val0, const HermiteValue &val1, Vector3 &out_normal) {
|
||||
inline Vector3 interpolate(
|
||||
const Vector3 &v0, const Vector3 &v1, const HermiteValue &val0, const HermiteValue &val1, Vector3 &out_normal) {
|
||||
if (Math::abs(val0.sdf - SURFACE_ISO_LEVEL) <= FLT_EPSILON) {
|
||||
out_normal = val0.gradient;
|
||||
out_normal.normalize();
|
||||
|
@ -1129,10 +1058,11 @@ inline Vector3 interpolate(const Vector3 &v0, const Vector3 &v1, const HermiteVa
|
|||
return v0 + mu * (v1 - v0);
|
||||
}
|
||||
|
||||
void polygonize_cell_marching_squares(const Vector3 *cube_corners, const HermiteValue *cube_values, float max_distance, MeshBuilder &mesh_builder, const int *corner_map) {
|
||||
void polygonize_cell_marching_squares(const Vector3 *cube_corners, const HermiteValue *cube_values, float max_distance,
|
||||
MeshBuilder &mesh_builder, const int *corner_map) {
|
||||
// Note:
|
||||
// Using Ogre's implementation directly resulted in inverted result, because it expects density values instead of SDF,
|
||||
// So I had to flip a few things around in order to make it work
|
||||
// Using Ogre's implementation directly resulted in inverted result, because it expects density values instead of
|
||||
// SDF, So I had to flip a few things around in order to make it work
|
||||
|
||||
unsigned char square_index = 0;
|
||||
HermiteValue values[4];
|
||||
|
@ -1147,11 +1077,8 @@ void polygonize_cell_marching_squares(const Vector3 *cube_corners, const Hermite
|
|||
|
||||
// Don't generate triangles if we are completely inside and far enough away from the surface
|
||||
max_distance = -max_distance;
|
||||
if (square_index == 15 &&
|
||||
values[0].sdf <= max_distance &&
|
||||
values[1].sdf <= max_distance &&
|
||||
values[2].sdf <= max_distance &&
|
||||
values[3].sdf <= max_distance) {
|
||||
if (square_index == 15 && values[0].sdf <= max_distance && values[1].sdf <= max_distance &&
|
||||
values[2].sdf <= max_distance && values[3].sdf <= max_distance) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1181,22 +1108,27 @@ void polygonize_cell_marching_squares(const Vector3 *cube_corners, const Hermite
|
|||
intersection_normals[6] = inner_val.gradient.normalized(); // * (inner_val.value + 1.0);
|
||||
|
||||
if (edge & 1) {
|
||||
intersection_points[1] = interpolate(cube_corners[corner_map[0]], cube_corners[corner_map[1]], values[0], values[1], intersection_normals[1]);
|
||||
intersection_points[1] = interpolate(cube_corners[corner_map[0]], cube_corners[corner_map[1]], values[0],
|
||||
values[1], intersection_normals[1]);
|
||||
}
|
||||
if (edge & 2) {
|
||||
intersection_points[3] = interpolate(cube_corners[corner_map[1]], cube_corners[corner_map[2]], values[1], values[2], intersection_normals[3]);
|
||||
intersection_points[3] = interpolate(cube_corners[corner_map[1]], cube_corners[corner_map[2]], values[1],
|
||||
values[2], intersection_normals[3]);
|
||||
}
|
||||
if (edge & 4) {
|
||||
intersection_points[5] = interpolate(cube_corners[corner_map[2]], cube_corners[corner_map[3]], values[2], values[3], intersection_normals[5]);
|
||||
intersection_points[5] = interpolate(cube_corners[corner_map[2]], cube_corners[corner_map[3]], values[2],
|
||||
values[3], intersection_normals[5]);
|
||||
}
|
||||
if (edge & 8) {
|
||||
intersection_points[7] = interpolate(cube_corners[corner_map[3]], cube_corners[corner_map[0]], values[3], values[0], intersection_normals[7]);
|
||||
intersection_points[7] = interpolate(cube_corners[corner_map[3]], cube_corners[corner_map[0]], values[3],
|
||||
values[0], intersection_normals[7]);
|
||||
}
|
||||
|
||||
// Ambigous case handling, 5 = 0 2 and 10 = 1 3
|
||||
/*if (squareIndex == 5 || squareIndex == 10)
|
||||
{
|
||||
Vector3 avg = (corners[corner_map[0]] + corners[corner_map[1]] + corners[corner_map[2]] + corners[corner_map[3]]) / (Real)4.0;
|
||||
Vector3 avg = (corners[corner_map[0]] + corners[corner_map[1]] + corners[corner_map[2]] +
|
||||
corners[corner_map[3]]) / (Real)4.0;
|
||||
// Lets take the alternative.
|
||||
if (mSrc->getValue(avg) >= ISO_LEVEL)
|
||||
{
|
||||
|
@ -1206,16 +1138,13 @@ void polygonize_cell_marching_squares(const Vector3 *cube_corners, const Hermite
|
|||
|
||||
// Create the triangles according to the table.
|
||||
for (int i = 0; MarchingCubes::ms_triangles[square_index][i] != -1; i += 3) {
|
||||
mesh_builder.add_vertex(
|
||||
intersection_points[MarchingCubes::ms_triangles[square_index][i]],
|
||||
mesh_builder.add_vertex(intersection_points[MarchingCubes::ms_triangles[square_index][i]],
|
||||
intersection_normals[MarchingCubes::ms_triangles[square_index][i]]);
|
||||
|
||||
mesh_builder.add_vertex(
|
||||
intersection_points[MarchingCubes::ms_triangles[square_index][i + 2]],
|
||||
mesh_builder.add_vertex(intersection_points[MarchingCubes::ms_triangles[square_index][i + 2]],
|
||||
intersection_normals[MarchingCubes::ms_triangles[square_index][i + 2]]);
|
||||
|
||||
mesh_builder.add_vertex(
|
||||
intersection_points[MarchingCubes::ms_triangles[square_index][i + 1]],
|
||||
mesh_builder.add_vertex(intersection_points[MarchingCubes::ms_triangles[square_index][i + 1]],
|
||||
intersection_normals[MarchingCubes::ms_triangles[square_index][i + 1]]);
|
||||
}
|
||||
}
|
||||
|
@ -1231,26 +1160,33 @@ static const int g_corner_map_bottom[4] = { 3, 2, 1, 0 };
|
|||
|
||||
} // namespace MarchingSquares
|
||||
|
||||
void add_marching_squares_skirts(const Vector3 *corners, const HermiteValue *values, MeshBuilder &mesh_builder, Vector3 min_pos, Vector3 max_pos) {
|
||||
void add_marching_squares_skirts(const Vector3 *corners, const HermiteValue *values, MeshBuilder &mesh_builder,
|
||||
Vector3 min_pos, Vector3 max_pos) {
|
||||
float max_distance = 0.2f; // Max distance to the isosurface
|
||||
|
||||
if (corners[0].z == min_pos.z) {
|
||||
polygonize_cell_marching_squares(corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_back);
|
||||
polygonize_cell_marching_squares(
|
||||
corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_back);
|
||||
}
|
||||
if (corners[2].z == max_pos.z) {
|
||||
polygonize_cell_marching_squares(corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_front);
|
||||
polygonize_cell_marching_squares(
|
||||
corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_front);
|
||||
}
|
||||
if (corners[0].x == min_pos.x) {
|
||||
polygonize_cell_marching_squares(corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_left);
|
||||
polygonize_cell_marching_squares(
|
||||
corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_left);
|
||||
}
|
||||
if (corners[1].x == max_pos.x) {
|
||||
polygonize_cell_marching_squares(corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_right);
|
||||
polygonize_cell_marching_squares(
|
||||
corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_right);
|
||||
}
|
||||
if (corners[5].y == max_pos.y) {
|
||||
polygonize_cell_marching_squares(corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_top);
|
||||
polygonize_cell_marching_squares(
|
||||
corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_top);
|
||||
}
|
||||
if (corners[0].y == min_pos.y) {
|
||||
polygonize_cell_marching_squares(corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_bottom);
|
||||
polygonize_cell_marching_squares(
|
||||
corners, values, max_distance, mesh_builder, MarchingSquares::g_corner_map_bottom);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1312,23 +1248,21 @@ void polygonize_cell_marching_cubes(const Vector3 *corners, const HermiteValue *
|
|||
|
||||
// Create the triangles according to the table.
|
||||
for (int i = 0; MarchingCubes::mc_triangles[case_index][i] != -1; i += 3) {
|
||||
mesh_builder.add_vertex(
|
||||
intersection_points[MarchingCubes::mc_triangles[case_index][i]],
|
||||
mesh_builder.add_vertex(intersection_points[MarchingCubes::mc_triangles[case_index][i]],
|
||||
intersection_normals[MarchingCubes::mc_triangles[case_index][i]]);
|
||||
|
||||
mesh_builder.add_vertex(
|
||||
intersection_points[MarchingCubes::mc_triangles[case_index][i + 1]],
|
||||
mesh_builder.add_vertex(intersection_points[MarchingCubes::mc_triangles[case_index][i + 1]],
|
||||
intersection_normals[MarchingCubes::mc_triangles[case_index][i + 1]]);
|
||||
|
||||
mesh_builder.add_vertex(
|
||||
intersection_points[MarchingCubes::mc_triangles[case_index][i + 2]],
|
||||
mesh_builder.add_vertex(intersection_points[MarchingCubes::mc_triangles[case_index][i + 2]],
|
||||
intersection_normals[MarchingCubes::mc_triangles[case_index][i + 2]]);
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
void polygonize_dual_cell(const DualCell &cell, const VoxelAccess &voxels, MeshBuilder &mesh_builder, bool skirts_enabled) {
|
||||
void polygonize_dual_cell(
|
||||
const DualCell &cell, const VoxelAccess &voxels, MeshBuilder &mesh_builder, bool skirts_enabled) {
|
||||
const Vector3 *corners = cell.corners;
|
||||
HermiteValue values[8];
|
||||
|
||||
|
@ -1343,11 +1277,13 @@ void polygonize_dual_cell(const DualCell &cell, const VoxelAccess &voxels, MeshB
|
|||
polygonize_cell_marching_cubes(corners, values, mesh_builder);
|
||||
|
||||
if (skirts_enabled) {
|
||||
add_marching_squares_skirts(corners, values, mesh_builder, Vector3(), (voxels.buffer.get_size() + voxels.offset).to_vec3());
|
||||
add_marching_squares_skirts(
|
||||
corners, values, mesh_builder, Vector3(), (voxels.buffer.get_size() + voxels.offset));
|
||||
}
|
||||
}
|
||||
|
||||
inline void polygonize_dual_grid(const DualGrid &grid, const VoxelAccess &voxels, MeshBuilder &mesh_builder, bool skirts_enabled) {
|
||||
inline void polygonize_dual_grid(
|
||||
const DualGrid &grid, const VoxelAccess &voxels, MeshBuilder &mesh_builder, bool skirts_enabled) {
|
||||
for (unsigned int i = 0; i < grid.cells.size(); ++i) {
|
||||
polygonize_dual_cell(grid.cells[i], voxels, mesh_builder, skirts_enabled);
|
||||
}
|
||||
|
@ -1359,10 +1295,10 @@ void polygonize_volume_directly(const VoxelBufferInternal &voxels, Vector3i min,
|
|||
HermiteValue values[8];
|
||||
|
||||
const Vector3i max = min + size;
|
||||
const Vector3 minf = min.to_vec3();
|
||||
const Vector3 minf = min;
|
||||
|
||||
const Vector3 min_vertex_pos = Vector3();
|
||||
const Vector3 max_vertex_pos = (voxels.get_size() - 2 * min).to_vec3();
|
||||
const Vector3 max_vertex_pos = voxels.get_size() - 2 * min;
|
||||
|
||||
for (int z = min.z; z < max.z; ++z) {
|
||||
for (int x = min.x; x < max.x; ++x) {
|
||||
|
@ -1409,8 +1345,7 @@ VoxelMesherDMC::VoxelMesherDMC() {
|
|||
set_padding(PADDING, PADDING);
|
||||
}
|
||||
|
||||
VoxelMesherDMC::~VoxelMesherDMC() {
|
||||
}
|
||||
VoxelMesherDMC::~VoxelMesherDMC() {}
|
||||
|
||||
void VoxelMesherDMC::set_mesh_mode(MeshMode mode) {
|
||||
RWLockWrite wlock(_parameters_lock);
|
||||
|
@ -1488,10 +1423,11 @@ void VoxelMesherDMC::build(VoxelMesher::Output &output, const VoxelMesher::Input
|
|||
// Unfortunately, such seams require the ability to quickly swap index buffers of the mesh using OpenGL/Vulkan,
|
||||
// which is not possible with current Godot's VisualServer without forking the whole lot (dang!),
|
||||
// and we are forced to at least re-upload the mesh entirely or have 16 versions of it just swapping seams...
|
||||
// So we can't improve this further until Godot's API gives us that possibility, or other approaches like skirts need to be taken.
|
||||
// So we can't improve this further until Godot's API gives us that possibility, or other approaches like skirts
|
||||
// need to be taken.
|
||||
|
||||
// Construct an intermediate to handle padding transparently
|
||||
dmc::VoxelAccess voxels_access(voxels, Vector3i(PADDING));
|
||||
dmc::VoxelAccess voxels_access(voxels, Vector3iUtil::create(PADDING));
|
||||
|
||||
Stats stats;
|
||||
real_t time_before = OS::get_singleton()->get_ticks_usec();
|
||||
|
@ -1560,12 +1496,12 @@ void VoxelMesherDMC::build(VoxelMesher::Output &output, const VoxelMesher::Input
|
|||
// We throw away adaptivity for meshing speed.
|
||||
// This is essentially regular marching cubes.
|
||||
time_before = OS::get_singleton()->get_ticks_usec();
|
||||
dmc::polygonize_volume_directly(
|
||||
voxels, Vector3i(PADDING), Vector3i(chunk_size), cache.mesh_builder, skirts_enabled);
|
||||
dmc::polygonize_volume_directly(voxels, Vector3iUtil::create(PADDING), Vector3iUtil::create(chunk_size),
|
||||
cache.mesh_builder, skirts_enabled);
|
||||
stats.meshing_time = OS::get_singleton()->get_ticks_usec() - time_before;
|
||||
}
|
||||
|
||||
if (surface.empty()) {
|
||||
if (surface.is_empty()) {
|
||||
time_before = OS::get_singleton()->get_ticks_usec();
|
||||
if (input.lod > 0) {
|
||||
cache.mesh_builder.scale(1 << input.lod);
|
||||
|
@ -1626,11 +1562,10 @@ void VoxelMesherDMC::_bind_methods() {
|
|||
PropertyInfo(Variant::INT, "mesh_mode", PROPERTY_HINT_ENUM, "Normal,Wireframe,DebugOctree,DebugDualGrid"),
|
||||
"set_mesh_mode", "get_mesh_mode");
|
||||
|
||||
ADD_PROPERTY(
|
||||
PropertyInfo(Variant::INT, "simplify_mode", PROPERTY_HINT_ENUM, "OctreeBottomUp,OctreeTopDown,None"),
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "simplify_mode", PROPERTY_HINT_ENUM, "OctreeBottomUp,OctreeTopDown,None"),
|
||||
"set_simplify_mode", "get_simplify_mode");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "geometric_error"), "set_simplify_mode", "get_simplify_mode");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "geometric_error"), "set_simplify_mode", "get_simplify_mode");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::INT, "seam_mode", PROPERTY_HINT_ENUM, "None,MarchingSquareSkirts"),
|
||||
"set_seam_mode", "get_seam_mode");
|
||||
|
|
|
@ -14,7 +14,6 @@ typedef ObjectPool<OctreeNode> OctreeNodePool;
|
|||
|
||||
// Octree used only for dual grid construction
|
||||
struct OctreeNode {
|
||||
|
||||
Vector3i origin;
|
||||
int size; // Nodes are cubic
|
||||
HermiteValue center_value;
|
||||
|
@ -67,20 +66,20 @@ class VoxelMesherDMC : public VoxelMesher {
|
|||
public:
|
||||
static const int PADDING = 2;
|
||||
|
||||
enum MeshMode {
|
||||
enum MeshMode { //
|
||||
MESH_NORMAL,
|
||||
MESH_WIREFRAME,
|
||||
MESH_DEBUG_OCTREE,
|
||||
MESH_DEBUG_DUAL_GRID
|
||||
};
|
||||
|
||||
enum SimplifyMode {
|
||||
enum SimplifyMode { //
|
||||
SIMPLIFY_OCTREE_BOTTOM_UP,
|
||||
SIMPLIFY_OCTREE_TOP_DOWN,
|
||||
SIMPLIFY_NONE
|
||||
};
|
||||
|
||||
enum SeamMode {
|
||||
enum SeamMode { //
|
||||
SEAM_NONE, // No seam management
|
||||
SEAM_MARCHING_SQUARE_SKIRTS,
|
||||
// SEAM_OVERLAP // Polygonize extra voxels with lower isolevel
|
||||
|
|
|
@ -28,7 +28,7 @@ Vector3 get_border_offset(const Vector3 pos, const int lod_index, const Vector3i
|
|||
|
||||
const float wk = TRANSITION_CELL_SCALE * p2k; // 2 ^ (lod - 2), if scale is 0.25
|
||||
|
||||
for (unsigned int i = 0; i < Vector3i::AXIS_COUNT; ++i) {
|
||||
for (unsigned int i = 0; i < Vector3iUtil::AXIS_COUNT; ++i) {
|
||||
const float p = pos[i];
|
||||
const float s = block_size[i];
|
||||
|
||||
|
@ -52,10 +52,12 @@ inline Vector3 project_border_offset(Vector3 delta, Vector3 normal) {
|
|||
// | y | + | -nx * ny , 1 - ny² , -ny * nz | * | Δy |
|
||||
// | z | | -nx * nz , -ny * nz , 1 - nz² | | Δz |
|
||||
//
|
||||
return Vector3(
|
||||
(1 - normal.x * normal.x) * delta.x /**/ - normal.y * normal.x * delta.y /* */ - normal.z * normal.x * delta.z,
|
||||
/**/ -normal.x * normal.y * delta.x + (1 - normal.y * normal.y) * delta.y /* */ - normal.z * normal.y * delta.z,
|
||||
/**/ -normal.x * normal.z * delta.x /**/ - normal.y * normal.z * delta.y /**/ + (1 - normal.z * normal.z) * delta.z);
|
||||
return Vector3((1 - normal.x * normal.x) * delta.x /**/ - normal.y * normal.x * delta.y /* */ -
|
||||
normal.z * normal.x * delta.z,
|
||||
/**/ -normal.x * normal.y * delta.x + (1 - normal.y * normal.y) * delta.y /* */ -
|
||||
normal.z * normal.y * delta.z,
|
||||
/**/ -normal.x * normal.z * delta.x /**/ - normal.y * normal.z * delta.y /**/ +
|
||||
(1 - normal.z * normal.z) * delta.z);
|
||||
}
|
||||
|
||||
inline Vector3 get_secondary_position(
|
||||
|
@ -75,7 +77,7 @@ inline uint8_t get_border_mask(const Vector3i &pos, const Vector3i &block_size)
|
|||
// 16: -Z
|
||||
// 32: +Z
|
||||
|
||||
for (unsigned int i = 0; i < Vector3i::AXIS_COUNT; i++) {
|
||||
for (unsigned int i = 0; i < Vector3iUtil::AXIS_COUNT; i++) {
|
||||
// Close to negative face.
|
||||
if (pos[i] == 0) {
|
||||
mask |= (1 << (i * 2));
|
||||
|
@ -101,10 +103,7 @@ inline Vector3 normalized_not_null(Vector3 n) {
|
|||
|
||||
inline Vector3i dir_to_prev_vec(uint8_t dir) {
|
||||
//return g_corner_dirs[mask] - Vector3(1,1,1);
|
||||
return Vector3i(
|
||||
-(dir & 1),
|
||||
-((dir >> 1) & 1),
|
||||
-((dir >> 2) & 1));
|
||||
return Vector3i(-(dir & 1), -((dir >> 1) & 1), -((dir >> 2) & 1));
|
||||
}
|
||||
|
||||
inline float sdf_as_float(uint8_t v) {
|
||||
|
@ -124,8 +123,7 @@ inline float sdf_as_float(double v) {
|
|||
}
|
||||
|
||||
template <typename Sdf_T>
|
||||
inline Vector3 get_corner_gradient(
|
||||
unsigned int data_index, Span<const Sdf_T> sdf_data, const Vector3i block_size) {
|
||||
inline Vector3 get_corner_gradient(unsigned int data_index, Span<const Sdf_T> sdf_data, const Vector3i block_size) {
|
||||
const unsigned int n010 = 1; // Y+1
|
||||
const unsigned int n100 = block_size.y; // X+1
|
||||
const unsigned int n001 = block_size.y * block_size.x; // Z+1
|
||||
|
@ -145,8 +143,8 @@ inline uint32_t pack_bytes(const FixedArray<uint8_t, 4> &a) {
|
|||
return (a[0] | (a[1] << 8) | (a[2] << 16) | (a[3] << 24));
|
||||
}
|
||||
|
||||
void add_texture_data(std::vector<Vector2> &uv, unsigned int packed_indices,
|
||||
FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights) {
|
||||
void add_texture_data(
|
||||
std::vector<Vector2> &uv, unsigned int packed_indices, FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights) {
|
||||
struct IntUV {
|
||||
uint32_t x;
|
||||
uint32_t y;
|
||||
|
@ -159,8 +157,7 @@ void add_texture_data(std::vector<Vector2> &uv, unsigned int packed_indices,
|
|||
iuv.y = pack_bytes(weights);
|
||||
}
|
||||
|
||||
template <unsigned int NVoxels>
|
||||
struct CellTextureDatas {
|
||||
template <unsigned int NVoxels> struct CellTextureDatas {
|
||||
uint32_t packed_indices = 0;
|
||||
FixedArray<uint8_t, MAX_TEXTURE_BLENDS> indices;
|
||||
FixedArray<FixedArray<uint8_t, MAX_TEXTURE_BLENDS>, NVoxels> weights;
|
||||
|
@ -218,11 +215,7 @@ CellTextureDatas<NVoxels> select_textures(const FixedArray<unsigned int, NVoxels
|
|||
// Sort indices to avoid cases that are ambiguous for blending, like 1,2,3,4 and 2,1,3,4
|
||||
// TODO maybe we could require this sorting to be done up front?
|
||||
// Or maybe could be done after meshing so we do it less times?
|
||||
sort(
|
||||
cell_textures.indices[0],
|
||||
cell_textures.indices[1],
|
||||
cell_textures.indices[2],
|
||||
cell_textures.indices[3]);
|
||||
sort(cell_textures.indices[0], cell_textures.indices[1], cell_textures.indices[2], cell_textures.indices[3]);
|
||||
|
||||
cell_textures.packed_indices = pack_bytes(cell_textures.indices);
|
||||
|
||||
|
@ -249,8 +242,7 @@ struct TextureIndicesData {
|
|||
|
||||
template <unsigned int NVoxels, typename WeightSampler_T>
|
||||
inline void get_cell_texture_data(CellTextureDatas<NVoxels> &cell_textures,
|
||||
const TextureIndicesData &texture_indices_data,
|
||||
const FixedArray<unsigned int, NVoxels> &voxel_indices,
|
||||
const TextureIndicesData &texture_indices_data, const FixedArray<unsigned int, NVoxels> &voxel_indices,
|
||||
const WeightSampler_T &weights_data) {
|
||||
if (texture_indices_data.buffer.size() == 0) {
|
||||
// Indices are known for the whole block, just read weights directly
|
||||
|
@ -267,37 +259,30 @@ inline void get_cell_texture_data(CellTextureDatas<NVoxels> &cell_textures,
|
|||
}
|
||||
}
|
||||
|
||||
template <typename Sdf_T>
|
||||
inline Sdf_T get_isolevel() = delete;
|
||||
template <typename Sdf_T> inline Sdf_T get_isolevel() = delete;
|
||||
|
||||
template <>
|
||||
inline uint8_t get_isolevel<uint8_t>() {
|
||||
template <> inline uint8_t get_isolevel<uint8_t>() {
|
||||
return 128;
|
||||
}
|
||||
|
||||
template <>
|
||||
inline uint16_t get_isolevel<uint16_t>() {
|
||||
template <> inline uint16_t get_isolevel<uint16_t>() {
|
||||
return 32768;
|
||||
}
|
||||
|
||||
template <>
|
||||
inline float get_isolevel<float>() {
|
||||
template <> inline float get_isolevel<float>() {
|
||||
return 0.f;
|
||||
}
|
||||
|
||||
// This function is template so we avoid branches and checks when sampling voxels
|
||||
template <typename Sdf_T, typename WeightSampler_T>
|
||||
void build_regular_mesh(
|
||||
Span<const Sdf_T> sdf_data,
|
||||
TextureIndicesData texture_indices_data,
|
||||
const WeightSampler_T &weights_sampler,
|
||||
const Vector3i block_size_with_padding,
|
||||
int lod_index, TexturingMode texturing_mode, Cache &cache, MeshArrays &output) {
|
||||
void build_regular_mesh(Span<const Sdf_T> sdf_data, TextureIndicesData texture_indices_data,
|
||||
const WeightSampler_T &weights_sampler, const Vector3i block_size_with_padding, int lod_index,
|
||||
TexturingMode texturing_mode, Cache &cache, MeshArrays &output) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
// This function has some comments as quotes from the Transvoxel paper.
|
||||
|
||||
const Vector3i block_size = block_size_with_padding - Vector3i(MIN_PADDING + MAX_PADDING);
|
||||
const Vector3i block_size = block_size_with_padding - Vector3iUtil::create(MIN_PADDING + MAX_PADDING);
|
||||
const Vector3i block_size_scaled = block_size << lod_index;
|
||||
|
||||
// Prepare vertex reuse cache
|
||||
|
@ -305,8 +290,8 @@ void build_regular_mesh(
|
|||
|
||||
// We iterate 2x2x2 voxel groups, which the paper calls "cells".
|
||||
// We also reach one voxel further to compute normals, so we adjust the iterated area
|
||||
const Vector3i min_pos = Vector3i(MIN_PADDING);
|
||||
const Vector3i max_pos = block_size_with_padding - Vector3i(MAX_PADDING);
|
||||
const Vector3i min_pos = Vector3iUtil::create(MIN_PADDING);
|
||||
const Vector3i max_pos = block_size_with_padding - Vector3iUtil::create(MAX_PADDING);
|
||||
|
||||
// How much to advance in the data array to get neighbor voxels
|
||||
const unsigned int n010 = 1; // Y+1
|
||||
|
@ -325,14 +310,14 @@ void build_regular_mesh(
|
|||
for (pos.z = min_pos.z; pos.z < max_pos.z; ++pos.z) {
|
||||
for (pos.y = min_pos.y; pos.y < max_pos.y; ++pos.y) {
|
||||
// TODO Optimization: change iteration to be ZXY? (Data is laid out with Y as deepest coordinate)
|
||||
unsigned int data_index = Vector3i(min_pos.x, pos.y, pos.z).get_zxy_index(block_size_with_padding);
|
||||
unsigned int data_index =
|
||||
Vector3iUtil::get_zxy_index(Vector3i(min_pos.x, pos.y, pos.z), block_size_with_padding);
|
||||
|
||||
for (pos.x = min_pos.x; pos.x < max_pos.x; ++pos.x, data_index += block_size_with_padding.y) {
|
||||
{
|
||||
const bool s = sdf_data[data_index] < isolevel;
|
||||
|
||||
if (
|
||||
(sdf_data[data_index + n010] < isolevel) == s &&
|
||||
if ((sdf_data[data_index + n010] < isolevel) == s &&
|
||||
(sdf_data[data_index + n100] < isolevel) == s &&
|
||||
(sdf_data[data_index + n110] < isolevel) == s &&
|
||||
(sdf_data[data_index + n001] < isolevel) == s &&
|
||||
|
@ -435,10 +420,8 @@ void build_regular_mesh(
|
|||
// In these cases, we allow new vertex creation on additional edges of a cell.
|
||||
// While iterating through the cells in a block, a 3-bit mask is maintained whose bits indicate
|
||||
// whether corresponding bits in a direction code are valid
|
||||
const uint8_t direction_validity_mask =
|
||||
(pos.x > min_pos.x ? 1 : 0) |
|
||||
((pos.y > min_pos.y ? 1 : 0) << 1) |
|
||||
((pos.z > min_pos.z ? 1 : 0) << 2);
|
||||
const uint8_t direction_validity_mask = (pos.x > min_pos.x ? 1 : 0) |
|
||||
((pos.y > min_pos.y ? 1 : 0) << 1) | ((pos.z > min_pos.z ? 1 : 0) << 2);
|
||||
|
||||
const uint8_t regular_cell_class_index = Tables::get_regular_cell_class(case_code);
|
||||
const Tables::RegularCellData ®ular_cell_data =
|
||||
|
@ -448,7 +431,7 @@ void build_regular_mesh(
|
|||
|
||||
FixedArray<int, 12> cell_vertex_indices(-1);
|
||||
|
||||
const uint8_t cell_border_mask = get_border_mask(pos - min_pos, block_size - Vector3i(1));
|
||||
const uint8_t cell_border_mask = get_border_mask(pos - min_pos, block_size - Vector3i(1, 1, 1));
|
||||
|
||||
// For each vertex in the case
|
||||
for (unsigned int vertex_index = 0; vertex_index < vertex_count; ++vertex_index) {
|
||||
|
@ -533,11 +516,11 @@ void build_regular_mesh(
|
|||
//const int ti1 = 0x100 - t;
|
||||
|
||||
//const Vector3i primary = p0 * ti0 + p1 * ti1;
|
||||
const Vector3 primaryf = p0.to_vec3() * t0 + p1.to_vec3() * t1;
|
||||
const Vector3 cg0 = get_corner_gradient<Sdf_T>(corner_data_indices[v0], sdf_data,
|
||||
block_size_with_padding);
|
||||
const Vector3 cg1 = get_corner_gradient<Sdf_T>(corner_data_indices[v1], sdf_data,
|
||||
block_size_with_padding);
|
||||
const Vector3 primaryf = Vector3(p0) * t0 + Vector3(p1) * t1;
|
||||
const Vector3 cg0 = get_corner_gradient<Sdf_T>(
|
||||
corner_data_indices[v0], sdf_data, block_size_with_padding);
|
||||
const Vector3 cg1 = get_corner_gradient<Sdf_T>(
|
||||
corner_data_indices[v1], sdf_data, block_size_with_padding);
|
||||
const Vector3 normal = normalized_not_null(cg0 * t0 + cg1 * t1);
|
||||
|
||||
Vector3 secondary;
|
||||
|
@ -561,7 +544,7 @@ void build_regular_mesh(
|
|||
weights[i] = static_cast<uint8_t>(
|
||||
clamp(Math::lerp(weights0[i], weights1[i], t1), 0.f, 255.f));
|
||||
}
|
||||
add_texture_data(output.uv, cell_textures.packed_indices, weights);
|
||||
add_texture_data(output.texturing_data, cell_textures.packed_indices, weights);
|
||||
}
|
||||
|
||||
if (reuse_dir & 8) {
|
||||
|
@ -576,9 +559,9 @@ void build_regular_mesh(
|
|||
// This cell owns the vertex, so it should be created.
|
||||
|
||||
const Vector3i primary = p1;
|
||||
const Vector3 primaryf = primary.to_vec3();
|
||||
const Vector3 cg1 = get_corner_gradient<Sdf_T>(
|
||||
corner_data_indices[v1], sdf_data, block_size_with_padding);
|
||||
const Vector3 primaryf = primary;
|
||||
const Vector3 cg1 =
|
||||
get_corner_gradient<Sdf_T>(corner_data_indices[v1], sdf_data, block_size_with_padding);
|
||||
const Vector3 normal = normalized_not_null(cg1);
|
||||
|
||||
Vector3 secondary;
|
||||
|
@ -589,12 +572,11 @@ void build_regular_mesh(
|
|||
border_mask |= get_border_mask(p1, block_size_scaled) << 6;
|
||||
}
|
||||
|
||||
cell_vertex_indices[vertex_index] =
|
||||
output.add_vertex(primaryf, normal, border_mask, secondary);
|
||||
cell_vertex_indices[vertex_index] = output.add_vertex(primaryf, normal, border_mask, secondary);
|
||||
|
||||
if (texturing_mode == TEXTURES_BLEND_4_OVER_16) {
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights1 = cell_textures.weights[v1];
|
||||
add_texture_data(output.uv, cell_textures.packed_indices, weights1);
|
||||
add_texture_data(output.texturing_data, cell_textures.packed_indices, weights1);
|
||||
}
|
||||
|
||||
current_reuse_cell.vertices[0] = cell_vertex_indices[vertex_index];
|
||||
|
@ -624,9 +606,9 @@ void build_regular_mesh(
|
|||
const unsigned int vi = t == 0 ? v1 : v0;
|
||||
|
||||
const Vector3i primary = t == 0 ? p1 : p0;
|
||||
const Vector3 primaryf = primary.to_vec3();
|
||||
const Vector3 cg = get_corner_gradient<Sdf_T>(corner_data_indices[vi], sdf_data,
|
||||
block_size_with_padding);
|
||||
const Vector3 primaryf = primary;
|
||||
const Vector3 cg = get_corner_gradient<Sdf_T>(
|
||||
corner_data_indices[vi], sdf_data, block_size_with_padding);
|
||||
const Vector3 normal = normalized_not_null(cg);
|
||||
|
||||
// TODO This bit of code is repeated several times, factor it?
|
||||
|
@ -643,7 +625,7 @@ void build_regular_mesh(
|
|||
|
||||
if (texturing_mode == TEXTURES_BLEND_4_OVER_16) {
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights = cell_textures.weights[vi];
|
||||
add_texture_data(output.uv, cell_textures.packed_indices, weights);
|
||||
add_texture_data(output.texturing_data, cell_textures.packed_indices, weights);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -741,16 +723,14 @@ inline void get_face_axes(int &ax, int &ay, int dir) {
|
|||
}
|
||||
|
||||
template <typename Sdf_T, typename WeightSampler_T>
|
||||
void build_transition_mesh(
|
||||
Span<const Sdf_T> sdf_data,
|
||||
TextureIndicesData texture_indices_data,
|
||||
const WeightSampler_T &weights_sampler,
|
||||
const Vector3i block_size_with_padding,
|
||||
int direction, int lod_index, TexturingMode texturing_mode, Cache &cache, MeshArrays &output) {
|
||||
void build_transition_mesh(Span<const Sdf_T> sdf_data, TextureIndicesData texture_indices_data,
|
||||
const WeightSampler_T &weights_sampler, const Vector3i block_size_with_padding, int direction, int lod_index,
|
||||
TexturingMode texturing_mode, Cache &cache, MeshArrays &output) {
|
||||
// From this point, we expect the buffer to contain allocated data.
|
||||
// This function has some comments as quotes from the Transvoxel paper.
|
||||
|
||||
const Vector3i block_size_without_padding = block_size_with_padding - Vector3i(MIN_PADDING + MAX_PADDING);
|
||||
const Vector3i block_size_without_padding =
|
||||
block_size_with_padding - Vector3iUtil::create(MIN_PADDING + MAX_PADDING);
|
||||
const Vector3i block_size_scaled = block_size_without_padding << lod_index;
|
||||
|
||||
ERR_FAIL_COND(block_size_with_padding.x < 3);
|
||||
|
@ -772,8 +752,8 @@ void build_transition_mesh(
|
|||
// This represents the actual box of voxels we are working on.
|
||||
// It also represents positions of the minimum and maximum vertices that can be generated.
|
||||
// Padding is present to allow reaching 1 voxel further for calculating normals
|
||||
const Vector3i min_pos = Vector3i(MIN_PADDING);
|
||||
const Vector3i max_pos = block_size_with_padding - Vector3i(MAX_PADDING);
|
||||
const Vector3i min_pos = Vector3iUtil::create(MIN_PADDING);
|
||||
const Vector3i max_pos = block_size_with_padding - Vector3iUtil::create(MAX_PADDING);
|
||||
|
||||
int axis_x, axis_y;
|
||||
get_face_axes(axis_x, axis_y, direction);
|
||||
|
@ -791,10 +771,14 @@ void build_transition_mesh(
|
|||
// const unsigned int n011 = n010 + n001;
|
||||
// const unsigned int n111 = n100 + n010 + n001;
|
||||
|
||||
// Using temporay locals otherwise clang-format makes it hard to read
|
||||
const Vector3i ftb_000 = face_to_block(0, 0, 0, direction, block_size_with_padding);
|
||||
const Vector3i ftb_x00 = face_to_block(1, 0, 0, direction, block_size_with_padding);
|
||||
const Vector3i ftb_0y0 = face_to_block(0, 1, 0, direction, block_size_with_padding);
|
||||
// How much to advance in the data array to get neighbor voxels, using face coordinates
|
||||
const int fn00 = face_to_block(0, 0, 0, direction, block_size_with_padding).get_zxy_index(block_size_with_padding);
|
||||
const int fn10 = face_to_block(1, 0, 0, direction, block_size_with_padding).get_zxy_index(block_size_with_padding) - fn00;
|
||||
const int fn01 = face_to_block(0, 1, 0, direction, block_size_with_padding).get_zxy_index(block_size_with_padding) - fn00;
|
||||
const int fn00 = Vector3iUtil::get_zxy_index(ftb_000, block_size_with_padding);
|
||||
const int fn10 = Vector3iUtil::get_zxy_index(ftb_x00, block_size_with_padding) - fn00;
|
||||
const int fn01 = Vector3iUtil::get_zxy_index(ftb_0y0, block_size_with_padding) - fn00;
|
||||
const int fn11 = fn10 + fn01;
|
||||
const int fn21 = 2 * fn10 + fn01;
|
||||
const int fn22 = 2 * fn10 + 2 * fn01;
|
||||
|
@ -814,19 +798,20 @@ void build_transition_mesh(
|
|||
// Warning: temporarily includes padding. It is undone later.
|
||||
cell_positions[0] = face_to_block(fx, fy, fz, direction, block_size_with_padding);
|
||||
|
||||
const int data_index = cell_positions[0].get_zxy_index(block_size_with_padding);
|
||||
const int data_index = Vector3iUtil::get_zxy_index(cell_positions[0], block_size_with_padding);
|
||||
|
||||
{
|
||||
const bool s = sdf_data[data_index] < isolevel;
|
||||
|
||||
if (
|
||||
(sdf_data[data_index + fn10] < isolevel) == s &&
|
||||
(sdf_data[data_index + fn20] < isolevel) == s &&
|
||||
(sdf_data[data_index + fn01] < isolevel) == s &&
|
||||
(sdf_data[data_index + fn11] < isolevel) == s &&
|
||||
(sdf_data[data_index + fn21] < isolevel) == s &&
|
||||
(sdf_data[data_index + fn02] < isolevel) == s &&
|
||||
(sdf_data[data_index + fn12] < isolevel) == s &&
|
||||
// `//` prevents clang-format from messing up
|
||||
if ( //
|
||||
(sdf_data[data_index + fn10] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn20] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn01] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn11] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn21] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn02] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn12] < isolevel) == s && //
|
||||
(sdf_data[data_index + fn22] < isolevel) == s) {
|
||||
// Not crossing the isolevel, this cell won't produce any geometry.
|
||||
// We must figure this out as fast as possible, because it will happen a lot.
|
||||
|
@ -1021,7 +1006,7 @@ void build_transition_mesh(
|
|||
const Vector3 n1 = cell_gradients[index_vertex_b];
|
||||
|
||||
//Vector3i primary = p0 * ti0 + p1 * ti1;
|
||||
const Vector3 primaryf = p0.to_vec3() * t0 + p1.to_vec3() * t1;
|
||||
const Vector3 primaryf = Vector3(p0) * t0 + Vector3(p1) * t1;
|
||||
const Vector3 normal = normalized_not_null(n0 * t0 + n1 * t1);
|
||||
|
||||
const bool fullres_side = (index_vertex_a < 9 || index_vertex_b < 9);
|
||||
|
@ -1030,8 +1015,8 @@ void build_transition_mesh(
|
|||
Vector3 secondary;
|
||||
if (fullres_side) {
|
||||
secondary = get_secondary_position(primaryf, normal, 0, block_size_scaled);
|
||||
border_mask |= (get_border_mask(p0, block_size_scaled) &
|
||||
get_border_mask(p1, block_size_scaled))
|
||||
border_mask |=
|
||||
(get_border_mask(p0, block_size_scaled) & get_border_mask(p1, block_size_scaled))
|
||||
<< 6;
|
||||
|
||||
} else {
|
||||
|
@ -1045,14 +1030,16 @@ void build_transition_mesh(
|
|||
cell_vertex_indices[vertex_index] = output.add_vertex(primaryf, normal, border_mask, secondary);
|
||||
|
||||
if (texturing_mode == TEXTURES_BLEND_4_OVER_16) {
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights0 = cell_textures.weights[index_vertex_a];
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights1 = cell_textures.weights[index_vertex_b];
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights0 =
|
||||
cell_textures.weights[index_vertex_a];
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights1 =
|
||||
cell_textures.weights[index_vertex_b];
|
||||
FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights;
|
||||
for (unsigned int i = 0; i < cell_textures.indices.size(); ++i) {
|
||||
weights[i] = static_cast<uint8_t>(
|
||||
clamp(Math::lerp(weights0[i], weights1[i], t1), 0.f, 255.f));
|
||||
}
|
||||
add_texture_data(output.uv, cell_textures.packed_indices, weights);
|
||||
add_texture_data(output.texturing_data, cell_textures.packed_indices, weights);
|
||||
}
|
||||
|
||||
if (reuse_direction & 0x8) {
|
||||
|
@ -1088,7 +1075,7 @@ void build_transition_mesh(
|
|||
// Going to create a new vertex
|
||||
|
||||
const Vector3i primary = cell_positions[cell_index];
|
||||
const Vector3 primaryf = primary.to_vec3();
|
||||
const Vector3 primaryf = primary;
|
||||
const Vector3 normal = normalized_not_null(cell_gradients[cell_index]);
|
||||
|
||||
const bool fullres_side = (cell_index < 9);
|
||||
|
@ -1107,7 +1094,7 @@ void build_transition_mesh(
|
|||
|
||||
if (texturing_mode == TEXTURES_BLEND_4_OVER_16) {
|
||||
const FixedArray<uint8_t, MAX_TEXTURE_BLENDS> weights = cell_textures.weights[cell_index];
|
||||
add_texture_data(output.uv, cell_textures.packed_indices, weights);
|
||||
add_texture_data(output.texturing_data, cell_textures.packed_indices, weights);
|
||||
}
|
||||
|
||||
// We are on a corner so the vertex will be re-usable later
|
||||
|
@ -1140,11 +1127,11 @@ template <typename T>
|
|||
Span<const T> get_or_decompress_channel(
|
||||
const VoxelBufferInternal &voxels, std::vector<T> &backing_buffer, unsigned int channel) {
|
||||
//
|
||||
ERR_FAIL_COND_V(voxels.get_channel_depth(channel) != VoxelBufferInternal::get_depth_from_size(sizeof(T)),
|
||||
Span<const T>());
|
||||
ERR_FAIL_COND_V(
|
||||
voxels.get_channel_depth(channel) != VoxelBufferInternal::get_depth_from_size(sizeof(T)), Span<const T>());
|
||||
|
||||
if (voxels.get_channel_compression(channel) == VoxelBufferInternal::COMPRESSION_UNIFORM) {
|
||||
backing_buffer.resize(voxels.get_size().volume());
|
||||
backing_buffer.resize(Vector3iUtil::get_volume(voxels.get_size()));
|
||||
const T v = voxels.get_voxel(Vector3i(), channel);
|
||||
// TODO Could use a fast fill using 8-byte blocks or intrinsics?
|
||||
for (unsigned int i = 0; i < backing_buffer.size(); ++i) {
|
||||
|
@ -1227,7 +1214,7 @@ DefaultTextureIndicesData build_regular_mesh(const VoxelBufferInternal &voxels,
|
|||
Span<uint8_t> sdf_data_raw;
|
||||
CRASH_COND(voxels.get_channel_raw(sdf_channel, sdf_data_raw) == false);
|
||||
|
||||
const unsigned int voxels_count = voxels.get_size().volume();
|
||||
const unsigned int voxels_count = Vector3iUtil::get_volume(voxels.get_size());
|
||||
|
||||
DefaultTextureIndicesData default_texture_indices_data;
|
||||
default_texture_indices_data.use = false;
|
||||
|
@ -1305,7 +1292,7 @@ void build_transition_mesh(const VoxelBufferInternal &voxels, unsigned int sdf_c
|
|||
Span<uint8_t> sdf_data_raw;
|
||||
CRASH_COND(voxels.get_channel_raw(sdf_channel, sdf_data_raw) == false);
|
||||
|
||||
const unsigned int voxels_count = voxels.get_size().volume();
|
||||
const unsigned int voxels_count = Vector3iUtil::get_volume(voxels.get_size());
|
||||
|
||||
// TODO Support more texturing data configurations
|
||||
TextureIndicesData indices_data;
|
||||
|
@ -1354,20 +1341,20 @@ void build_transition_mesh(const VoxelBufferInternal &voxels, unsigned int sdf_c
|
|||
switch (voxels.get_channel_depth(sdf_channel)) {
|
||||
case VoxelBufferInternal::DEPTH_8_BIT: {
|
||||
Span<const uint8_t> sdf_data = sdf_data_raw.reinterpret_cast_to<const uint8_t>();
|
||||
build_transition_mesh<uint8_t>(sdf_data, indices_data, weights_data,
|
||||
voxels.get_size(), direction, lod_index, texturing_mode, cache, output);
|
||||
build_transition_mesh<uint8_t>(sdf_data, indices_data, weights_data, voxels.get_size(), direction,
|
||||
lod_index, texturing_mode, cache, output);
|
||||
} break;
|
||||
|
||||
case VoxelBufferInternal::DEPTH_16_BIT: {
|
||||
Span<const uint16_t> sdf_data = sdf_data_raw.reinterpret_cast_to<const uint16_t>();
|
||||
build_transition_mesh<uint16_t>(sdf_data, indices_data, weights_data,
|
||||
voxels.get_size(), direction, lod_index, texturing_mode, cache, output);
|
||||
build_transition_mesh<uint16_t>(sdf_data, indices_data, weights_data, voxels.get_size(), direction,
|
||||
lod_index, texturing_mode, cache, output);
|
||||
} break;
|
||||
|
||||
case VoxelBufferInternal::DEPTH_32_BIT: {
|
||||
Span<const float> sdf_data = sdf_data_raw.reinterpret_cast_to<const float>();
|
||||
build_transition_mesh<float>(sdf_data, indices_data, weights_data,
|
||||
voxels.get_size(), direction, lod_index, texturing_mode, cache, output);
|
||||
build_transition_mesh<float>(sdf_data, indices_data, weights_data, voxels.get_size(), direction, lod_index,
|
||||
texturing_mode, cache, output);
|
||||
} break;
|
||||
|
||||
case VoxelBufferInternal::DEPTH_64_BIT:
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#include "../../util/fixed_array.h"
|
||||
#include "../../util/math/vector3i.h"
|
||||
|
||||
#include <core/color.h>
|
||||
#include <core/math/color.h>
|
||||
#include <core/math/vector2.h>
|
||||
#include <core/math/vector3.h>
|
||||
#include <vector>
|
||||
|
@ -32,15 +32,15 @@ enum TexturingMode {
|
|||
struct MeshArrays {
|
||||
std::vector<Vector3> vertices;
|
||||
std::vector<Vector3> normals;
|
||||
std::vector<Color> extra;
|
||||
std::vector<Vector2> uv;
|
||||
std::vector<Color> lod_data;
|
||||
std::vector<Vector2> texturing_data;
|
||||
std::vector<int> indices;
|
||||
|
||||
void clear() {
|
||||
vertices.clear();
|
||||
normals.clear();
|
||||
extra.clear();
|
||||
uv.clear();
|
||||
lod_data.clear();
|
||||
texturing_data.clear();
|
||||
indices.clear();
|
||||
}
|
||||
|
||||
|
@ -48,7 +48,7 @@ struct MeshArrays {
|
|||
int vi = vertices.size();
|
||||
vertices.push_back(primary);
|
||||
normals.push_back(normal);
|
||||
extra.push_back(Color(secondary.x, secondary.y, secondary.z, border_mask));
|
||||
lod_data.push_back(Color(secondary.x, secondary.y, secondary.z, border_mask));
|
||||
return vi;
|
||||
}
|
||||
};
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
//
|
||||
//================================================================================
|
||||
|
||||
#include <core/error_macros.h>
|
||||
#include <core/error/error_macros.h>
|
||||
|
||||
namespace Transvoxel {
|
||||
namespace Tables {
|
||||
|
@ -50,13 +50,9 @@ struct RegularCellData {
|
|||
return vertexIndex[i];
|
||||
}
|
||||
|
||||
long GetVertexCount(void) const {
|
||||
return (geometryCounts >> 4);
|
||||
}
|
||||
long GetVertexCount(void) const { return (geometryCounts >> 4); }
|
||||
|
||||
long GetTriangleCount(void) const {
|
||||
return (geometryCounts & 0x0F);
|
||||
}
|
||||
long GetTriangleCount(void) const { return (geometryCounts & 0x0F); }
|
||||
};
|
||||
|
||||
// The TransitionCellData structure holds information about the triangulation
|
||||
|
@ -74,13 +70,9 @@ struct TransitionCellData {
|
|||
return vertexIndex[i];
|
||||
}
|
||||
|
||||
long GetVertexCount(void) const {
|
||||
return (geometryCounts >> 4);
|
||||
}
|
||||
long GetVertexCount(void) const { return (geometryCounts >> 4); }
|
||||
|
||||
long GetTriangleCount(void) const {
|
||||
return (geometryCounts & 0x0F);
|
||||
}
|
||||
long GetTriangleCount(void) const { return (geometryCounts & 0x0F); }
|
||||
};
|
||||
|
||||
// The regularCellClass table maps an 8-bit regular Marching Cubes case index to
|
||||
|
@ -88,7 +80,7 @@ struct TransitionCellData {
|
|||
// modified Marching Cubes algorithm, a couple of them use the same exact triangulations,
|
||||
// just with different vertex locations. We combined those classes for this table so
|
||||
// that the class index ranges from 0 to 15.
|
||||
|
||||
// clang-format off
|
||||
const unsigned char regularCellClass[256] = {
|
||||
0x00, 0x01, 0x01, 0x03, 0x01, 0x03, 0x02, 0x04, 0x01, 0x02, 0x03, 0x04, 0x03, 0x04, 0x04, 0x03,
|
||||
0x01, 0x03, 0x02, 0x04, 0x02, 0x04, 0x06, 0x0C, 0x02, 0x05, 0x05, 0x0B, 0x05, 0x0A, 0x07, 0x04,
|
||||
|
@ -107,6 +99,7 @@ const unsigned char regularCellClass[256] = {
|
|||
0x04, 0x07, 0x0A, 0x0E, 0x0B, 0x0E, 0x0E, 0x02, 0x0C, 0x0F, 0x04, 0x0D, 0x04, 0x0D, 0x03, 0x01,
|
||||
0x03, 0x04, 0x04, 0x03, 0x04, 0x03, 0x0D, 0x01, 0x04, 0x0D, 0x03, 0x01, 0x03, 0x01, 0x01, 0x00
|
||||
};
|
||||
// clang-format on
|
||||
inline unsigned char get_regular_cell_class(unsigned int i) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 256);
|
||||
|
@ -116,7 +109,7 @@ inline unsigned char get_regular_cell_class(unsigned int i) {
|
|||
|
||||
// The regularCellData table holds the triangulation data for all 16 distinct classes to
|
||||
// which a case can be mapped by the regularCellClass table.
|
||||
|
||||
// clang-format off
|
||||
const RegularCellData regularCellData[16] = {
|
||||
{ 0x00, {} },
|
||||
{ 0x31, { 0, 1, 2 } },
|
||||
|
@ -135,6 +128,7 @@ const RegularCellData regularCellData[16] = {
|
|||
{ 0x75, { 0, 1, 2, 0, 2, 3, 0, 3, 4, 0, 4, 5, 0, 5, 6 } },
|
||||
{ 0x95, { 0, 4, 5, 0, 3, 4, 0, 1, 3, 1, 2, 3, 6, 7, 8 } }
|
||||
};
|
||||
// clang-format on
|
||||
inline const RegularCellData &get_regular_cell_data(unsigned int i) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 16);
|
||||
|
@ -147,7 +141,7 @@ inline const RegularCellData &get_regular_cell_data(unsigned int i) {
|
|||
// about whether a vertex can be reused from a neighboring cell. See Section 3.3 for details.
|
||||
// The low byte contains the indexes for the two endpoints of the edge on which the vertex lies,
|
||||
// as numbered in Figure 3.7. The high byte contains the vertex reuse data shown in Figure 3.8.
|
||||
|
||||
// clang-format off
|
||||
const unsigned short regularVertexData[256][12] = {
|
||||
{},
|
||||
{ 0x6201, 0x5102, 0x3304 },
|
||||
|
@ -406,6 +400,7 @@ const unsigned short regularVertexData[256][12] = {
|
|||
{ 0x6201, 0x3304, 0x5102 },
|
||||
{}
|
||||
};
|
||||
// clang-format on
|
||||
inline unsigned short get_regular_vertex_data(unsigned int i, unsigned int j) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 256);
|
||||
|
@ -420,7 +415,7 @@ inline unsigned short get_regular_vertex_data(unsigned int i, unsigned int j) {
|
|||
// We combined those classes for this table so that the class index ranges from 0 to 55.
|
||||
// The high bit is set in the cases for which the inverse state of the voxel data maps to
|
||||
// the equivalence class, meaning that the winding order of each triangle should be reversed.
|
||||
|
||||
// clang-format off
|
||||
const unsigned char transitionCellClass[512] = {
|
||||
0x00, 0x01, 0x02, 0x84, 0x01, 0x05, 0x04, 0x04, 0x02, 0x87, 0x09, 0x8C, 0x84, 0x0B, 0x05, 0x05,
|
||||
0x01, 0x08, 0x07, 0x8D, 0x05, 0x0F, 0x8B, 0x0B, 0x04, 0x0D, 0x0C, 0x1C, 0x04, 0x8B, 0x85, 0x85,
|
||||
|
@ -455,6 +450,7 @@ const unsigned char transitionCellClass[512] = {
|
|||
0x05, 0x05, 0x0B, 0x84, 0x2F, 0x26, 0x35, 0x84, 0x8B, 0x0B, 0x8F, 0x85, 0xB5, 0x87, 0x34, 0x81,
|
||||
0x85, 0x85, 0x8B, 0x04, 0xA6, 0x25, 0x07, 0x82, 0x84, 0x84, 0x85, 0x81, 0x04, 0x82, 0x81, 0x80
|
||||
};
|
||||
// clang-format on
|
||||
inline unsigned char get_transition_cell_class(unsigned int i) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 512);
|
||||
|
@ -465,7 +461,7 @@ inline unsigned char get_transition_cell_class(unsigned int i) {
|
|||
// The transitionCellData table holds the triangulation data for all 56 distinct classes to
|
||||
// which a case can be mapped by the transitionCellClass table. The class index should be ANDed
|
||||
// with 0x7F before using it to look up triangulation data in this table.
|
||||
|
||||
// clang-format off
|
||||
const TransitionCellData transitionCellData[56] = {
|
||||
{ 0x00, {} },
|
||||
{ 0x42, { 0, 1, 3, 1, 2, 3 } },
|
||||
|
@ -524,6 +520,7 @@ const TransitionCellData transitionCellData[56] = {
|
|||
{ 0xA8, { 0, 1, 5, 1, 4, 5, 1, 2, 4, 2, 3, 4, 3, 6, 7, 3, 7, 4, 0, 8, 9, 0, 5, 8 } },
|
||||
{ 0xA8, { 0, 1, 5, 1, 4, 5, 1, 2, 4, 2, 3, 4, 2, 6, 3, 3, 6, 7, 0, 8, 9, 0, 5, 8 } }
|
||||
};
|
||||
// clang-format on
|
||||
inline const TransitionCellData &get_transition_cell_data(unsigned int i) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 56);
|
||||
|
@ -533,10 +530,11 @@ inline const TransitionCellData &get_transition_cell_data(unsigned int i) {
|
|||
|
||||
// The transitionCornerData table contains the transition cell corner reuse data
|
||||
// shown in Figure 4.18.
|
||||
|
||||
// clang-format off
|
||||
const unsigned char transitionCornerData[13] = {
|
||||
0x30, 0x21, 0x20, 0x12, 0x40, 0x82, 0x10, 0x81, 0x80, 0x37, 0x27, 0x17, 0x87
|
||||
};
|
||||
// clang-format on
|
||||
inline unsigned char get_transition_corner_data(unsigned int i) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 13);
|
||||
|
@ -549,7 +547,7 @@ inline unsigned char get_transition_corner_data(unsigned int i) {
|
|||
// a vertex can be reused from a neighboring cell. See Section 4.5 for details. The low byte
|
||||
// contains the indexes for the two endpoints of the edge on which the vertex lies, as numbered
|
||||
// in Figure 4.16. The high byte contains the vertex reuse data shown in Figure 4.17.
|
||||
|
||||
// clang-format off
|
||||
const unsigned short transitionVertexData[512][12] = {
|
||||
{},
|
||||
{ 0x2301, 0x1503, 0x199B, 0x289A },
|
||||
|
@ -1064,6 +1062,7 @@ const unsigned short transitionVertexData[512][12] = {
|
|||
{ 0x2301, 0x1503, 0x199B, 0x289A },
|
||||
{}
|
||||
};
|
||||
// clang-format on
|
||||
inline unsigned short get_transition_vertex_data(unsigned int i, unsigned int j) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= 512);
|
||||
|
|
|
@ -5,22 +5,21 @@
|
|||
#include "../../util/profiling.h"
|
||||
#include "transvoxel_tables.cpp"
|
||||
|
||||
namespace {
|
||||
static const unsigned int MESH_COMPRESSION_FLAGS =
|
||||
Mesh::ARRAY_COMPRESS_NORMAL |
|
||||
Mesh::ARRAY_COMPRESS_TANGENT |
|
||||
//Mesh::ARRAY_COMPRESS_COLOR | // Using color as 4 full floats to transfer extra attributes for now...
|
||||
//Mesh::ARRAY_COMPRESS_TEX_UV | // Not compressing UV, we use it for different texturing information
|
||||
Mesh::ARRAY_COMPRESS_TEX_UV2 |
|
||||
Mesh::ARRAY_COMPRESS_WEIGHTS;
|
||||
}
|
||||
// namespace {
|
||||
// static const unsigned int MESH_COMPRESSION_FLAGS = //
|
||||
// Mesh::ARRAY_FORMAT_NORMAL | //
|
||||
// Mesh::ARRAY_FORMAT_TANGENT | //
|
||||
// //Mesh::ARRAY_COMPRESS_COLOR | // Using color as 4 full floats to transfer extra attributes for now...
|
||||
// //Mesh::ARRAY_COMPRESS_TEX_UV | // Not compressing UV, we use it for different texturing information
|
||||
// Mesh::ARRAY_FORMAT_TEX_UV2 | //
|
||||
// Mesh::ARRAY_FORMAT_WEIGHTS;
|
||||
// }
|
||||
|
||||
VoxelMesherTransvoxel::VoxelMesherTransvoxel() {
|
||||
set_padding(Transvoxel::MIN_PADDING, Transvoxel::MAX_PADDING);
|
||||
}
|
||||
|
||||
VoxelMesherTransvoxel::~VoxelMesherTransvoxel() {
|
||||
}
|
||||
VoxelMesherTransvoxel::~VoxelMesherTransvoxel() {}
|
||||
|
||||
Ref<Resource> VoxelMesherTransvoxel::duplicate(bool p_subresources) const {
|
||||
return memnew(VoxelMesherTransvoxel);
|
||||
|
@ -28,22 +27,21 @@ Ref<Resource> VoxelMesherTransvoxel::duplicate(bool p_subresources) const {
|
|||
|
||||
int VoxelMesherTransvoxel::get_used_channels_mask() const {
|
||||
if (_texture_mode == TEXTURES_BLEND_4_OVER_16) {
|
||||
return (1 << VoxelBufferInternal::CHANNEL_SDF) |
|
||||
(1 << VoxelBufferInternal::CHANNEL_INDICES) |
|
||||
(1 << VoxelBufferInternal::CHANNEL_WEIGHTS);
|
||||
return (1 << VoxelBufferInternal::CHANNEL_SDF) | (1 << VoxelBufferInternal::CHANNEL_INDICES) |
|
||||
(1 << VoxelBufferInternal::CHANNEL_WEIGHTS);
|
||||
}
|
||||
return (1 << VoxelBufferInternal::CHANNEL_SDF);
|
||||
}
|
||||
|
||||
void VoxelMesherTransvoxel::fill_surface_arrays(Array &arrays, const Transvoxel::MeshArrays &src) {
|
||||
PoolVector<Vector3> vertices;
|
||||
PoolVector<Vector3> normals;
|
||||
PoolVector<Color> extra;
|
||||
PoolVector<Vector2> uv;
|
||||
PoolVector<int> indices;
|
||||
PackedVector3Array vertices;
|
||||
PackedVector3Array normals;
|
||||
PackedColorArray lod_data; // 4*float32
|
||||
PackedVector2Array texturing_data; // 2*4*uint8
|
||||
PackedInt32Array indices;
|
||||
|
||||
raw_copy_to(vertices, src.vertices);
|
||||
raw_copy_to(extra, src.extra);
|
||||
raw_copy_to(lod_data, src.lod_data);
|
||||
raw_copy_to(indices, src.indices);
|
||||
|
||||
arrays.resize(Mesh::ARRAY_MAX);
|
||||
|
@ -52,11 +50,11 @@ void VoxelMesherTransvoxel::fill_surface_arrays(Array &arrays, const Transvoxel:
|
|||
raw_copy_to(normals, src.normals);
|
||||
arrays[Mesh::ARRAY_NORMAL] = normals;
|
||||
}
|
||||
if (src.uv.size() != 0) {
|
||||
raw_copy_to(uv, src.uv);
|
||||
arrays[Mesh::ARRAY_TEX_UV] = uv;
|
||||
if (src.texturing_data.size() != 0) {
|
||||
raw_copy_to(texturing_data, src.texturing_data);
|
||||
arrays[Mesh::ARRAY_CUSTOM0] = texturing_data;
|
||||
}
|
||||
arrays[Mesh::ARRAY_COLOR] = extra;
|
||||
arrays[Mesh::ARRAY_CUSTOM1] = lod_data;
|
||||
arrays[Mesh::ARRAY_INDEX] = indices;
|
||||
}
|
||||
|
||||
|
@ -68,11 +66,12 @@ static void remap_vertex_array(const std::vector<T> &src_data, std::vector<T> &d
|
|||
return;
|
||||
}
|
||||
dst_data.resize(unique_vertex_count);
|
||||
meshopt_remapVertexBuffer(&dst_data[0], &src_data[0], src_data.size(), sizeof(T), remap_indices.data());
|
||||
zylannmeshopt::meshopt_remapVertexBuffer(
|
||||
&dst_data[0], &src_data[0], src_data.size(), sizeof(T), remap_indices.data());
|
||||
}
|
||||
|
||||
static void simplify(const Transvoxel::MeshArrays &src_mesh, Transvoxel::MeshArrays &dst_mesh,
|
||||
float p_target_ratio, float p_error_threshold) {
|
||||
static void simplify(const Transvoxel::MeshArrays &src_mesh, Transvoxel::MeshArrays &dst_mesh, float p_target_ratio,
|
||||
float p_error_threshold) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
||||
// Gather and check input
|
||||
|
@ -94,10 +93,11 @@ static void simplify(const Transvoxel::MeshArrays &src_mesh, Transvoxel::MeshArr
|
|||
{
|
||||
VOXEL_PROFILE_SCOPE_NAMED("meshopt_simplify");
|
||||
|
||||
const unsigned int lod_index_count = meshopt_simplify(
|
||||
&lod_indices[0], reinterpret_cast<const unsigned int *>(src_mesh.indices.data()), src_mesh.indices.size(),
|
||||
&src_mesh.vertices[0].x, src_mesh.vertices.size(),
|
||||
sizeof(Vector3), target_index_count, p_error_threshold, &lod_error);
|
||||
// TODO See build script about the `zylannmeshopt::` namespace
|
||||
const unsigned int lod_index_count = zylannmeshopt::meshopt_simplify(&lod_indices[0],
|
||||
reinterpret_cast<const unsigned int *>(src_mesh.indices.data()), src_mesh.indices.size(),
|
||||
&src_mesh.vertices[0].x, src_mesh.vertices.size(), sizeof(Vector3), target_index_count,
|
||||
p_error_threshold, &lod_error);
|
||||
|
||||
lod_indices.resize(lod_index_count);
|
||||
}
|
||||
|
@ -111,17 +111,17 @@ static void simplify(const Transvoxel::MeshArrays &src_mesh, Transvoxel::MeshArr
|
|||
remap_indices.clear();
|
||||
remap_indices.resize(src_mesh.vertices.size());
|
||||
|
||||
const unsigned int unique_vertex_count = meshopt_optimizeVertexFetchRemap(
|
||||
const unsigned int unique_vertex_count = zylannmeshopt::meshopt_optimizeVertexFetchRemap(
|
||||
&remap_indices[0], lod_indices.data(), lod_indices.size(), src_mesh.vertices.size());
|
||||
|
||||
remap_vertex_array(src_mesh.vertices, dst_mesh.vertices, remap_indices, unique_vertex_count);
|
||||
remap_vertex_array(src_mesh.normals, dst_mesh.normals, remap_indices, unique_vertex_count);
|
||||
remap_vertex_array(src_mesh.extra, dst_mesh.extra, remap_indices, unique_vertex_count);
|
||||
remap_vertex_array(src_mesh.uv, dst_mesh.uv, remap_indices, unique_vertex_count);
|
||||
remap_vertex_array(src_mesh.lod_data, dst_mesh.lod_data, remap_indices, unique_vertex_count);
|
||||
remap_vertex_array(src_mesh.texturing_data, dst_mesh.texturing_data, remap_indices, unique_vertex_count);
|
||||
|
||||
dst_mesh.indices.resize(lod_indices.size());
|
||||
// TODO Not sure if arguments are correct
|
||||
meshopt_remapIndexBuffer(reinterpret_cast<unsigned int *>(dst_mesh.indices.data()),
|
||||
zylannmeshopt::meshopt_remapIndexBuffer(reinterpret_cast<unsigned int *>(dst_mesh.indices.data()),
|
||||
lod_indices.data(), lod_indices.size(), remap_indices.data());
|
||||
}
|
||||
|
||||
|
@ -148,9 +148,8 @@ void VoxelMesherTransvoxel::build(VoxelMesher::Output &output, const VoxelMesher
|
|||
|
||||
// const uint64_t time_before = OS::get_singleton()->get_ticks_usec();
|
||||
|
||||
Transvoxel::DefaultTextureIndicesData default_texture_indices_data = Transvoxel::build_regular_mesh(
|
||||
voxels, sdf_channel, input.lod, static_cast<Transvoxel::TexturingMode>(_texture_mode), s_cache,
|
||||
s_mesh_arrays);
|
||||
Transvoxel::DefaultTextureIndicesData default_texture_indices_data = Transvoxel::build_regular_mesh(voxels,
|
||||
sdf_channel, input.lod, static_cast<Transvoxel::TexturingMode>(_texture_mode), s_cache, s_mesh_arrays);
|
||||
|
||||
if (s_mesh_arrays.vertices.size() == 0) {
|
||||
// The mesh can be empty
|
||||
|
@ -163,8 +162,8 @@ void VoxelMesherTransvoxel::build(VoxelMesher::Output &output, const VoxelMesher
|
|||
// TODO When voxel texturing is enabled, this will decrease quality a lot.
|
||||
// There is no support yet for taking textures into account when simplifying.
|
||||
// See https://github.com/zeux/meshoptimizer/issues/158
|
||||
simplify(s_mesh_arrays, s_simplified_mesh_arrays,
|
||||
_mesh_optimization_params.target_ratio, _mesh_optimization_params.error_threshold);
|
||||
simplify(s_mesh_arrays, s_simplified_mesh_arrays, _mesh_optimization_params.target_ratio,
|
||||
_mesh_optimization_params.error_threshold);
|
||||
|
||||
fill_surface_arrays(regular_arrays, s_simplified_mesh_arrays);
|
||||
|
||||
|
@ -195,7 +194,7 @@ void VoxelMesherTransvoxel::build(VoxelMesher::Output &output, const VoxelMesher
|
|||
// print_line(String("VoxelMesherTransvoxel spent {0} us").format(varray(time_spent)));
|
||||
|
||||
output.primitive_type = Mesh::PRIMITIVE_TRIANGLES;
|
||||
output.compression_flags = MESH_COMPRESSION_FLAGS;
|
||||
//output.compression_flags = MESH_COMPRESSION_FLAGS;
|
||||
}
|
||||
|
||||
// TODO For testing at the moment
|
||||
|
@ -228,8 +227,8 @@ Ref<ArrayMesh> VoxelMesherTransvoxel::build_transition_mesh(Ref<VoxelBuffer> vox
|
|||
|
||||
Array arrays;
|
||||
fill_surface_arrays(arrays, s_mesh_arrays);
|
||||
mesh.instance();
|
||||
mesh->add_surface_from_arrays(Mesh::PRIMITIVE_TRIANGLES, arrays, Array(), MESH_COMPRESSION_FLAGS);
|
||||
mesh.instantiate();
|
||||
mesh->add_surface_from_arrays(Mesh::PRIMITIVE_TRIANGLES, arrays);
|
||||
return mesh;
|
||||
}
|
||||
|
||||
|
@ -277,8 +276,8 @@ void VoxelMesherTransvoxel::_bind_methods() {
|
|||
|
||||
ClassDB::bind_method(D_METHOD("set_mesh_optimization_enabled", "enabled"),
|
||||
&VoxelMesherTransvoxel::set_mesh_optimization_enabled);
|
||||
ClassDB::bind_method(D_METHOD("is_mesh_optimization_enabled"),
|
||||
&VoxelMesherTransvoxel::is_mesh_optimization_enabled);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("is_mesh_optimization_enabled"), &VoxelMesherTransvoxel::is_mesh_optimization_enabled);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_mesh_optimization_error_threshold", "threshold"),
|
||||
&VoxelMesherTransvoxel::set_mesh_optimization_error_threshold);
|
||||
|
@ -287,21 +286,21 @@ void VoxelMesherTransvoxel::_bind_methods() {
|
|||
|
||||
ClassDB::bind_method(D_METHOD("set_mesh_optimization_target_ratio", "ratio"),
|
||||
&VoxelMesherTransvoxel::set_mesh_optimization_target_ratio);
|
||||
ClassDB::bind_method(D_METHOD("get_mesh_optimization_target_ratio"),
|
||||
&VoxelMesherTransvoxel::get_mesh_optimization_target_ratio);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("get_mesh_optimization_target_ratio"), &VoxelMesherTransvoxel::get_mesh_optimization_target_ratio);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(
|
||||
Variant::INT, "texturing_mode", PROPERTY_HINT_ENUM, "None,4-blend over 16 textures (4 bits)"),
|
||||
ADD_PROPERTY(
|
||||
PropertyInfo(Variant::INT, "texturing_mode", PROPERTY_HINT_ENUM, "None,4-blend over 16 textures (4 bits)"),
|
||||
"set_texturing_mode", "get_texturing_mode");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "mesh_optimization_enabled"),
|
||||
"set_mesh_optimization_enabled", "is_mesh_optimization_enabled");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::BOOL, "mesh_optimization_enabled"), "set_mesh_optimization_enabled",
|
||||
"is_mesh_optimization_enabled");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "mesh_optimization_error_threshold"),
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "mesh_optimization_error_threshold"),
|
||||
"set_mesh_optimization_error_threshold", "get_mesh_optimization_error_threshold");
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::REAL, "mesh_optimization_target_ratio"),
|
||||
"set_mesh_optimization_target_ratio", "get_mesh_optimization_target_ratio");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::FLOAT, "mesh_optimization_target_ratio"), "set_mesh_optimization_target_ratio",
|
||||
"get_mesh_optimization_target_ratio");
|
||||
|
||||
BIND_ENUM_CONSTANT(TEXTURES_NONE);
|
||||
BIND_ENUM_CONSTANT(TEXTURES_BLEND_4_OVER_16);
|
||||
|
|
|
@ -9,17 +9,17 @@ Ref<Mesh> VoxelMesher::build_mesh(Ref<VoxelBuffer> voxels, Array materials) {
|
|||
Input input = { voxels->get_buffer(), 0 };
|
||||
build(output, input);
|
||||
|
||||
if (output.surfaces.empty()) {
|
||||
if (output.surfaces.is_empty()) {
|
||||
return Ref<ArrayMesh>();
|
||||
}
|
||||
|
||||
Ref<ArrayMesh> mesh;
|
||||
mesh.instance();
|
||||
mesh.instantiate();
|
||||
|
||||
int surface_index = 0;
|
||||
for (int i = 0; i < output.surfaces.size(); ++i) {
|
||||
Array surface = output.surfaces[i];
|
||||
if (surface.empty()) {
|
||||
if (surface.is_empty()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -28,7 +28,7 @@ Ref<Mesh> VoxelMesher::build_mesh(Ref<VoxelBuffer> voxels, Array materials) {
|
|||
continue;
|
||||
}
|
||||
|
||||
mesh->add_surface_from_arrays(output.primitive_type, surface, Array(), output.compression_flags);
|
||||
mesh->add_surface_from_arrays(output.primitive_type, surface, Array(), Dictionary(), output.mesh_flags);
|
||||
if (i < materials.size()) {
|
||||
mesh->surface_set_material(surface_index, materials[i]);
|
||||
}
|
||||
|
|
|
@ -21,7 +21,7 @@ public:
|
|||
Vector<Array> surfaces;
|
||||
FixedArray<Vector<Array>, Cube::SIDE_COUNT> transition_surfaces;
|
||||
Mesh::PrimitiveType primitive_type = Mesh::PRIMITIVE_TRIANGLES;
|
||||
unsigned int compression_flags = Mesh::ARRAY_COMPRESS_DEFAULT;
|
||||
unsigned int mesh_flags = 0;
|
||||
Ref<Image> atlas_image;
|
||||
};
|
||||
|
||||
|
@ -39,14 +39,20 @@ public:
|
|||
// If this is not respected, the mesher might produce seams at the edges, or an error
|
||||
unsigned int get_maximum_padding() const;
|
||||
|
||||
virtual Ref<Resource> duplicate(bool p_subresources = false) const { return Ref<Resource>(); }
|
||||
virtual Ref<Resource> duplicate(bool p_subresources = false) const {
|
||||
return Ref<Resource>();
|
||||
}
|
||||
|
||||
// Gets which channels this mesher is able to use in its current configuration.
|
||||
// This is returned as a bitmask where channel index corresponds to bit position.
|
||||
virtual int get_used_channels_mask() const { return 0; }
|
||||
virtual int get_used_channels_mask() const {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Returns true if this mesher supports generating voxel data at multiple levels of detail.
|
||||
virtual bool supports_lod() const { return true; }
|
||||
virtual bool supports_lod() const {
|
||||
return true;
|
||||
}
|
||||
|
||||
protected:
|
||||
static void _bind_methods();
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
#include "util/noise/fast_noise_lite.h"
|
||||
#include "util/noise/fast_noise_lite_gradient.h"
|
||||
|
||||
#include <core/engine.h>
|
||||
#include <core/config/engine.h>
|
||||
|
||||
#ifdef TOOLS_ENABLED
|
||||
#include "editor/editor_plugin.h"
|
||||
|
@ -135,7 +135,7 @@ void register_voxel_types() {
|
|||
// Engine::get_singleton()->add_singleton(Engine::Singleton("SingletonName",singleton_instance));
|
||||
|
||||
PRINT_VERBOSE(String("Size of Object: {0}").format(varray((int)sizeof(Object))));
|
||||
PRINT_VERBOSE(String("Size of Reference: {0}").format(varray((int)sizeof(Reference))));
|
||||
PRINT_VERBOSE(String("Size of RefCounted: {0}").format(varray((int)sizeof(RefCounted))));
|
||||
PRINT_VERBOSE(String("Size of Node: {0}").format(varray((int)sizeof(Node))));
|
||||
PRINT_VERBOSE(String("Size of VoxelBuffer: {0}").format(varray((int)sizeof(VoxelBuffer))));
|
||||
PRINT_VERBOSE(String("Size of VoxelMeshBlock: {0}").format(varray((int)sizeof(VoxelMeshBlock))));
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#ifndef VOXEL_STRUCT_DB_H
|
||||
#define VOXEL_STRUCT_DB_H
|
||||
|
||||
#include <core/error_macros.h>
|
||||
#include <core/error/error_macros.h>
|
||||
#include <vector>
|
||||
|
||||
// Stores uniquely-identified structs in a packed array.
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
#include "voxel_async_dependency_tracker.h"
|
||||
|
||||
#include <core/os/memory.h>
|
||||
#include <scene/main/viewport.h>
|
||||
#include <scene/main/window.h> // Needed for doing `Node *root = SceneTree::get_root()`, Window* is forward-declared
|
||||
#include <thread>
|
||||
|
||||
namespace {
|
||||
|
@ -97,7 +97,7 @@ VoxelServer::VoxelServer() {
|
|||
|
||||
GLOBAL_DEF_RST("voxel/threads/count/ratio_over_max", 0.5f);
|
||||
ProjectSettings::get_singleton()->set_custom_property_info("voxel/threads/count/ratio_over_max",
|
||||
PropertyInfo(Variant::REAL, "voxel/threads/count/ratio_over_max", PROPERTY_HINT_RANGE, "0,1,0.1"));
|
||||
PropertyInfo(Variant::FLOAT, "voxel/threads/count/ratio_over_max", PROPERTY_HINT_RANGE, "0,1,0.1"));
|
||||
|
||||
GLOBAL_DEF_RST("voxel/threads/main/time_budget_ms", 8);
|
||||
ProjectSettings::get_singleton()->set_custom_property_info("voxel/threads/main/time_budget_ms",
|
||||
|
@ -225,7 +225,7 @@ uint32_t VoxelServer::add_volume(VolumeCallbacks callbacks, VolumeType type) {
|
|||
return _world.volumes.create(volume);
|
||||
}
|
||||
|
||||
void VoxelServer::set_volume_transform(uint32_t volume_id, Transform t) {
|
||||
void VoxelServer::set_volume_transform(uint32_t volume_id, Transform3D t) {
|
||||
Volume &volume = _world.volumes.get(volume_id);
|
||||
volume.transform = t;
|
||||
}
|
||||
|
@ -303,15 +303,15 @@ void VoxelServer::invalidate_volume_mesh_requests(uint32_t volume_id) {
|
|||
}
|
||||
|
||||
static inline Vector3i get_block_center(Vector3i pos, int bs, int lod) {
|
||||
return (pos << lod) * bs + Vector3i(bs / 2);
|
||||
return (pos << lod) * bs + Vector3iUtil::create(bs / 2);
|
||||
}
|
||||
|
||||
void VoxelServer::init_priority_dependency(
|
||||
VoxelServer::PriorityDependency &dep, Vector3i block_position, uint8_t lod, const Volume &volume, int block_size) {
|
||||
void VoxelServer::init_priority_dependency(VoxelServer::PriorityDependency &dep, Vector3i block_position, uint8_t lod,
|
||||
const Volume &volume, int block_size) {
|
||||
const Vector3i voxel_pos = get_block_center(block_position, block_size, lod);
|
||||
const float block_radius = (block_size << lod) / 2;
|
||||
dep.shared = _world.shared_priority_dependency;
|
||||
dep.world_position = volume.transform.xform(voxel_pos.to_vec3());
|
||||
dep.world_position = volume.transform.xform(voxel_pos);
|
||||
const float transformed_block_radius =
|
||||
volume.transform.basis.xform(Vector3(block_radius, block_radius, block_radius)).length();
|
||||
|
||||
|
@ -327,9 +327,8 @@ void VoxelServer::init_priority_dependency(
|
|||
case VOLUME_SPARSE_OCTREE:
|
||||
// Distance beyond which it is safe to drop a block without risking to block LOD subdivision.
|
||||
// This does not depend on viewer's view distance, but on LOD precision instead.
|
||||
dep.drop_distance_squared =
|
||||
squared(2.f * transformed_block_radius *
|
||||
get_octree_lod_block_region_extent(volume.octree_lod_distance, block_size));
|
||||
dep.drop_distance_squared = squared(2.f * transformed_block_radius *
|
||||
get_octree_lod_block_region_extent(volume.octree_lod_distance, block_size));
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -395,8 +394,8 @@ void VoxelServer::request_block_load(uint32_t volume_id, Vector3i block_pos, int
|
|||
}
|
||||
}
|
||||
|
||||
void VoxelServer::request_block_generate(uint32_t volume_id, Vector3i block_pos, int lod,
|
||||
std::shared_ptr<VoxelAsyncDependencyTracker> tracker) {
|
||||
void VoxelServer::request_block_generate(
|
||||
uint32_t volume_id, Vector3i block_pos, int lod, std::shared_ptr<VoxelAsyncDependencyTracker> tracker) {
|
||||
//
|
||||
const Volume &volume = _world.volumes.get(volume_id);
|
||||
ERR_FAIL_COND(volume.stream_dependency->generator.is_null());
|
||||
|
@ -428,8 +427,8 @@ void VoxelServer::request_all_stream_blocks(uint32_t volume_id) {
|
|||
_general_thread_pool.enqueue(r);
|
||||
}
|
||||
|
||||
void VoxelServer::request_voxel_block_save(uint32_t volume_id, std::shared_ptr<VoxelBufferInternal> voxels,
|
||||
Vector3i block_pos, int lod) {
|
||||
void VoxelServer::request_voxel_block_save(
|
||||
uint32_t volume_id, std::shared_ptr<VoxelBufferInternal> voxels, Vector3i block_pos, int lod) {
|
||||
//
|
||||
const Volume &volume = _world.volumes.get(volume_id);
|
||||
ERR_FAIL_COND(volume.stream.is_null());
|
||||
|
@ -451,8 +450,8 @@ void VoxelServer::request_voxel_block_save(uint32_t volume_id, std::shared_ptr<V
|
|||
_streaming_thread_pool.enqueue(r);
|
||||
}
|
||||
|
||||
void VoxelServer::request_instance_block_save(uint32_t volume_id, std::unique_ptr<VoxelInstanceBlockData> instances,
|
||||
Vector3i block_pos, int lod) {
|
||||
void VoxelServer::request_instance_block_save(
|
||||
uint32_t volume_id, std::unique_ptr<VoxelInstanceBlockData> instances, Vector3i block_pos, int lod) {
|
||||
const Volume &volume = _world.volumes.get(volume_id);
|
||||
ERR_FAIL_COND(volume.stream.is_null());
|
||||
CRASH_COND(volume.stream_dependency == nullptr);
|
||||
|
@ -491,8 +490,8 @@ void VoxelServer::request_block_generate_from_data_request(BlockDataRequest &src
|
|||
void VoxelServer::request_block_save_from_generate_request(BlockGenerateRequest &src) {
|
||||
// This can be called from another thread
|
||||
|
||||
PRINT_VERBOSE(String("Requesting save of generator output for block {0} lod {1}")
|
||||
.format(varray(src.position.to_vec3(), src.lod)));
|
||||
PRINT_VERBOSE(
|
||||
String("Requesting save of generator output for block {0} lod {1}").format(varray(src.position, src.lod)));
|
||||
|
||||
BlockDataRequest *r = memnew(BlockDataRequest());
|
||||
// TODO Optimization: `r->voxels` doesnt actually need to be shared
|
||||
|
@ -765,8 +764,7 @@ void VoxelServer::BlockDataRequest::run(VoxelTaskContext ctx) {
|
|||
instance_data_request.lod = lod;
|
||||
instance_data_request.position = position;
|
||||
VoxelStream::Result instances_result;
|
||||
stream->load_instance_blocks(
|
||||
Span<VoxelStreamInstanceDataRequest>(&instance_data_request, 1),
|
||||
stream->load_instance_blocks(Span<VoxelStreamInstanceDataRequest>(&instance_data_request, 1),
|
||||
Span<VoxelStream::Result>(&instances_result, 1));
|
||||
|
||||
if (instances_result == VoxelStream::RESULT_ERROR) {
|
||||
|
@ -786,7 +784,8 @@ void VoxelServer::BlockDataRequest::run(VoxelTaskContext ctx) {
|
|||
VoxelBufferInternal voxels_copy;
|
||||
{
|
||||
RWLockRead lock(voxels->get_lock());
|
||||
// TODO Optimization: is that copy necessary? It's possible it was already done while issuing the request
|
||||
// TODO Optimization: is that copy necessary? It's possible it was already done while issuing the
|
||||
// request
|
||||
voxels->duplicate_to(voxels_copy, true);
|
||||
}
|
||||
voxels = nullptr;
|
||||
|
@ -800,7 +799,7 @@ void VoxelServer::BlockDataRequest::run(VoxelTaskContext ctx) {
|
|||
// this should not be null.
|
||||
|
||||
PRINT_VERBOSE(String("Saving instance block {0} lod {1} with data {2}")
|
||||
.format(varray(position.to_vec3(), lod, ptr2s(instances.get()))));
|
||||
.format(varray(position, lod, ptr2s(instances.get()))));
|
||||
|
||||
VoxelStreamInstanceDataRequest instance_data_request;
|
||||
instance_data_request.lod = lod;
|
||||
|
@ -873,11 +872,9 @@ void VoxelServer::BlockDataRequest::apply_result() {
|
|||
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
VoxelServer::AllBlocksDataRequest::AllBlocksDataRequest() {
|
||||
}
|
||||
VoxelServer::AllBlocksDataRequest::AllBlocksDataRequest() {}
|
||||
|
||||
VoxelServer::AllBlocksDataRequest::~AllBlocksDataRequest() {
|
||||
}
|
||||
VoxelServer::AllBlocksDataRequest::~AllBlocksDataRequest() {}
|
||||
|
||||
void VoxelServer::AllBlocksDataRequest::run(VoxelTaskContext ctx) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
|
@ -1059,7 +1056,8 @@ static void copy_block_and_neighbors(Span<std::shared_ptr<VoxelBufferInternal>>
|
|||
std::shared_ptr<VoxelBufferInternal> ¢ral_buffer = blocks[anchor_buffer_index];
|
||||
ERR_FAIL_COND_MSG(central_buffer == nullptr && generator.is_null(), "Central buffer must be valid");
|
||||
if (central_buffer != nullptr) {
|
||||
ERR_FAIL_COND_MSG(central_buffer->get_size().all_members_equal() == false, "Central buffer must be cubic");
|
||||
ERR_FAIL_COND_MSG(
|
||||
Vector3iUtil::all_members_equal(central_buffer->get_size()) == false, "Central buffer must be cubic");
|
||||
}
|
||||
const int mesh_block_size = data_block_size * mesh_block_size_factor;
|
||||
const int padded_mesh_block_size = mesh_block_size + min_padding + max_padding;
|
||||
|
@ -1071,8 +1069,8 @@ static void copy_block_and_neighbors(Span<std::shared_ptr<VoxelBufferInternal>>
|
|||
// dst.set_channel_depth(ci, central_buffer->get_channel_depth(ci));
|
||||
// }
|
||||
|
||||
const Vector3i min_pos = -Vector3i(min_padding);
|
||||
const Vector3i max_pos = Vector3i(mesh_block_size + max_padding);
|
||||
const Vector3i min_pos = -Vector3iUtil::create(min_padding);
|
||||
const Vector3i max_pos = Vector3iUtil::create(mesh_block_size + max_padding);
|
||||
|
||||
std::vector<Box3i> boxes_to_generate;
|
||||
const Box3i mesh_data_box = Box3i::from_min_max(min_pos, max_pos);
|
||||
|
@ -1109,7 +1107,7 @@ static void copy_block_and_neighbors(Span<std::shared_ptr<VoxelBufferInternal>>
|
|||
// but is it just better to do it anyways for every clipped box?
|
||||
VOXEL_PROFILE_SCOPE_NAMED("Box subtract");
|
||||
unsigned int count = boxes_to_generate.size();
|
||||
Box3i block_box = Box3i(offset, Vector3i(data_block_size)).clipped(mesh_data_box);
|
||||
Box3i block_box = Box3i(offset, Vector3iUtil::create(data_block_size)).clipped(mesh_data_box);
|
||||
|
||||
for (unsigned int box_index = 0; box_index < count; ++box_index) {
|
||||
Box3i box = boxes_to_generate[box_index];
|
||||
|
@ -1136,13 +1134,14 @@ static void copy_block_and_neighbors(Span<std::shared_ptr<VoxelBufferInternal>>
|
|||
const Box3i &box = boxes_to_generate[i];
|
||||
//print_line(String("size={0}").format(varray(box.size.to_vec3())));
|
||||
generated_voxels.create(box.size);
|
||||
//generated_voxels.set_voxel_f(2.0f, box.size.x / 2, box.size.y / 2, box.size.z / 2, VoxelBufferInternal::CHANNEL_SDF);
|
||||
//generated_voxels.set_voxel_f(2.0f, box.size.x / 2, box.size.y / 2, box.size.z / 2,
|
||||
//VoxelBufferInternal::CHANNEL_SDF);
|
||||
VoxelBlockRequest r{ generated_voxels, (box.pos << lod_index) + origin_in_voxels, lod_index };
|
||||
generator->generate_block(r);
|
||||
|
||||
for (unsigned int ci = 0; ci < channels_count; ++ci) {
|
||||
dst.copy_from(generated_voxels, Vector3i(), generated_voxels.get_size(),
|
||||
box.pos + Vector3i(min_padding), channels[ci]);
|
||||
box.pos + Vector3iUtil::create(min_padding), channels[ci]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1167,9 +1166,8 @@ void VoxelServer::BlockMeshRequest::run(VoxelTaskContext ctx) {
|
|||
|
||||
// TODO Cache?
|
||||
VoxelBufferInternal voxels;
|
||||
copy_block_and_neighbors(to_span(blocks, blocks_count),
|
||||
voxels, min_padding, max_padding, mesher->get_used_channels_mask(),
|
||||
meshing_dependency->generator, data_block_size, lod, position);
|
||||
copy_block_and_neighbors(to_span(blocks, blocks_count), voxels, min_padding, max_padding,
|
||||
mesher->get_used_channels_mask(), meshing_dependency->generator, data_block_size, lod, position);
|
||||
|
||||
const VoxelMesher::Input input = { voxels, lod };
|
||||
mesher->build(surfaces_output, input);
|
||||
|
@ -1243,7 +1241,7 @@ void VoxelServerUpdater::ensure_existence(SceneTree *st) {
|
|||
if (g_updater_created) {
|
||||
return;
|
||||
}
|
||||
Viewport *root = st->get_root();
|
||||
Node *root = st->get_root();
|
||||
for (int i = 0; i < root->get_child_count(); ++i) {
|
||||
VoxelServerUpdater *u = Object::cast_to<VoxelServerUpdater>(root->get_child(i));
|
||||
if (u != nullptr) {
|
||||
|
|
|
@ -54,10 +54,7 @@ public:
|
|||
};
|
||||
|
||||
struct BlockDataOutput {
|
||||
enum Type {
|
||||
TYPE_LOAD,
|
||||
TYPE_SAVE
|
||||
};
|
||||
enum Type { TYPE_LOAD, TYPE_SAVE };
|
||||
|
||||
Type type;
|
||||
std::shared_ptr<VoxelBufferInternal> voxels;
|
||||
|
@ -104,7 +101,7 @@ public:
|
|||
bool require_visuals = true;
|
||||
};
|
||||
|
||||
enum VolumeType {
|
||||
enum VolumeType { //
|
||||
VOLUME_SPARSE_GRID,
|
||||
VOLUME_SPARSE_OCTREE
|
||||
};
|
||||
|
@ -118,7 +115,7 @@ public:
|
|||
|
||||
// TODO Rename functions to C convention
|
||||
uint32_t add_volume(VolumeCallbacks callbacks, VolumeType type);
|
||||
void set_volume_transform(uint32_t volume_id, Transform t);
|
||||
void set_volume_transform(uint32_t volume_id, Transform3D t);
|
||||
void set_volume_render_block_size(uint32_t volume_id, uint32_t block_size);
|
||||
void set_volume_data_block_size(uint32_t volume_id, uint32_t block_size);
|
||||
void set_volume_stream(uint32_t volume_id, Ref<VoxelStream> stream);
|
||||
|
@ -129,13 +126,13 @@ public:
|
|||
void request_block_mesh(uint32_t volume_id, const BlockMeshInput &input);
|
||||
// TODO Add parameter to skip stream loading
|
||||
void request_block_load(uint32_t volume_id, Vector3i block_pos, int lod, bool request_instances);
|
||||
void request_block_generate(uint32_t volume_id, Vector3i block_pos, int lod,
|
||||
std::shared_ptr<VoxelAsyncDependencyTracker> tracker);
|
||||
void request_block_generate(
|
||||
uint32_t volume_id, Vector3i block_pos, int lod, std::shared_ptr<VoxelAsyncDependencyTracker> tracker);
|
||||
void request_all_stream_blocks(uint32_t volume_id);
|
||||
void request_voxel_block_save(uint32_t volume_id, std::shared_ptr<VoxelBufferInternal> voxels, Vector3i block_pos,
|
||||
int lod);
|
||||
void request_instance_block_save(uint32_t volume_id, std::unique_ptr<VoxelInstanceBlockData> instances,
|
||||
Vector3i block_pos, int lod);
|
||||
void request_voxel_block_save(
|
||||
uint32_t volume_id, std::shared_ptr<VoxelBufferInternal> voxels, Vector3i block_pos, int lod);
|
||||
void request_instance_block_save(
|
||||
uint32_t volume_id, std::unique_ptr<VoxelInstanceBlockData> instances, Vector3i block_pos, int lod);
|
||||
void remove_volume(uint32_t volume_id);
|
||||
bool is_volume_valid(uint32_t volume_id) const;
|
||||
|
||||
|
@ -151,8 +148,7 @@ public:
|
|||
bool is_viewer_requiring_collisions(uint32_t viewer_id) const;
|
||||
bool viewer_exists(uint32_t viewer_id) const;
|
||||
|
||||
template <typename F>
|
||||
inline void for_each_viewer(F f) const {
|
||||
template <typename F> inline void for_each_viewer(F f) const {
|
||||
_world.viewers.for_each_with_id(f);
|
||||
}
|
||||
|
||||
|
@ -246,7 +242,7 @@ private:
|
|||
struct Volume {
|
||||
VolumeType type;
|
||||
VolumeCallbacks callbacks;
|
||||
Transform transform;
|
||||
Transform3D transform;
|
||||
Ref<VoxelStream> stream;
|
||||
Ref<VoxelGenerator> generator;
|
||||
Ref<VoxelMesher> mesher;
|
||||
|
@ -281,17 +277,13 @@ private:
|
|||
float drop_distance_squared;
|
||||
};
|
||||
|
||||
void init_priority_dependency(PriorityDependency &dep, Vector3i block_position, uint8_t lod, const Volume &volume,
|
||||
int block_size);
|
||||
void init_priority_dependency(
|
||||
PriorityDependency &dep, Vector3i block_position, uint8_t lod, const Volume &volume, int block_size);
|
||||
static int get_priority(const PriorityDependency &dep, uint8_t lod_index, float *out_closest_distance_sq);
|
||||
|
||||
class BlockDataRequest : public IVoxelTask {
|
||||
public:
|
||||
enum Type {
|
||||
TYPE_LOAD = 0,
|
||||
TYPE_SAVE,
|
||||
TYPE_FALLBACK_ON_GENERATOR
|
||||
};
|
||||
enum Type { TYPE_LOAD = 0, TYPE_SAVE, TYPE_FALLBACK_ON_GENERATOR };
|
||||
|
||||
BlockDataRequest();
|
||||
~BlockDataRequest();
|
||||
|
@ -411,8 +403,7 @@ private:
|
|||
};
|
||||
|
||||
struct VoxelFileLockerRead {
|
||||
VoxelFileLockerRead(String path) :
|
||||
_path(path) {
|
||||
VoxelFileLockerRead(String path) : _path(path) {
|
||||
VoxelServer::get_singleton()->get_file_locker().lock_read(path);
|
||||
}
|
||||
|
||||
|
@ -424,8 +415,7 @@ struct VoxelFileLockerRead {
|
|||
};
|
||||
|
||||
struct VoxelFileLockerWrite {
|
||||
VoxelFileLockerWrite(String path) :
|
||||
_path(path) {
|
||||
VoxelFileLockerWrite(String path) : _path(path) {
|
||||
VoxelServer::get_singleton()->get_file_locker().lock_write(path);
|
||||
}
|
||||
|
||||
|
|
|
@ -15,8 +15,7 @@
|
|||
// return false;
|
||||
// }
|
||||
|
||||
VoxelThreadPool::VoxelThreadPool() {
|
||||
}
|
||||
VoxelThreadPool::VoxelThreadPool() {}
|
||||
|
||||
VoxelThreadPool::~VoxelThreadPool() {
|
||||
destroy_all_threads();
|
||||
|
@ -32,7 +31,7 @@ void VoxelThreadPool::create_thread(ThreadData &d, uint32_t i) {
|
|||
d.stop = false;
|
||||
d.waiting = false;
|
||||
d.index = i;
|
||||
if (!_name.empty()) {
|
||||
if (!_name.is_empty()) {
|
||||
d.name = String("{0} {1}").format(varray(_name, i));
|
||||
}
|
||||
d.thread.start(thread_func_static, &d);
|
||||
|
@ -117,7 +116,7 @@ void VoxelThreadPool::thread_func_static(void *p_data) {
|
|||
ThreadData &data = *static_cast<ThreadData *>(p_data);
|
||||
VoxelThreadPool &pool = *data.pool;
|
||||
|
||||
if (!data.name.empty()) {
|
||||
if (!data.name.is_empty()) {
|
||||
Thread::set_name(data.name);
|
||||
|
||||
#ifdef VOXEL_PROFILER_ENABLED
|
||||
|
|
|
@ -1,12 +1,10 @@
|
|||
#include "funcs.h"
|
||||
#include "../util/math/box3i.h"
|
||||
|
||||
void copy_3d_region_zxy(
|
||||
Span<uint8_t> dst, Vector3i dst_size, Vector3i dst_min,
|
||||
Span<const uint8_t> src, Vector3i src_size, Vector3i src_min, Vector3i src_max,
|
||||
size_t item_size) {
|
||||
void copy_3d_region_zxy(Span<uint8_t> dst, Vector3i dst_size, Vector3i dst_min, Span<const uint8_t> src,
|
||||
Vector3i src_size, Vector3i src_min, Vector3i src_max, size_t item_size) {
|
||||
//
|
||||
Vector3i::sort_min_max(src_min, src_max);
|
||||
Vector3iUtil::sort_min_max(src_min, src_max);
|
||||
clip_copy_region(src_min, src_max, src_size, dst_min, dst_size);
|
||||
const Vector3i area_size = src_max - src_min;
|
||||
if (area_size.x <= 0 || area_size.y <= 0 || area_size.z <= 0) {
|
||||
|
@ -20,8 +18,8 @@ void copy_3d_region_zxy(
|
|||
Box3i::from_min_max(src_min, src_max).intersects(Box3i::from_min_max(dst_min, dst_min + area_size)),
|
||||
"Copy across the same buffer to an overlapping area is not supported");
|
||||
}
|
||||
ERR_FAIL_COND(area_size.volume() * item_size > dst.size());
|
||||
ERR_FAIL_COND(area_size.volume() * item_size > src.size());
|
||||
ERR_FAIL_COND(Vector3iUtil::get_volume(area_size) * item_size > dst.size());
|
||||
ERR_FAIL_COND(Vector3iUtil::get_volume(area_size) * item_size > src.size());
|
||||
#endif
|
||||
|
||||
if (area_size == src_size && area_size == dst_size) {
|
||||
|
@ -38,8 +36,8 @@ void copy_3d_region_zxy(
|
|||
Vector3i pos;
|
||||
for (pos.z = 0; pos.z < area_size.z; ++pos.z) {
|
||||
pos.x = 0;
|
||||
unsigned int src_ri = Vector3i(src_min + pos).get_zxy_index(src_size) * item_size;
|
||||
unsigned int dst_ri = Vector3i(dst_min + pos).get_zxy_index(dst_size) * item_size;
|
||||
unsigned int src_ri = Vector3iUtil::get_zxy_index(Vector3i(src_min + pos), src_size) * item_size;
|
||||
unsigned int dst_ri = Vector3iUtil::get_zxy_index(Vector3i(dst_min + pos), dst_size) * item_size;
|
||||
for (; pos.x < area_size.x; ++pos.x) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
ERR_FAIL_COND(dst_ri >= dst.size());
|
||||
|
|
|
@ -38,25 +38,20 @@ inline void clip_copy_region(
|
|||
clip_copy_region_coord(src_min.z, src_max.z, src_size.z, dst_min.z, dst_size.z);
|
||||
}
|
||||
|
||||
void copy_3d_region_zxy(
|
||||
Span<uint8_t> dst, Vector3i dst_size, Vector3i dst_min,
|
||||
Span<const uint8_t> src, Vector3i src_size, Vector3i src_min, Vector3i src_max,
|
||||
size_t item_size);
|
||||
void copy_3d_region_zxy(Span<uint8_t> dst, Vector3i dst_size, Vector3i dst_min, Span<const uint8_t> src,
|
||||
Vector3i src_size, Vector3i src_min, Vector3i src_max, size_t item_size);
|
||||
|
||||
template <typename T>
|
||||
inline void copy_3d_region_zxy(
|
||||
Span<T> dst, Vector3i dst_size, Vector3i dst_min,
|
||||
Span<const T> src, Vector3i src_size, Vector3i src_min, Vector3i src_max) {
|
||||
inline void copy_3d_region_zxy(Span<T> dst, Vector3i dst_size, Vector3i dst_min, Span<const T> src, Vector3i src_size,
|
||||
Vector3i src_min, Vector3i src_max) {
|
||||
// The `template` keyword before method name is required when compiling with GCC
|
||||
copy_3d_region_zxy(
|
||||
dst.template reinterpret_cast_to<uint8_t>(), dst_size, dst_min,
|
||||
src.template reinterpret_cast_to<const uint8_t>(), src_size, src_min, src_max,
|
||||
sizeof(T));
|
||||
copy_3d_region_zxy(dst.template reinterpret_cast_to<uint8_t>(), dst_size, dst_min,
|
||||
src.template reinterpret_cast_to<const uint8_t>(), src_size, src_min, src_max, sizeof(T));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
void fill_3d_region_zxy(Span<T> dst, Vector3i dst_size, Vector3i dst_min, Vector3i dst_max, const T value) {
|
||||
Vector3i::sort_min_max(dst_min, dst_max);
|
||||
Vector3iUtil::sort_min_max(dst_min, dst_max);
|
||||
dst_min.x = clamp(dst_min.x, 0, dst_size.x);
|
||||
dst_min.y = clamp(dst_min.y, 0, dst_size.y);
|
||||
dst_min.z = clamp(dst_min.z, 0, dst_size.z);
|
||||
|
@ -70,7 +65,7 @@ void fill_3d_region_zxy(Span<T> dst, Vector3i dst_size, Vector3i dst_min, Vector
|
|||
}
|
||||
|
||||
#ifdef DEBUG_ENABLED
|
||||
ERR_FAIL_COND(area_size.volume() > dst.size());
|
||||
ERR_FAIL_COND(Vector3iUtil::get_volume(area_size) > dst.size());
|
||||
#endif
|
||||
|
||||
if (area_size == dst_size) {
|
||||
|
@ -199,6 +194,7 @@ struct IntBasis {
|
|||
default:
|
||||
CRASH_NOW();
|
||||
}
|
||||
return Vector3i();
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -207,11 +203,11 @@ struct IntBasis {
|
|||
// The array's coordinate convention uses ZXY (index+1 does Y+1).
|
||||
template <typename T>
|
||||
Vector3i transform_3d_array_zxy(Span<const T> src_grid, Span<T> dst_grid, Vector3i src_size, IntBasis basis) {
|
||||
ERR_FAIL_COND_V(!basis.x.is_unit_vector(), src_size);
|
||||
ERR_FAIL_COND_V(!basis.y.is_unit_vector(), src_size);
|
||||
ERR_FAIL_COND_V(!basis.z.is_unit_vector(), src_size);
|
||||
ERR_FAIL_COND_V(src_grid.size() != static_cast<size_t>(src_size.volume()), src_size);
|
||||
ERR_FAIL_COND_V(dst_grid.size() != static_cast<size_t>(src_size.volume()), src_size);
|
||||
ERR_FAIL_COND_V(!Vector3iUtil::is_unit_vector(basis.x), src_size);
|
||||
ERR_FAIL_COND_V(!Vector3iUtil::is_unit_vector(basis.y), src_size);
|
||||
ERR_FAIL_COND_V(!Vector3iUtil::is_unit_vector(basis.z), src_size);
|
||||
ERR_FAIL_COND_V(src_grid.size() != static_cast<size_t>(Vector3iUtil::get_volume(src_size)), src_size);
|
||||
ERR_FAIL_COND_V(dst_grid.size() != static_cast<size_t>(Vector3iUtil::get_volume(src_size)), src_size);
|
||||
|
||||
const int xa = basis.x.x != 0 ? 0 : basis.x.y != 0 ? 1 : 2;
|
||||
const int ya = basis.y.x != 0 ? 0 : basis.y.y != 0 ? 1 : 2;
|
||||
|
|
|
@ -2,8 +2,7 @@
|
|||
#include "../edition/voxel_tool_buffer.h"
|
||||
#include "../util/godot/funcs.h"
|
||||
|
||||
#include <core/func_ref.h>
|
||||
#include <core/image.h>
|
||||
#include <core/io/image.h>
|
||||
|
||||
const char *VoxelBuffer::CHANNEL_ID_HINT_STRING = "Type,Sdf,Color,Indices,Weights,Data5,Data6,Data7";
|
||||
|
||||
|
@ -16,8 +15,7 @@ VoxelBuffer::VoxelBuffer(std::shared_ptr<VoxelBufferInternal> &other) {
|
|||
_buffer = other;
|
||||
}
|
||||
|
||||
VoxelBuffer::~VoxelBuffer() {
|
||||
}
|
||||
VoxelBuffer::~VoxelBuffer() {}
|
||||
|
||||
void VoxelBuffer::clear() {
|
||||
_buffer->clear();
|
||||
|
@ -36,13 +34,10 @@ void VoxelBuffer::copy_channel_from(Ref<VoxelBuffer> other, unsigned int channel
|
|||
_buffer->copy_from(other->get_buffer(), channel);
|
||||
}
|
||||
|
||||
void VoxelBuffer::copy_channel_from_area(Ref<VoxelBuffer> other, Vector3 src_min, Vector3 src_max, Vector3 dst_min,
|
||||
unsigned int channel) {
|
||||
void VoxelBuffer::copy_channel_from_area(
|
||||
Ref<VoxelBuffer> other, Vector3i src_min, Vector3i src_max, Vector3i dst_min, unsigned int channel) {
|
||||
ERR_FAIL_COND(other.is_null());
|
||||
_buffer->copy_from(other->get_buffer(),
|
||||
Vector3i::from_floored(src_min),
|
||||
Vector3i::from_floored(src_max),
|
||||
Vector3i::from_floored(dst_min), channel);
|
||||
_buffer->copy_from(other->get_buffer(), src_min, src_max, dst_min, channel);
|
||||
}
|
||||
|
||||
void VoxelBuffer::fill(uint64_t defval, unsigned int channel_index) {
|
||||
|
@ -69,17 +64,14 @@ VoxelBuffer::Compression VoxelBuffer::get_channel_compression(unsigned int chann
|
|||
return VoxelBuffer::Compression(_buffer->get_channel_compression(channel_index));
|
||||
}
|
||||
|
||||
void VoxelBuffer::downscale_to(Ref<VoxelBuffer> dst, Vector3 src_min, Vector3 src_max, Vector3 dst_min) const {
|
||||
void VoxelBuffer::downscale_to(Ref<VoxelBuffer> dst, Vector3i src_min, Vector3i src_max, Vector3i dst_min) const {
|
||||
ERR_FAIL_COND(dst.is_null());
|
||||
_buffer->downscale_to(dst->get_buffer(),
|
||||
Vector3i::from_floored(src_min),
|
||||
Vector3i::from_floored(src_max),
|
||||
Vector3i::from_floored(dst_min));
|
||||
_buffer->downscale_to(dst->get_buffer(), src_min, src_max, dst_min);
|
||||
}
|
||||
|
||||
Ref<VoxelBuffer> VoxelBuffer::duplicate(bool include_metadata) const {
|
||||
Ref<VoxelBuffer> d;
|
||||
d.instance();
|
||||
d.instantiate();
|
||||
_buffer->duplicate_to(d->get_buffer(), include_metadata);
|
||||
return d;
|
||||
}
|
||||
|
@ -103,29 +95,25 @@ void VoxelBuffer::set_block_metadata(Variant meta) {
|
|||
_buffer->set_block_metadata(meta);
|
||||
}
|
||||
|
||||
void VoxelBuffer::for_each_voxel_metadata(Ref<FuncRef> callback) const {
|
||||
void VoxelBuffer::for_each_voxel_metadata(const Callable &callback) const {
|
||||
ERR_FAIL_COND(callback.is_null());
|
||||
_buffer->for_each_voxel_metadata(callback);
|
||||
}
|
||||
|
||||
void VoxelBuffer::for_each_voxel_metadata_in_area(Ref<FuncRef> callback, Vector3 min_pos, Vector3 max_pos) {
|
||||
void VoxelBuffer::for_each_voxel_metadata_in_area(const Callable &callback, Vector3i min_pos, Vector3i max_pos) {
|
||||
ERR_FAIL_COND(callback.is_null());
|
||||
_buffer->for_each_voxel_metadata_in_area(callback,
|
||||
Box3i::from_min_max(Vector3i::from_floored(min_pos), Vector3i::from_floored(max_pos)));
|
||||
_buffer->for_each_voxel_metadata_in_area(callback, Box3i::from_min_max(min_pos, max_pos));
|
||||
}
|
||||
|
||||
void VoxelBuffer::copy_voxel_metadata_in_area(Ref<VoxelBuffer> src_buffer, Vector3 src_min_pos, Vector3 src_max_pos,
|
||||
Vector3 dst_pos) {
|
||||
void VoxelBuffer::copy_voxel_metadata_in_area(
|
||||
Ref<VoxelBuffer> src_buffer, Vector3i src_min_pos, Vector3i src_max_pos, Vector3i dst_pos) {
|
||||
ERR_FAIL_COND(src_buffer.is_null());
|
||||
_buffer->copy_voxel_metadata_in_area(
|
||||
src_buffer->get_buffer(),
|
||||
Box3i::from_min_max(Vector3i::from_floored(src_min_pos), Vector3i::from_floored(src_max_pos)),
|
||||
Vector3i::from_floored(dst_pos));
|
||||
src_buffer->get_buffer(), Box3i::from_min_max(src_min_pos, src_max_pos), dst_pos);
|
||||
}
|
||||
|
||||
void VoxelBuffer::clear_voxel_metadata_in_area(Vector3 min_pos, Vector3 max_pos) {
|
||||
_buffer->clear_voxel_metadata_in_area(
|
||||
Box3i::from_min_max(Vector3i::from_floored(min_pos), Vector3i::from_floored(max_pos)));
|
||||
void VoxelBuffer::clear_voxel_metadata_in_area(Vector3i min_pos, Vector3i max_pos) {
|
||||
_buffer->clear_voxel_metadata_in_area(Box3i::from_min_max(min_pos, max_pos));
|
||||
}
|
||||
|
||||
void VoxelBuffer::clear_voxel_metadata() {
|
||||
|
@ -145,10 +133,9 @@ void VoxelBuffer::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("get_size_y"), &VoxelBuffer::get_size_y);
|
||||
ClassDB::bind_method(D_METHOD("get_size_z"), &VoxelBuffer::get_size_z);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("set_voxel", "value", "x", "y", "z", "channel"),
|
||||
&VoxelBuffer::set_voxel, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("set_voxel_f", "value", "x", "y", "z", "channel"),
|
||||
&VoxelBuffer::set_voxel_f, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("set_voxel", "value", "x", "y", "z", "channel"), &VoxelBuffer::set_voxel, DEFVAL(0));
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("set_voxel_f", "value", "x", "y", "z", "channel"), &VoxelBuffer::set_voxel_f, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("set_voxel_v", "value", "pos", "channel"), &VoxelBuffer::set_voxel_v, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("get_voxel", "x", "y", "z", "channel"), &VoxelBuffer::get_voxel, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("get_voxel_f", "x", "y", "z", "channel"), &VoxelBuffer::get_voxel_f, DEFVAL(0));
|
||||
|
@ -159,13 +146,11 @@ void VoxelBuffer::_bind_methods() {
|
|||
|
||||
ClassDB::bind_method(D_METHOD("fill", "value", "channel"), &VoxelBuffer::fill, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("fill_f", "value", "channel"), &VoxelBuffer::fill_f, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("fill_area", "value", "min", "max", "channel"),
|
||||
&VoxelBuffer::fill_area, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("fill_area", "value", "min", "max", "channel"), &VoxelBuffer::fill_area, DEFVAL(0));
|
||||
ClassDB::bind_method(D_METHOD("copy_channel_from", "other", "channel"), &VoxelBuffer::copy_channel_from);
|
||||
ClassDB::bind_method(D_METHOD("copy_channel_from_area", "other", "src_min", "src_max", "dst_min", "channel"),
|
||||
&VoxelBuffer::copy_channel_from_area);
|
||||
ClassDB::bind_method(D_METHOD("downscale_to", "dst", "src_min", "src_max", "dst_min"),
|
||||
&VoxelBuffer::downscale_to);
|
||||
ClassDB::bind_method(D_METHOD("downscale_to", "dst", "src_min", "src_max", "dst_min"), &VoxelBuffer::downscale_to);
|
||||
|
||||
ClassDB::bind_method(D_METHOD("is_uniform", "channel"), &VoxelBuffer::is_uniform);
|
||||
// TODO Rename `compress_uniform_channels`
|
||||
|
@ -180,8 +165,8 @@ void VoxelBuffer::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("for_each_voxel_metadata_in_area", "callback", "min_pos", "max_pos"),
|
||||
&VoxelBuffer::for_each_voxel_metadata_in_area);
|
||||
ClassDB::bind_method(D_METHOD("clear_voxel_metadata"), &VoxelBuffer::clear_voxel_metadata);
|
||||
ClassDB::bind_method(D_METHOD("clear_voxel_metadata_in_area", "min_pos", "max_pos"),
|
||||
&VoxelBuffer::clear_voxel_metadata_in_area);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("clear_voxel_metadata_in_area", "min_pos", "max_pos"), &VoxelBuffer::clear_voxel_metadata_in_area);
|
||||
ClassDB::bind_method(
|
||||
D_METHOD("copy_voxel_metadata_in_area", "src_buffer", "src_min_pos", "src_max_pos", "dst_min_pos"),
|
||||
&VoxelBuffer::copy_voxel_metadata_in_area);
|
||||
|
|
|
@ -1,12 +1,11 @@
|
|||
#ifndef VOXEL_BUFFER_H
|
||||
#define VOXEL_BUFFER_H
|
||||
|
||||
#include <memory>
|
||||
#include "voxel_buffer_internal.h"
|
||||
#include <memory>
|
||||
|
||||
class VoxelTool;
|
||||
class Image;
|
||||
class FuncRef;
|
||||
|
||||
// TODO I wish I could call the original class `VoxelBuffer` and expose this other one with that name.
|
||||
// Godot doesn't seem to allow doing that. So the original class had to be named `VoxelBufferInternal`...
|
||||
|
@ -14,8 +13,8 @@ class FuncRef;
|
|||
// Scripts-facing wrapper around VoxelBufferInternal.
|
||||
// It is separate because being a Godot object requires to carry more baggage, and because this data type can
|
||||
// be instanced many times while being rarely accessed directly from scripts, it is a bit better to take this part out
|
||||
class VoxelBuffer : public Reference {
|
||||
GDCLASS(VoxelBuffer, Reference)
|
||||
class VoxelBuffer : public RefCounted {
|
||||
GDCLASS(VoxelBuffer, RefCounted)
|
||||
|
||||
public:
|
||||
enum ChannelId {
|
||||
|
@ -74,39 +73,34 @@ public:
|
|||
|
||||
//inline std::shared_ptr<VoxelBufferInternal> get_buffer_shared() { return _buffer; }
|
||||
|
||||
Vector3 get_size() const {
|
||||
return _buffer->get_size().to_vec3();
|
||||
}
|
||||
Vector3i get_size() const { return _buffer->get_size(); }
|
||||
// TODO Deprecate
|
||||
int get_size_x() const { return _buffer->get_size().x; }
|
||||
int get_size_y() const { return _buffer->get_size().x; }
|
||||
int get_size_z() const { return _buffer->get_size().x; }
|
||||
|
||||
void create(int x, int y, int z) {
|
||||
_buffer->create(x, y, z);
|
||||
}
|
||||
void create(int x, int y, int z) { _buffer->create(x, y, z); }
|
||||
void clear();
|
||||
|
||||
uint64_t get_voxel(int x, int y, int z, unsigned int channel) const {
|
||||
return _buffer->get_voxel(x, y, z, channel);
|
||||
}
|
||||
uint64_t get_voxel(int x, int y, int z, unsigned int channel) const { return _buffer->get_voxel(x, y, z, channel); }
|
||||
void set_voxel(uint64_t value, int x, int y, int z, unsigned int channel) {
|
||||
_buffer->set_voxel(value, x, y, z, channel);
|
||||
}
|
||||
real_t get_voxel_f(int x, int y, int z, unsigned int channel_index) const;
|
||||
void set_voxel_f(real_t value, int x, int y, int z, unsigned int channel_index);
|
||||
|
||||
void set_voxel_v(uint64_t value, Vector3 pos, unsigned int channel_index) {
|
||||
void set_voxel_v(uint64_t value, Vector3i pos, unsigned int channel_index) {
|
||||
_buffer->set_voxel(value, pos.x, pos.y, pos.z, channel_index);
|
||||
}
|
||||
|
||||
void copy_channel_from(Ref<VoxelBuffer> other, unsigned int channel);
|
||||
void copy_channel_from_area(
|
||||
Ref<VoxelBuffer> other, Vector3 src_min, Vector3 src_max, Vector3 dst_min, unsigned int channel);
|
||||
Ref<VoxelBuffer> other, Vector3i src_min, Vector3i src_max, Vector3i dst_min, unsigned int channel);
|
||||
|
||||
void fill(uint64_t defval, unsigned int channel_index = 0);
|
||||
void fill_f(real_t value, unsigned int channel = 0);
|
||||
void fill_area(uint64_t defval, Vector3 min, Vector3 max, unsigned int channel_index) {
|
||||
_buffer->fill_area(defval, Vector3i::from_floored(min), Vector3i::from_floored(max), channel_index);
|
||||
void fill_area(uint64_t defval, Vector3i min, Vector3i max, unsigned int channel_index) {
|
||||
_buffer->fill_area(defval, min, max, channel_index);
|
||||
}
|
||||
|
||||
bool is_uniform(unsigned int channel_index) const;
|
||||
|
@ -114,7 +108,7 @@ public:
|
|||
void compress_uniform_channels();
|
||||
Compression get_channel_compression(unsigned int channel_index) const;
|
||||
|
||||
void downscale_to(Ref<VoxelBuffer> dst, Vector3 src_min, Vector3 src_max, Vector3 dst_min) const;
|
||||
void downscale_to(Ref<VoxelBuffer> dst, Vector3i src_min, Vector3i src_max, Vector3i dst_min) const;
|
||||
|
||||
Ref<VoxelBuffer> duplicate(bool include_metadata) const;
|
||||
|
||||
|
@ -133,19 +127,15 @@ public:
|
|||
Variant get_block_metadata() const { return _buffer->get_block_metadata(); }
|
||||
void set_block_metadata(Variant meta);
|
||||
|
||||
Variant get_voxel_metadata(Vector3 pos) const {
|
||||
return _buffer->get_voxel_metadata(Vector3i::from_floored(pos));
|
||||
}
|
||||
void set_voxel_metadata(Vector3 pos, Variant meta) {
|
||||
_buffer->set_voxel_metadata(Vector3i::from_floored(pos), meta);
|
||||
}
|
||||
void for_each_voxel_metadata(Ref<FuncRef> callback) const;
|
||||
void for_each_voxel_metadata_in_area(Ref<FuncRef> callback, Vector3 min_pos, Vector3 max_pos);
|
||||
Variant get_voxel_metadata(Vector3i pos) const { return _buffer->get_voxel_metadata(pos); }
|
||||
void set_voxel_metadata(Vector3i pos, Variant meta) { _buffer->set_voxel_metadata(pos, meta); }
|
||||
void for_each_voxel_metadata(const Callable &callback) const;
|
||||
void for_each_voxel_metadata_in_area(const Callable &callback, Vector3i min_pos, Vector3i max_pos);
|
||||
void copy_voxel_metadata_in_area(
|
||||
Ref<VoxelBuffer> src_buffer, Vector3 src_min_pos, Vector3 src_max_pos, Vector3 dst_pos);
|
||||
Ref<VoxelBuffer> src_buffer, Vector3i src_min_pos, Vector3i src_max_pos, Vector3i dst_pos);
|
||||
|
||||
void clear_voxel_metadata();
|
||||
void clear_voxel_metadata_in_area(Vector3 min_pos, Vector3 max_pos);
|
||||
void clear_voxel_metadata_in_area(Vector3i min_pos, Vector3i max_pos);
|
||||
|
||||
// Debugging
|
||||
|
||||
|
|
|
@ -8,8 +8,7 @@
|
|||
#include "../util/profiling.h"
|
||||
#include "voxel_buffer_internal.h"
|
||||
|
||||
#include <core/func_ref.h>
|
||||
#include <core/image.h>
|
||||
#include <core/io/image.h>
|
||||
#include <core/io/marshalls.h>
|
||||
#include <core/math/math_funcs.h>
|
||||
#include <string.h>
|
||||
|
@ -350,9 +349,9 @@ void VoxelBufferInternal::fill(uint64_t defval, unsigned int channel_index) {
|
|||
void VoxelBufferInternal::fill_area(uint64_t defval, Vector3i min, Vector3i max, unsigned int channel_index) {
|
||||
ERR_FAIL_INDEX(channel_index, MAX_CHANNELS);
|
||||
|
||||
Vector3i::sort_min_max(min, max);
|
||||
min.clamp_to(Vector3i(0, 0, 0), _size + Vector3i(1, 1, 1));
|
||||
max.clamp_to(Vector3i(0, 0, 0), _size + Vector3i(1, 1, 1));
|
||||
Vector3iUtil::sort_min_max(min, max);
|
||||
min = min.clamp(Vector3i(0, 0, 0), _size);
|
||||
max = max.clamp(Vector3i(0, 0, 0), _size); // `_size` is included
|
||||
const Vector3i area_size = max - min;
|
||||
if (area_size.x == 0 || area_size.y == 0 || area_size.z == 0) {
|
||||
return;
|
||||
|
@ -420,8 +419,7 @@ void VoxelBufferInternal::fill_f(real_t value, unsigned int channel) {
|
|||
fill(real_to_raw_voxel(value, _channels[channel].depth), channel);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
inline bool is_uniform_b(const uint8_t *data, size_t item_count) {
|
||||
template <typename T> inline bool is_uniform_b(const uint8_t *data, size_t item_count) {
|
||||
return is_uniform<T>(reinterpret_cast<const T *>(data), item_count);
|
||||
}
|
||||
|
||||
|
@ -575,7 +573,7 @@ void VoxelBufferInternal::copy_from(const VoxelBufferInternal &other, Vector3i s
|
|||
} else if (channel.defval != other_channel.defval) {
|
||||
// This logic is still required due to how source and destination regions can be specified.
|
||||
// The actual size of the destination area must be determined from the source area, after it has been clipped.
|
||||
Vector3i::sort_min_max(src_min, src_max);
|
||||
Vector3iUtil::sort_min_max(src_min, src_max);
|
||||
clip_copy_region(src_min, src_max, other._size, dst_min, _size);
|
||||
const Vector3i area_size = src_max - src_min;
|
||||
if (area_size.x <= 0 || area_size.y <= 0 || area_size.z <= 0) {
|
||||
|
@ -673,18 +671,18 @@ void VoxelBufferInternal::delete_channel(Channel &channel) {
|
|||
channel.size_in_bytes = 0;
|
||||
}
|
||||
|
||||
void VoxelBufferInternal::downscale_to(VoxelBufferInternal &dst, Vector3i src_min, Vector3i src_max,
|
||||
Vector3i dst_min) const {
|
||||
void VoxelBufferInternal::downscale_to(
|
||||
VoxelBufferInternal &dst, Vector3i src_min, Vector3i src_max, Vector3i dst_min) const {
|
||||
// TODO Align input to multiple of two
|
||||
|
||||
src_min.clamp_to(Vector3i(), _size);
|
||||
src_max.clamp_to(Vector3i(), _size + Vector3i(1));
|
||||
src_min = src_min.clamp(Vector3i(), _size - Vector3i(1, 1, 1));
|
||||
src_max = src_max.clamp(Vector3i(), _size);
|
||||
|
||||
Vector3i dst_max = dst_min + ((src_max - src_min) >> 1);
|
||||
|
||||
// TODO This will be wrong if it overlaps the border?
|
||||
dst_min.clamp_to(Vector3i(), dst._size);
|
||||
dst_max.clamp_to(Vector3i(), dst._size + Vector3i(1));
|
||||
dst_min = dst_min.clamp(Vector3i(), dst._size - Vector3i(1, 1, 1));
|
||||
dst_max = dst_max.clamp(Vector3i(), dst._size);
|
||||
|
||||
for (int channel_index = 0; channel_index < MAX_CHANNELS; ++channel_index) {
|
||||
const Channel &src_channel = _channels[channel_index];
|
||||
|
@ -818,18 +816,19 @@ void VoxelBufferInternal::set_voxel_metadata(Vector3i pos, Variant meta) {
|
|||
}
|
||||
}
|
||||
|
||||
void VoxelBufferInternal::for_each_voxel_metadata(Ref<FuncRef> callback) const {
|
||||
void VoxelBufferInternal::for_each_voxel_metadata(const Callable &callback) const {
|
||||
ERR_FAIL_COND(callback.is_null());
|
||||
const Map<Vector3i, Variant>::Element *elem = _voxel_metadata.front();
|
||||
|
||||
while (elem != nullptr) {
|
||||
const Variant key = elem->key().to_vec3();
|
||||
const Variant key = elem->key();
|
||||
const Variant *args[2] = { &key, &elem->value() };
|
||||
Variant::CallError err;
|
||||
callback->call_func(args, 2, err);
|
||||
Callable::CallError err;
|
||||
Variant retval; // We don't care about the return value, Callable API requires it
|
||||
callback.call(args, 2, retval, err);
|
||||
|
||||
ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK,
|
||||
String("FuncRef call failed at {0}").format(varray(key)));
|
||||
ERR_FAIL_COND_MSG(
|
||||
err.error != Callable::CallError::CALL_OK, String("Callable failed at {0}").format(varray(key)));
|
||||
// TODO Can't provide detailed error because FuncRef doesn't give us access to the object
|
||||
// ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK, false,
|
||||
// Variant::get_call_error_text(callback->get_object(), method_name, nullptr, 0, err));
|
||||
|
@ -838,16 +837,17 @@ void VoxelBufferInternal::for_each_voxel_metadata(Ref<FuncRef> callback) const {
|
|||
}
|
||||
}
|
||||
|
||||
void VoxelBufferInternal::for_each_voxel_metadata_in_area(Ref<FuncRef> callback, Box3i box) const {
|
||||
void VoxelBufferInternal::for_each_voxel_metadata_in_area(const Callable &callback, Box3i box) const {
|
||||
ERR_FAIL_COND(callback.is_null());
|
||||
for_each_voxel_metadata_in_area(box, [&callback](Vector3i pos, Variant meta) {
|
||||
const Variant key = pos.to_vec3();
|
||||
const Variant key = pos;
|
||||
const Variant *args[2] = { &key, &meta };
|
||||
Variant::CallError err;
|
||||
callback->call_func(args, 2, err);
|
||||
Callable::CallError err;
|
||||
Variant retval; // We don't care about the return value, Callable API requires it
|
||||
callback.call(args, 2, retval, err);
|
||||
|
||||
ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK,
|
||||
String("FuncRef call failed at {0}").format(varray(key)));
|
||||
ERR_FAIL_COND_MSG(
|
||||
err.error != Callable::CallError::CALL_OK, String("Callable failed at {0}").format(varray(key)));
|
||||
// TODO Can't provide detailed error because FuncRef doesn't give us access to the object
|
||||
// ERR_FAIL_COND_MSG(err.error != Variant::CallError::CALL_OK, false,
|
||||
// Variant::get_call_error_text(callback->get_object(), method_name, nullptr, 0, err));
|
||||
|
@ -869,8 +869,8 @@ void VoxelBufferInternal::clear_voxel_metadata_in_area(Box3i box) {
|
|||
}
|
||||
}
|
||||
|
||||
void VoxelBufferInternal::copy_voxel_metadata_in_area(const VoxelBufferInternal &src_buffer, Box3i src_box,
|
||||
Vector3i dst_origin) {
|
||||
void VoxelBufferInternal::copy_voxel_metadata_in_area(
|
||||
const VoxelBufferInternal &src_buffer, Box3i src_box, Vector3i dst_origin) {
|
||||
ERR_FAIL_COND(!src_buffer.is_box_valid(src_box));
|
||||
|
||||
const Box3i clipped_src_box = src_box.clipped(Box3i(src_box.pos - dst_origin, _size));
|
||||
|
@ -904,9 +904,9 @@ void VoxelBufferInternal::copy_voxel_metadata(const VoxelBufferInternal &src_buf
|
|||
}
|
||||
|
||||
Ref<Image> VoxelBufferInternal::debug_print_sdf_to_image_top_down() {
|
||||
Image *im = memnew(Image);
|
||||
Ref<Image> im;
|
||||
im.instantiate();
|
||||
im->create(_size.x, _size.z, false, Image::FORMAT_RGB8);
|
||||
im->lock();
|
||||
Vector3i pos;
|
||||
for (pos.z = 0; pos.z < _size.z; ++pos.z) {
|
||||
for (pos.x = 0; pos.x < _size.x; ++pos.x) {
|
||||
|
@ -921,6 +921,5 @@ Ref<Image> VoxelBufferInternal::debug_print_sdf_to_image_top_down() {
|
|||
im->set_pixel(pos.x, pos.z, Color(c, c, c));
|
||||
}
|
||||
}
|
||||
im->unlock();
|
||||
return Ref<Image>(im);
|
||||
return im;
|
||||
}
|
||||
|
|
|
@ -7,14 +7,13 @@
|
|||
#include "../util/span.h"
|
||||
#include "funcs.h"
|
||||
|
||||
#include <core/map.h>
|
||||
#include <core/reference.h>
|
||||
#include <core/vector.h>
|
||||
#include <core/object/ref_counted.h>
|
||||
#include <core/templates/map.h>
|
||||
#include <core/templates/vector.h>
|
||||
#include <limits>
|
||||
|
||||
class VoxelTool;
|
||||
class Image;
|
||||
class FuncRef;
|
||||
|
||||
// Dense voxels data storage.
|
||||
// Organized in channels of configurable bit depth.
|
||||
|
@ -43,13 +42,7 @@ public:
|
|||
COMPRESSION_COUNT
|
||||
};
|
||||
|
||||
enum Depth {
|
||||
DEPTH_8_BIT,
|
||||
DEPTH_16_BIT,
|
||||
DEPTH_32_BIT,
|
||||
DEPTH_64_BIT,
|
||||
DEPTH_COUNT
|
||||
};
|
||||
enum Depth { DEPTH_8_BIT, DEPTH_16_BIT, DEPTH_32_BIT, DEPTH_64_BIT, DEPTH_COUNT };
|
||||
|
||||
static inline uint32_t get_depth_byte_count(VoxelBufferInternal::Depth d) {
|
||||
CRASH_COND(d < 0 || d >= VoxelBufferInternal::DEPTH_COUNT);
|
||||
|
@ -69,6 +62,7 @@ public:
|
|||
default:
|
||||
CRASH_NOW();
|
||||
}
|
||||
return DEPTH_COUNT;
|
||||
}
|
||||
|
||||
static const Depth DEFAULT_CHANNEL_DEPTH = DEPTH_8_BIT;
|
||||
|
@ -109,7 +103,9 @@ public:
|
|||
void clear_channel(unsigned int channel_index, uint64_t clear_value = 0);
|
||||
void clear_channel_f(unsigned int channel_index, real_t clear_value);
|
||||
|
||||
_FORCE_INLINE_ const Vector3i &get_size() const { return _size; }
|
||||
_FORCE_INLINE_ const Vector3i &get_size() const {
|
||||
return _size;
|
||||
}
|
||||
|
||||
void set_default_values(FixedArray<uint64_t, VoxelBufferInternal::MAX_CHANNELS> values);
|
||||
|
||||
|
@ -203,8 +199,7 @@ public:
|
|||
// `action_func` receives a voxel value from the channel, and returns a modified value.
|
||||
// if the returned value is different, it will be applied to the buffer.
|
||||
// Can be used to blend voxels together.
|
||||
template <typename F>
|
||||
inline void read_write_action(Box3i box, unsigned int channel_index, F action_func) {
|
||||
template <typename F> inline void read_write_action(Box3i box, unsigned int channel_index, F action_func) {
|
||||
ERR_FAIL_INDEX(channel_index, MAX_CHANNELS);
|
||||
|
||||
box.clip(Box3i(Vector3i(), _size));
|
||||
|
@ -226,15 +221,14 @@ public:
|
|||
}
|
||||
|
||||
static _FORCE_INLINE_ size_t get_index(const Vector3i pos, const Vector3i size) {
|
||||
return pos.get_zxy_index(size);
|
||||
return Vector3iUtil::get_zxy_index(pos, size);
|
||||
}
|
||||
|
||||
_FORCE_INLINE_ size_t get_index(unsigned int x, unsigned int y, unsigned int z) const {
|
||||
return y + _size.y * (x + _size.x * z); // ZXY index
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
inline void for_each_index_and_pos(const Box3i &box, F f) {
|
||||
template <typename F> inline void for_each_index_and_pos(const Box3i &box, F f) {
|
||||
const Vector3i min_pos = box.pos;
|
||||
const Vector3i max_pos = box.pos + box.size;
|
||||
Vector3i pos;
|
||||
|
@ -259,8 +253,7 @@ public:
|
|||
ERR_FAIL_COND(!Box3i(Vector3i(), _size).contains(box));
|
||||
ERR_FAIL_COND(get_depth_byte_count(channel.depth) != sizeof(Data_T));
|
||||
#endif
|
||||
Span<Data_T> data = Span<uint8_t>(channel.data, channel.size_in_bytes)
|
||||
.reinterpret_cast_to<Data_T>();
|
||||
Span<Data_T> data = Span<uint8_t>(channel.data, channel.size_in_bytes).reinterpret_cast_to<Data_T>();
|
||||
// `&` is required because lambda captures are `const` by default and `mutable` can be used only from C++23
|
||||
for_each_index_and_pos(box, [&data, action_func, offset](size_t i, Vector3i pos) {
|
||||
data.set(i, action_func(pos + offset, data[i]));
|
||||
|
@ -270,8 +263,8 @@ public:
|
|||
|
||||
// void action_func(Vector3i pos, Data0_T &inout_v0, Data1_T &inout_v1)
|
||||
template <typename F, typename Data0_T, typename Data1_T>
|
||||
void write_box_2_template(const Box3i &box, unsigned int channel_index0, unsigned channel_index1, F action_func,
|
||||
Vector3i offset) {
|
||||
void write_box_2_template(
|
||||
const Box3i &box, unsigned int channel_index0, unsigned channel_index1, F action_func, Vector3i offset) {
|
||||
decompress_channel(channel_index0);
|
||||
decompress_channel(channel_index1);
|
||||
Channel &channel0 = _channels[channel_index0];
|
||||
|
@ -281,10 +274,8 @@ public:
|
|||
ERR_FAIL_COND(get_depth_byte_count(channel0.depth) != sizeof(Data0_T));
|
||||
ERR_FAIL_COND(get_depth_byte_count(channel1.depth) != sizeof(Data1_T));
|
||||
#endif
|
||||
Span<Data0_T> data0 = Span<uint8_t>(channel0.data, channel0.size_in_bytes)
|
||||
.reinterpret_cast_to<Data0_T>();
|
||||
Span<Data1_T> data1 = Span<uint8_t>(channel1.data, channel1.size_in_bytes)
|
||||
.reinterpret_cast_to<Data1_T>();
|
||||
Span<Data0_T> data0 = Span<uint8_t>(channel0.data, channel0.size_in_bytes).reinterpret_cast_to<Data0_T>();
|
||||
Span<Data1_T> data1 = Span<uint8_t>(channel1.data, channel1.size_in_bytes).reinterpret_cast_to<Data1_T>();
|
||||
for_each_index_and_pos(box, [action_func, offset, &data0, &data1](size_t i, Vector3i pos) {
|
||||
// TODO The caller must still specify exactly the correct type, maybe some conversion could be used
|
||||
action_func(pos + offset, data0[i], data1[i]);
|
||||
|
@ -293,8 +284,7 @@ public:
|
|||
compress_if_uniform(channel1);
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
void write_box(const Box3i &box, unsigned int channel_index, F action_func, Vector3i offset) {
|
||||
template <typename F> void write_box(const Box3i &box, unsigned int channel_index, F action_func, Vector3i offset) {
|
||||
#ifdef DEBUG_ENABLED
|
||||
ERR_FAIL_INDEX(channel_index, MAX_CHANNELS);
|
||||
#endif
|
||||
|
@ -382,7 +372,7 @@ public:
|
|||
}
|
||||
|
||||
_FORCE_INLINE_ uint64_t get_volume() const {
|
||||
return _size.volume();
|
||||
return Vector3iUtil::get_volume(_size);
|
||||
}
|
||||
|
||||
// TODO Have a template version based on channel depth
|
||||
|
@ -403,13 +393,14 @@ public:
|
|||
|
||||
// Metadata
|
||||
|
||||
Variant get_block_metadata() const { return _block_metadata; }
|
||||
Variant get_block_metadata() const {
|
||||
return _block_metadata;
|
||||
}
|
||||
void set_block_metadata(Variant meta);
|
||||
Variant get_voxel_metadata(Vector3i pos) const;
|
||||
void set_voxel_metadata(Vector3i pos, Variant meta);
|
||||
|
||||
template <typename F>
|
||||
void for_each_voxel_metadata_in_area(Box3i box, F callback) const {
|
||||
template <typename F> void for_each_voxel_metadata_in_area(Box3i box, F callback) const {
|
||||
const Map<Vector3i, Variant>::Element *elem = _voxel_metadata.front();
|
||||
while (elem != nullptr) {
|
||||
if (box.contains(elem->key())) {
|
||||
|
@ -419,20 +410,26 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
void for_each_voxel_metadata(Ref<FuncRef> callback) const;
|
||||
void for_each_voxel_metadata_in_area(Ref<FuncRef> callback, Box3i box) const;
|
||||
void for_each_voxel_metadata(const Callable &callback) const;
|
||||
void for_each_voxel_metadata_in_area(const Callable &callback, Box3i box) const;
|
||||
|
||||
void clear_voxel_metadata();
|
||||
void clear_voxel_metadata_in_area(Box3i box);
|
||||
void copy_voxel_metadata_in_area(const VoxelBufferInternal &src_buffer, Box3i src_box, Vector3i dst_origin);
|
||||
void copy_voxel_metadata(const VoxelBufferInternal &src_buffer);
|
||||
|
||||
const Map<Vector3i, Variant> &get_voxel_metadata() const { return _voxel_metadata; }
|
||||
const Map<Vector3i, Variant> &get_voxel_metadata() const {
|
||||
return _voxel_metadata;
|
||||
}
|
||||
|
||||
// Internal synchronization.
|
||||
// This lock is optional, and used internally at the moment, only in multithreaded areas.
|
||||
inline const RWLock &get_lock() const { return _rw_lock; }
|
||||
inline RWLock &get_lock() { return _rw_lock; }
|
||||
inline const RWLock &get_lock() const {
|
||||
return _rw_lock;
|
||||
}
|
||||
inline RWLock &get_lock() {
|
||||
return _rw_lock;
|
||||
}
|
||||
|
||||
// Debugging
|
||||
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
#ifndef VOXEL_DATA_BLOCK_H
|
||||
#define VOXEL_DATA_BLOCK_H
|
||||
|
||||
#include <memory>
|
||||
#include "../storage/voxel_buffer_internal.h"
|
||||
#include "../util/macros.h"
|
||||
#include "voxel_ref_count.h"
|
||||
#include <memory>
|
||||
|
||||
// Stores loaded voxel data for a chunk of the volume. Mesh and colliders are stored separately.
|
||||
class VoxelDataBlock {
|
||||
|
@ -13,8 +13,8 @@ public:
|
|||
const unsigned int lod_index = 0;
|
||||
VoxelRefCount viewers;
|
||||
|
||||
static VoxelDataBlock *create(Vector3i bpos, std::shared_ptr<VoxelBufferInternal> &buffer, unsigned int size,
|
||||
unsigned int p_lod_index) {
|
||||
static VoxelDataBlock *create(
|
||||
Vector3i bpos, std::shared_ptr<VoxelBufferInternal> &buffer, unsigned int size, unsigned int p_lod_index) {
|
||||
const int bs = size;
|
||||
ERR_FAIL_COND_V(buffer == nullptr, nullptr);
|
||||
ERR_FAIL_COND_V(buffer->get_size() != Vector3i(bs, bs, bs), nullptr);
|
||||
|
@ -50,7 +50,7 @@ public:
|
|||
void set_modified(bool modified) {
|
||||
#ifdef TOOLS_ENABLED
|
||||
if (_modified == false && modified) {
|
||||
PRINT_VERBOSE(String("Marking block {0} as modified").format(varray(position.to_vec3())));
|
||||
PRINT_VERBOSE(String("Marking block {0} as modified").format(varray(position)));
|
||||
}
|
||||
#endif
|
||||
_modified = modified;
|
||||
|
|
|
@ -23,8 +23,7 @@ public:
|
|||
}
|
||||
|
||||
// D action(Vector3i pos, D value)
|
||||
template <typename F>
|
||||
void write_box(Box3i voxel_box, unsigned int channel, F action) {
|
||||
template <typename F> void write_box(Box3i voxel_box, unsigned int channel, F action) {
|
||||
_box_loop(voxel_box, [action, channel](VoxelBufferInternal &voxels, Box3i local_box, Vector3i voxel_offset) {
|
||||
voxels.write_box(local_box, channel, action, voxel_offset);
|
||||
});
|
||||
|
@ -33,10 +32,11 @@ public:
|
|||
// void action(Vector3i pos, D0 &value, D1 &value)
|
||||
template <typename F>
|
||||
void write_box_2(const Box3i &voxel_box, unsigned int channel0, unsigned int channel1, F action) {
|
||||
_box_loop(voxel_box, [action, channel0, channel1](
|
||||
VoxelBufferInternal &voxels, Box3i local_box, Vector3i voxel_offset) {
|
||||
voxels.write_box_2_template<F, uint16_t, uint16_t>(local_box, channel0, channel1, action, voxel_offset);
|
||||
});
|
||||
_box_loop(voxel_box,
|
||||
[action, channel0, channel1](VoxelBufferInternal &voxels, Box3i local_box, Vector3i voxel_offset) {
|
||||
voxels.write_box_2_template<F, uint16_t, uint16_t>(
|
||||
local_box, channel0, channel1, action, voxel_offset);
|
||||
});
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -44,8 +44,7 @@ private:
|
|||
return _block_size;
|
||||
}
|
||||
|
||||
template <typename Block_F>
|
||||
inline void _box_loop(Box3i voxel_box, Block_F block_action) {
|
||||
template <typename Block_F> inline void _box_loop(Box3i voxel_box, Block_F block_action) {
|
||||
Vector3i block_rpos;
|
||||
const Vector3i area_origin_in_voxels = _offset_in_blocks * _block_size;
|
||||
unsigned int index = 0;
|
||||
|
@ -60,7 +59,7 @@ private:
|
|||
}
|
||||
const Vector3i block_origin = block_rpos * _block_size + area_origin_in_voxels;
|
||||
Box3i local_box(voxel_box.pos - block_origin, voxel_box.size);
|
||||
local_box.clip(Box3i(Vector3i(), Vector3i(_block_size)));
|
||||
local_box.clip(Box3i(Vector3i(), Vector3iUtil::create(_block_size)));
|
||||
RWLockWrite wlock(block->get_lock());
|
||||
block_action(*block, local_box, block_origin);
|
||||
}
|
||||
|
@ -75,25 +74,21 @@ private:
|
|||
|
||||
inline void create(Vector3i size, unsigned int block_size) {
|
||||
_blocks.clear();
|
||||
_blocks.resize(size.volume());
|
||||
_blocks.resize(Vector3iUtil::get_volume(size));
|
||||
_size_in_blocks = size;
|
||||
_block_size = block_size;
|
||||
}
|
||||
|
||||
inline bool is_valid_position(Vector3i pos) {
|
||||
pos -= _offset_in_blocks;
|
||||
return pos.x >= 0 &&
|
||||
pos.y >= 0 &&
|
||||
pos.z >= 0 &&
|
||||
pos.x < _size_in_blocks.x &&
|
||||
pos.y < _size_in_blocks.y &&
|
||||
pos.z < _size_in_blocks.z;
|
||||
return pos.x >= 0 && pos.y >= 0 && pos.z >= 0 && pos.x < _size_in_blocks.x && pos.y < _size_in_blocks.y &&
|
||||
pos.z < _size_in_blocks.z;
|
||||
}
|
||||
|
||||
inline void set_block(Vector3i position, std::shared_ptr<VoxelBufferInternal> block) {
|
||||
ERR_FAIL_COND(!is_valid_position(position));
|
||||
position -= _offset_in_blocks;
|
||||
const unsigned int index = position.get_zxy_index(_size_in_blocks);
|
||||
const unsigned int index = Vector3iUtil::get_zxy_index(position, _size_in_blocks);
|
||||
CRASH_COND(index >= _blocks.size());
|
||||
_blocks[index] = block;
|
||||
}
|
||||
|
@ -101,7 +96,7 @@ private:
|
|||
inline VoxelBufferInternal *get_block(Vector3i position) {
|
||||
ERR_FAIL_COND_V(!is_valid_position(position), nullptr);
|
||||
position -= _offset_in_blocks;
|
||||
const unsigned int index = position.get_zxy_index(_size_in_blocks);
|
||||
const unsigned int index = Vector3iUtil::get_zxy_index(position, _size_in_blocks);
|
||||
CRASH_COND(index >= _blocks.size());
|
||||
return _blocks[index].get();
|
||||
}
|
||||
|
|
|
@ -136,7 +136,8 @@ const VoxelDataBlock *VoxelDataMap::get_block(Vector3i bpos) const {
|
|||
#ifdef DEBUG_ENABLED
|
||||
CRASH_COND(i >= _blocks.size());
|
||||
#endif
|
||||
// TODO This function can't cache _last_accessed_block, because it's const, so repeated accesses are hashing again...
|
||||
// TODO This function can't cache _last_accessed_block, because it's const, so repeated accesses are hashing
|
||||
// again...
|
||||
const VoxelDataBlock *block = _blocks[i];
|
||||
CRASH_COND(block == nullptr); // The map should not contain null blocks
|
||||
return block;
|
||||
|
@ -177,8 +178,8 @@ void VoxelDataMap::remove_block_internal(Vector3i bpos, unsigned int index) {
|
|||
}
|
||||
}
|
||||
|
||||
VoxelDataBlock *VoxelDataMap::set_block_buffer(Vector3i bpos, std::shared_ptr<VoxelBufferInternal> &buffer,
|
||||
bool overwrite) {
|
||||
VoxelDataBlock *VoxelDataMap::set_block_buffer(
|
||||
Vector3i bpos, std::shared_ptr<VoxelBufferInternal> &buffer, bool overwrite) {
|
||||
ERR_FAIL_COND_V(buffer == nullptr, nullptr);
|
||||
VoxelDataBlock *block = get_block(bpos);
|
||||
if (block == nullptr) {
|
||||
|
@ -188,7 +189,7 @@ VoxelDataBlock *VoxelDataMap::set_block_buffer(Vector3i bpos, std::shared_ptr<Vo
|
|||
block->set_voxels(buffer);
|
||||
} else {
|
||||
PRINT_VERBOSE(String("Discarded block {0} lod {1}, there was already data and overwriting is not enabled")
|
||||
.format(varray(bpos.to_vec3(), _lod_index)));
|
||||
.format(varray(bpos, _lod_index)));
|
||||
}
|
||||
return block;
|
||||
}
|
||||
|
@ -237,15 +238,12 @@ void VoxelDataMap::copy(Vector3i min_pos, VoxelBufferInternal &dst_buffer, unsig
|
|||
const uint8_t channel = channels[ci];
|
||||
dst_buffer.set_channel_depth(channel, src_buffer.get_channel_depth(channel));
|
||||
// Note: copy_from takes care of clamping the area if it's on an edge
|
||||
dst_buffer.copy_from(src_buffer,
|
||||
min_pos - src_block_origin,
|
||||
src_buffer.get_size(),
|
||||
Vector3i(),
|
||||
channel);
|
||||
dst_buffer.copy_from(
|
||||
src_buffer, min_pos - src_block_origin, src_buffer.get_size(), Vector3i(), channel);
|
||||
}
|
||||
|
||||
} else if (gen_func != nullptr) {
|
||||
const Box3i box = Box3i(bpos << _block_size_pow2, Vector3i(_block_size))
|
||||
const Box3i box = Box3i(bpos << _block_size_pow2, Vector3iUtil::create(_block_size))
|
||||
.clipped(Box3i(min_pos, dst_buffer.get_size()));
|
||||
|
||||
// TODO Format?
|
||||
|
@ -262,11 +260,8 @@ void VoxelDataMap::copy(Vector3i min_pos, VoxelBufferInternal &dst_buffer, unsig
|
|||
const uint8_t channel = channels[ci];
|
||||
// For now, inexistent blocks default to hardcoded defaults, corresponding to "empty space".
|
||||
// If we want to change this, we may have to add an API for that.
|
||||
dst_buffer.fill_area(
|
||||
_default_voxel[channel],
|
||||
src_block_origin - min_pos,
|
||||
src_block_origin - min_pos + block_size_v,
|
||||
channel);
|
||||
dst_buffer.fill_area(_default_voxel[channel], src_block_origin - min_pos,
|
||||
src_block_origin - min_pos + block_size_v, channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -320,11 +315,8 @@ void VoxelDataMap::paste(Vector3i min_pos, VoxelBufferInternal &src_buffer, unsi
|
|||
});
|
||||
|
||||
} else {
|
||||
dst_buffer.copy_from(src_buffer,
|
||||
Vector3i(),
|
||||
src_buffer.get_size(),
|
||||
min_pos - dst_block_origin,
|
||||
channel);
|
||||
dst_buffer.copy_from(
|
||||
src_buffer, Vector3i(), src_buffer.get_size(), min_pos - dst_block_origin, channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -355,9 +347,7 @@ int VoxelDataMap::get_block_count() const {
|
|||
|
||||
bool VoxelDataMap::is_area_fully_loaded(const Box3i voxels_box) const {
|
||||
Box3i block_box = voxels_box.downscaled(get_block_size());
|
||||
return block_box.all_cells_match([this](Vector3i pos) {
|
||||
return has_block(pos);
|
||||
});
|
||||
return block_box.all_cells_match([this](Vector3i pos) { return has_block(pos); });
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -382,8 +372,8 @@ void preload_box(VoxelDataLodMap &data, Box3i voxel_box, VoxelGenerator *generat
|
|||
for (unsigned int lod_index = 0; lod_index < data.lod_count; ++lod_index) {
|
||||
const Box3i block_box = voxel_box.downscaled(data_block_size << lod_index);
|
||||
|
||||
PRINT_VERBOSE(String("Preloading box {0} at lod {1} synchronously")
|
||||
.format(varray(block_box.to_string(), lod_index)));
|
||||
PRINT_VERBOSE(
|
||||
String("Preloading box {0} at lod {1} synchronously").format(varray(block_box.to_string(), lod_index)));
|
||||
|
||||
VoxelDataLodMap::Lod &data_lod = data.lods[lod_index];
|
||||
const unsigned int prev_size = todo.size();
|
||||
|
@ -401,7 +391,7 @@ void preload_box(VoxelDataLodMap &data, Box3i voxel_box, VoxelGenerator *generat
|
|||
count_per_lod.push_back(todo.size() - prev_size);
|
||||
}
|
||||
|
||||
const Vector3i block_size(data_block_size);
|
||||
const Vector3i block_size = Vector3iUtil::create(data_block_size);
|
||||
|
||||
// Generate
|
||||
for (unsigned int i = 0; i < todo.size(); ++i) {
|
||||
|
@ -410,11 +400,8 @@ void preload_box(VoxelDataLodMap &data, Box3i voxel_box, VoxelGenerator *generat
|
|||
task.voxels->create(block_size);
|
||||
// TODO Format?
|
||||
if (generator != nullptr) {
|
||||
VoxelBlockRequest r{
|
||||
*task.voxels,
|
||||
task.block_pos * (data_block_size << task.lod_index),
|
||||
int(task.lod_index)
|
||||
};
|
||||
VoxelBlockRequest r{ *task.voxels, task.block_pos * (data_block_size << task.lod_index),
|
||||
int(task.lod_index) };
|
||||
generator->generate_block(r);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -24,10 +24,7 @@ public:
|
|||
}
|
||||
|
||||
_FORCE_INLINE_ Vector3i to_local(Vector3i pos) const {
|
||||
return Vector3i(
|
||||
pos.x & _block_size_mask,
|
||||
pos.y & _block_size_mask,
|
||||
pos.z & _block_size_mask);
|
||||
return Vector3i(pos.x & _block_size_mask, pos.y & _block_size_mask, pos.z & _block_size_mask);
|
||||
}
|
||||
|
||||
// Converts block coodinates into voxel coordinates
|
||||
|
@ -40,9 +37,15 @@ public:
|
|||
|
||||
void create(unsigned int block_size_po2, int lod_index);
|
||||
|
||||
_FORCE_INLINE_ unsigned int get_block_size() const { return _block_size; }
|
||||
_FORCE_INLINE_ unsigned int get_block_size_pow2() const { return _block_size_pow2; }
|
||||
_FORCE_INLINE_ unsigned int get_block_size_mask() const { return _block_size_mask; }
|
||||
_FORCE_INLINE_ unsigned int get_block_size() const {
|
||||
return _block_size;
|
||||
}
|
||||
_FORCE_INLINE_ unsigned int get_block_size_pow2() const {
|
||||
return _block_size_pow2;
|
||||
}
|
||||
_FORCE_INLINE_ unsigned int get_block_size_mask() const {
|
||||
return _block_size_mask;
|
||||
}
|
||||
|
||||
void set_lod_index(int lod_index);
|
||||
unsigned int get_lod_index() const;
|
||||
|
@ -68,15 +71,14 @@ public:
|
|||
uint64_t mask_value, bool create_new_blocks);
|
||||
|
||||
// Moves the given buffer into a block of the map. The buffer is referenced, no copy is made.
|
||||
VoxelDataBlock *set_block_buffer(Vector3i bpos, std::shared_ptr<VoxelBufferInternal> &buffer,
|
||||
bool overwrite = true);
|
||||
VoxelDataBlock *set_block_buffer(
|
||||
Vector3i bpos, std::shared_ptr<VoxelBufferInternal> &buffer, bool overwrite = true);
|
||||
|
||||
struct NoAction {
|
||||
inline void operator()(VoxelDataBlock *block) {}
|
||||
};
|
||||
|
||||
template <typename Action_T>
|
||||
void remove_block(Vector3i bpos, Action_T pre_delete) {
|
||||
template <typename Action_T> void remove_block(Vector3i bpos, Action_T pre_delete) {
|
||||
auto it = _blocks_map.find(bpos);
|
||||
if (it != _blocks_map.end()) {
|
||||
const unsigned int i = it->second;
|
||||
|
@ -102,16 +104,14 @@ public:
|
|||
int get_block_count() const;
|
||||
|
||||
// TODO Rename for_each_block
|
||||
template <typename Op_T>
|
||||
inline void for_all_blocks(Op_T op) {
|
||||
template <typename Op_T> inline void for_all_blocks(Op_T op) {
|
||||
for (auto it = _blocks.begin(); it != _blocks.end(); ++it) {
|
||||
op(*it);
|
||||
}
|
||||
}
|
||||
|
||||
// TODO Rename for_each_block
|
||||
template <typename Op_T>
|
||||
inline void for_all_blocks(Op_T op) const {
|
||||
template <typename Op_T> inline void for_all_blocks(Op_T op) const {
|
||||
for (auto it = _blocks.begin(); it != _blocks.end(); ++it) {
|
||||
op(*it);
|
||||
}
|
||||
|
@ -119,8 +119,7 @@ public:
|
|||
|
||||
bool is_area_fully_loaded(const Box3i voxels_box) const;
|
||||
|
||||
template <typename F>
|
||||
inline void write_box(const Box3i &voxel_box, unsigned int channel, F action) {
|
||||
template <typename F> inline void write_box(const Box3i &voxel_box, unsigned int channel, F action) {
|
||||
write_box(voxel_box, channel, action, [](const VoxelBufferInternal &, const Vector3i &) {});
|
||||
}
|
||||
|
||||
|
@ -153,20 +152,21 @@ public:
|
|||
template <typename F, typename G>
|
||||
void write_box_2(const Box3i &voxel_box, unsigned int channel0, unsigned int channel1, F action, G gen_func) {
|
||||
const Box3i block_box = voxel_box.downscaled(get_block_size());
|
||||
const Vector3i block_size(get_block_size());
|
||||
block_box.for_each_cell_zxy([this, action, voxel_box, channel0, channel1, block_size, gen_func](Vector3i block_pos) {
|
||||
VoxelDataBlock *block = get_block(block_pos);
|
||||
if (block == nullptr) {
|
||||
block = create_default_block(block_pos);
|
||||
gen_func(block->get_voxels(), block_pos << get_block_size_pow2());
|
||||
}
|
||||
const Vector3i block_origin = block_to_voxel(block_pos);
|
||||
Box3i local_box(voxel_box.pos - block_origin, voxel_box.size);
|
||||
local_box.clip(Box3i(Vector3i(), block_size));
|
||||
RWLockWrite wlock(block->get_voxels().get_lock());
|
||||
block->get_voxels().write_box_2_template<F, uint16_t, uint16_t>(
|
||||
local_box, channel0, channel1, action, block_origin);
|
||||
});
|
||||
const Vector3i block_size = Vector3iUtil::create(get_block_size());
|
||||
block_box.for_each_cell_zxy(
|
||||
[this, action, voxel_box, channel0, channel1, block_size, gen_func](Vector3i block_pos) {
|
||||
VoxelDataBlock *block = get_block(block_pos);
|
||||
if (block == nullptr) {
|
||||
block = create_default_block(block_pos);
|
||||
gen_func(block->get_voxels(), block_pos << get_block_size_pow2());
|
||||
}
|
||||
const Vector3i block_origin = block_to_voxel(block_pos);
|
||||
Box3i local_box(voxel_box.pos - block_origin, voxel_box.size);
|
||||
local_box.clip(Box3i(Vector3i(), block_size));
|
||||
RWLockWrite wlock(block->get_voxels().get_lock());
|
||||
block->get_voxels().write_box_2_template<F, uint16_t, uint16_t>(
|
||||
local_box, channel0, channel1, action, block_origin);
|
||||
});
|
||||
}
|
||||
|
||||
private:
|
||||
|
|
|
@ -3,8 +3,8 @@
|
|||
#include "../util/profiling.h"
|
||||
|
||||
#include <core/os/os.h>
|
||||
#include <core/print_string.h>
|
||||
#include <core/variant.h>
|
||||
#include <core/string/print_string.h>
|
||||
#include <core/variant/variant.h>
|
||||
|
||||
namespace {
|
||||
VoxelMemoryPool *g_memory_pool = nullptr;
|
||||
|
@ -27,8 +27,7 @@ VoxelMemoryPool *VoxelMemoryPool::get_singleton() {
|
|||
return g_memory_pool;
|
||||
}
|
||||
|
||||
VoxelMemoryPool::VoxelMemoryPool() {
|
||||
}
|
||||
VoxelMemoryPool::VoxelMemoryPool() {}
|
||||
|
||||
VoxelMemoryPool::~VoxelMemoryPool() {
|
||||
#ifdef TOOLS_ENABLED
|
||||
|
@ -145,8 +144,7 @@ void VoxelMemoryPool::debug_print() {
|
|||
Pool &pool = _pot_pools[pot];
|
||||
MutexLock lock(pool.mutex);
|
||||
print_line(String("Pool {0}: {1} blocks (capacity {2})")
|
||||
.format(varray(pot,
|
||||
SIZE_T_TO_VARIANT(pool.blocks.size()),
|
||||
.format(varray(pot, SIZE_T_TO_VARIANT(pool.blocks.size()),
|
||||
SIZE_T_TO_VARIANT(pool.blocks.capacity()))));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
#ifndef VOXEL_VIEWER_REF_COUNT_H
|
||||
#define VOXEL_VIEWER_REF_COUNT_H
|
||||
|
||||
#include <core/error/error_macros.h>
|
||||
|
||||
class VoxelRefCount {
|
||||
public:
|
||||
inline void add() {
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#include "../util/serialization.h"
|
||||
|
||||
#include <core/io/file_access_memory.h>
|
||||
#include <core/variant.h>
|
||||
#include <core/variant/variant.h>
|
||||
#include <limits>
|
||||
|
||||
namespace VoxelCompressedData {
|
||||
|
@ -35,10 +35,7 @@ bool decompress(Span<const uint8_t> src, std::vector<uint8_t> &dst) {
|
|||
dst.resize(decompressed_size);
|
||||
|
||||
const uint32_t actually_decompressed_size = LZ4_decompress_safe(
|
||||
(const char *)src.data() + header_size,
|
||||
(char *)dst.data(),
|
||||
src.size() - header_size,
|
||||
dst.size());
|
||||
(const char *)src.data() + header_size, (char *)dst.data(), src.size() - header_size, dst.size());
|
||||
|
||||
ERR_FAIL_COND_V_MSG(actually_decompressed_size < 0, false,
|
||||
String("LZ4 decompression error {0}").format(varray(actually_decompressed_size)));
|
||||
|
@ -80,10 +77,7 @@ bool compress(Span<const uint8_t> src, std::vector<uint8_t> &dst, Compression co
|
|||
dst.resize(header_size + LZ4_compressBound(src.size()));
|
||||
|
||||
const uint32_t compressed_size = LZ4_compress_default(
|
||||
(const char *)src.data(),
|
||||
(char *)dst.data() + header_size,
|
||||
src.size(),
|
||||
dst.size() - header_size);
|
||||
(const char *)src.data(), (char *)dst.data() + header_size, src.size(), dst.size() - header_size);
|
||||
|
||||
ERR_FAIL_COND_V(compressed_size < 0, false);
|
||||
ERR_FAIL_COND_V(compressed_size == 0, false);
|
||||
|
|
|
@ -23,7 +23,8 @@ const char *to_string(VoxelFileResult res) {
|
|||
}
|
||||
}
|
||||
|
||||
VoxelFileResult check_magic_and_version(FileAccess *f, uint8_t expected_version, const char *expected_magic, uint8_t &out_version) {
|
||||
VoxelFileResult check_magic_and_version(
|
||||
FileAccess *f, uint8_t expected_version, const char *expected_magic, uint8_t &out_version) {
|
||||
uint8_t magic[5] = { '\0' };
|
||||
int count = f->get_buffer(magic, 4);
|
||||
if (count != 4) {
|
||||
|
@ -77,7 +78,7 @@ void insert_bytes(FileAccess *f, size_t count, size_t temp_chunk_size) {
|
|||
CRASH_COND(f == nullptr);
|
||||
CRASH_COND(temp_chunk_size == 0);
|
||||
|
||||
const size_t prev_file_len = f->get_len();
|
||||
const size_t prev_file_len = f->get_length();
|
||||
const size_t insert_pos = f->get_position();
|
||||
|
||||
// Make the file larger
|
||||
|
@ -90,7 +91,7 @@ void insert_bytes(FileAccess *f, size_t count, size_t temp_chunk_size) {
|
|||
size_t bytes_to_move = initial_bytes_to_move;
|
||||
std::vector<uint8_t> temp;
|
||||
size_t src_pos = prev_file_len;
|
||||
size_t dst_pos = f->get_len();
|
||||
size_t dst_pos = f->get_length();
|
||||
|
||||
// Copy chunks of the file at a later position, from last to first.
|
||||
// The last copied chunk can be smaller.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
#define FILE_UTILS_H
|
||||
|
||||
#include "../util/math/vector3i.h"
|
||||
#include <core/os/dir_access.h>
|
||||
#include <core/os/file_access.h>
|
||||
#include <core/io/dir_access.h>
|
||||
#include <core/io/file_access.h>
|
||||
|
||||
inline Vector3i get_vec3u8(FileAccess *f) {
|
||||
Vector3i v;
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#include "../constants/voxel_constants.h"
|
||||
#include "../util/math/funcs.h"
|
||||
#include "../util/serialization.h"
|
||||
#include <core/variant.h>
|
||||
#include <core/variant/variant.h>
|
||||
|
||||
namespace {
|
||||
const uint32_t TRAILING_MAGIC = 0x900df00d;
|
||||
|
@ -28,7 +28,7 @@ struct CompressedQuaternion4b {
|
|||
uint8_t z;
|
||||
uint8_t w;
|
||||
|
||||
static CompressedQuaternion4b from_quat(Quat q) {
|
||||
static CompressedQuaternion4b from_quaternion(Quaternion q) {
|
||||
CompressedQuaternion4b c;
|
||||
c.x = norm_to_u8(q.x);
|
||||
c.y = norm_to_u8(q.y);
|
||||
|
@ -37,8 +37,8 @@ struct CompressedQuaternion4b {
|
|||
return c;
|
||||
}
|
||||
|
||||
Quat to_quat() const {
|
||||
Quat q;
|
||||
Quaternion to_quaternion() const {
|
||||
Quaternion q;
|
||||
q.x = u8_to_norm(x);
|
||||
q.y = u8_to_norm(y);
|
||||
q.z = u8_to_norm(z);
|
||||
|
@ -97,8 +97,8 @@ bool serialize_instance_block_data(const VoxelInstanceBlockData &src, std::vecto
|
|||
const float scale = instance.transform.get_basis().get_scale().y;
|
||||
w.store_8(static_cast<uint8_t>(scale_norm_scale * (scale - scale_min) * 0xff));
|
||||
|
||||
const Quat q = instance.transform.get_basis().get_rotation_quat();
|
||||
const CompressedQuaternion4b cq = CompressedQuaternion4b::from_quat(q);
|
||||
const Quaternion q = instance.transform.get_basis().get_rotation_quaternion();
|
||||
const CompressedQuaternion4b cq = CompressedQuaternion4b::from_quaternion(q);
|
||||
w.store_8(cq.x);
|
||||
w.store_8(cq.y);
|
||||
w.store_8(cq.z);
|
||||
|
@ -153,10 +153,10 @@ bool deserialize_instance_block_data(VoxelInstanceBlockData &dst, Span<const uin
|
|||
cq.y = r.get_8();
|
||||
cq.z = r.get_8();
|
||||
cq.w = r.get_8();
|
||||
const Quat q = cq.to_quat();
|
||||
const Quaternion q = cq.to_quaternion();
|
||||
|
||||
VoxelInstanceBlockData::InstanceData &instance = layer.instances[j];
|
||||
instance.transform = Transform(Basis(q).scaled(Vector3(s, s, s)), Vector3(x, y, z));
|
||||
instance.transform = Transform3D(Basis(q).scaled(Vector3(s, s, s)), Vector3(x, y, z));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -2,12 +2,12 @@
|
|||
#define VOXEL_INSTANCE_DATA_H
|
||||
|
||||
#include "../util/span.h"
|
||||
#include <core/math/transform.h>
|
||||
#include <core/math/transform_3d.h>
|
||||
|
||||
// Stores data to pass around until it either gets saved or turned into actual instances
|
||||
struct VoxelInstanceBlockData {
|
||||
struct InstanceData {
|
||||
Transform transform;
|
||||
Transform3D transform;
|
||||
};
|
||||
|
||||
enum VoxelInstanceFormat {
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
#include "../../util/macros.h"
|
||||
#include "../../util/profiling.h"
|
||||
#include "../file_utils.h"
|
||||
#include <core/os/file_access.h>
|
||||
#include <core/io/file_access.h>
|
||||
#include <algorithm>
|
||||
|
||||
namespace {
|
||||
|
@ -35,17 +35,17 @@ bool VoxelRegionFormat::validate() const {
|
|||
for (unsigned int i = 0; i < channel_depths.size(); ++i) {
|
||||
bytes_per_block += VoxelBufferInternal::get_depth_bit_count(channel_depths[i]) / 8;
|
||||
}
|
||||
bytes_per_block *= Vector3i(1 << block_size_po2).volume();
|
||||
bytes_per_block *= Vector3iUtil::get_volume(Vector3iUtil::create(1 << block_size_po2));
|
||||
const size_t sectors_per_block = (bytes_per_block - 1) / sector_size + 1;
|
||||
ERR_FAIL_COND_V(sectors_per_block > VoxelRegionBlockInfo::MAX_SECTOR_COUNT, false);
|
||||
const size_t max_potential_sectors = region_size.volume() * sectors_per_block;
|
||||
const size_t max_potential_sectors = Vector3iUtil::get_volume(region_size) * sectors_per_block;
|
||||
ERR_FAIL_COND_V(max_potential_sectors > VoxelRegionBlockInfo::MAX_SECTOR_INDEX, false);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool VoxelRegionFormat::verify_block(const VoxelBufferInternal &block) const {
|
||||
ERR_FAIL_COND_V(block.get_size() != Vector3i(1 << block_size_po2), false);
|
||||
ERR_FAIL_COND_V(block.get_size() != Vector3iUtil::create(1 << block_size_po2), false);
|
||||
for (unsigned int i = 0; i < VoxelBufferInternal::MAX_CHANNELS; ++i) {
|
||||
ERR_FAIL_COND_V(block.get_channel_depth(i) != channel_depths[i], false);
|
||||
}
|
||||
|
@ -55,9 +55,8 @@ bool VoxelRegionFormat::verify_block(const VoxelBufferInternal &block) const {
|
|||
static uint32_t get_header_size_v3(const VoxelRegionFormat &format) {
|
||||
// Which file offset blocks data is starting
|
||||
// magic + version + blockinfos
|
||||
return MAGIC_AND_VERSION_SIZE + FIXED_HEADER_DATA_SIZE +
|
||||
(format.has_palette ? PALETTE_SIZE_IN_BYTES : 0) +
|
||||
format.region_size.volume() * sizeof(VoxelRegionBlockInfo);
|
||||
return MAGIC_AND_VERSION_SIZE + FIXED_HEADER_DATA_SIZE + (format.has_palette ? PALETTE_SIZE_IN_BYTES : 0) +
|
||||
Vector3iUtil::get_volume(format.region_size) * sizeof(VoxelRegionBlockInfo);
|
||||
}
|
||||
|
||||
static bool save_header(FileAccess *f, uint8_t version, const VoxelRegionFormat &format,
|
||||
|
@ -95,8 +94,8 @@ static bool save_header(FileAccess *f, uint8_t version, const VoxelRegionFormat
|
|||
}
|
||||
|
||||
// TODO Deal with endianess
|
||||
f->store_buffer(reinterpret_cast<const uint8_t *>(block_infos.data()),
|
||||
block_infos.size() * sizeof(VoxelRegionBlockInfo));
|
||||
f->store_buffer(
|
||||
reinterpret_cast<const uint8_t *>(block_infos.data()), block_infos.size() * sizeof(VoxelRegionBlockInfo));
|
||||
|
||||
size_t blocks_begin_offset = f->get_position();
|
||||
#ifdef DEBUG_ENABLED
|
||||
|
@ -111,7 +110,7 @@ static bool load_header(FileAccess *f, uint8_t &out_version, VoxelRegionFormat &
|
|||
ERR_FAIL_COND_V(f == nullptr, false);
|
||||
|
||||
ERR_FAIL_COND_V(f->get_position() != 0, false);
|
||||
ERR_FAIL_COND_V(f->get_len() < MAGIC_AND_VERSION_SIZE, false);
|
||||
ERR_FAIL_COND_V(f->get_length() < MAGIC_AND_VERSION_SIZE, false);
|
||||
|
||||
FixedArray<char, 5> magic(0);
|
||||
ERR_FAIL_COND_V(f->get_buffer(reinterpret_cast<uint8_t *>(magic.data()), 4) != 4, false);
|
||||
|
@ -156,7 +155,7 @@ static bool load_header(FileAccess *f, uint8_t &out_version, VoxelRegionFormat &
|
|||
}
|
||||
|
||||
out_version = version;
|
||||
out_block_infos.resize(out_format.region_size.volume());
|
||||
out_block_infos.resize(Vector3iUtil::get_volume(out_format.region_size));
|
||||
|
||||
// TODO Deal with endianess
|
||||
const size_t blocks_len = out_block_infos.size() * sizeof(VoxelRegionBlockInfo);
|
||||
|
@ -292,7 +291,7 @@ bool VoxelRegionFile::set_format(const VoxelRegionFormat &format) {
|
|||
|
||||
// This will be the format used to create the next file if not found on open()
|
||||
_header.format = format;
|
||||
_header.blocks.resize(format.region_size.volume());
|
||||
_header.blocks.resize(Vector3iUtil::get_volume(format.region_size));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -330,13 +329,13 @@ Error VoxelRegionFile::load_block(
|
|||
CRASH_COND(f->eof_reached());
|
||||
|
||||
ERR_FAIL_COND_V_MSG(!serializer.decompress_and_deserialize(f, block_data_size, out_block), ERR_PARSE_ERROR,
|
||||
String("Failed to read block {0}").format(varray(position.to_vec3())));
|
||||
String("Failed to read block {0}").format(varray(position)));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
Error VoxelRegionFile::save_block(Vector3i position, VoxelBufferInternal &block,
|
||||
VoxelBlockSerializerInternal &serializer) {
|
||||
Error VoxelRegionFile::save_block(
|
||||
Vector3i position, VoxelBufferInternal &block, VoxelBlockSerializerInternal &serializer) {
|
||||
//
|
||||
ERR_FAIL_COND_V(_header.format.verify_block(block) == false, ERR_INVALID_PARAMETER);
|
||||
|
||||
|
@ -478,8 +477,8 @@ void VoxelRegionFile::remove_sectors_from_block(Vector3i block_pos, unsigned int
|
|||
CRASH_COND(block_index >= _header.blocks.size());
|
||||
VoxelRegionBlockInfo &block_info = _header.blocks[block_index];
|
||||
|
||||
unsigned int src_offset = _blocks_begin_offset +
|
||||
(block_info.get_sector_index() + block_info.get_sector_count()) * sector_size;
|
||||
unsigned int src_offset =
|
||||
_blocks_begin_offset + (block_info.get_sector_index() + block_info.get_sector_count()) * sector_size;
|
||||
|
||||
unsigned int dst_offset = src_offset - p_sector_count * sector_size;
|
||||
|
||||
|
@ -511,8 +510,7 @@ void VoxelRegionFile::remove_sectors_from_block(Vector3i block_pos, unsigned int
|
|||
// but FileAccess doesn't have any function to do that... so can't rely on EOF either
|
||||
|
||||
// Erase sectors from cache
|
||||
_sectors.erase(
|
||||
_sectors.begin() + (block_info.get_sector_index() + block_info.get_sector_count() - p_sector_count),
|
||||
_sectors.erase(_sectors.begin() + (block_info.get_sector_index() + block_info.get_sector_count() - p_sector_count),
|
||||
_sectors.begin() + (block_info.get_sector_index() + block_info.get_sector_count()));
|
||||
|
||||
const unsigned int old_sector_index = block_info.get_sector_index();
|
||||
|
@ -555,7 +553,7 @@ bool VoxelRegionFile::migrate_from_v2_to_v3(FileAccess *f, VoxelRegionFormat &fo
|
|||
|
||||
// Which file offset blocks data is starting
|
||||
// magic + version + blockinfos
|
||||
const unsigned int old_header_size = format.region_size.volume() * sizeof(uint32_t);
|
||||
const unsigned int old_header_size = Vector3iUtil::get_volume(format.region_size) * sizeof(uint32_t);
|
||||
|
||||
const unsigned int new_header_size = get_header_size_v3(format) - MAGIC_AND_VERSION_SIZE;
|
||||
ERR_FAIL_COND_V_MSG(new_header_size < old_header_size, false, "New version is supposed to have larger header");
|
||||
|
@ -575,7 +573,7 @@ bool VoxelRegionFile::migrate_from_v2_to_v3(FileAccess *f, VoxelRegionFormat &fo
|
|||
|
||||
bool VoxelRegionFile::migrate_to_latest(FileAccess *f) {
|
||||
ERR_FAIL_COND_V(f == nullptr, false);
|
||||
ERR_FAIL_COND_V(_file_path.empty(), false);
|
||||
ERR_FAIL_COND_V(_file_path.is_empty(), false);
|
||||
|
||||
uint8_t version = _header.version;
|
||||
|
||||
|
@ -607,11 +605,11 @@ Error VoxelRegionFile::load_header(FileAccess *f) {
|
|||
}
|
||||
|
||||
unsigned int VoxelRegionFile::get_block_index_in_header(const Vector3i &rpos) const {
|
||||
return rpos.get_zxy_index(_header.format.region_size);
|
||||
return Vector3iUtil::get_zxy_index(rpos, _header.format.region_size);
|
||||
}
|
||||
|
||||
Vector3i VoxelRegionFile::get_block_position_from_index(uint32_t i) const {
|
||||
return Vector3i::from_zxy_index(i, _header.format.region_size);
|
||||
return Vector3iUtil::from_zxy_index(i, _header.format.region_size);
|
||||
}
|
||||
|
||||
uint32_t VoxelRegionFile::get_sector_count_from_bytes(uint32_t size_in_bytes) const {
|
||||
|
@ -640,7 +638,7 @@ void VoxelRegionFile::debug_check() {
|
|||
ERR_FAIL_COND(!is_open());
|
||||
ERR_FAIL_COND(_file_access == nullptr);
|
||||
FileAccess *f = _file_access;
|
||||
const size_t file_len = f->get_len();
|
||||
const size_t file_len = f->get_length();
|
||||
|
||||
for (unsigned int lut_index = 0; lut_index < _header.blocks.size(); ++lut_index) {
|
||||
const VoxelRegionBlockInfo &block_info = _header.blocks[lut_index];
|
||||
|
@ -652,8 +650,7 @@ void VoxelRegionFile::debug_check() {
|
|||
const unsigned int block_begin = _blocks_begin_offset + sector_index * _header.format.sector_size;
|
||||
if (block_begin >= file_len) {
|
||||
print_line(String("ERROR: LUT {0} ({1}): offset {2} is larger than file size {3}")
|
||||
.format(varray(lut_index, position.to_vec3(), block_begin,
|
||||
SIZE_T_TO_VARIANT(file_len))));
|
||||
.format(varray(lut_index, position, block_begin, SIZE_T_TO_VARIANT(file_len))));
|
||||
continue;
|
||||
}
|
||||
f->seek(block_begin);
|
||||
|
@ -662,8 +659,7 @@ void VoxelRegionFile::debug_check() {
|
|||
const size_t remaining_size = file_len - pos;
|
||||
if (block_data_size > remaining_size) {
|
||||
print_line(String("ERROR: LUT {0} ({1}): block size at offset {2} is larger than remaining size {3}")
|
||||
.format(varray(lut_index, position.to_vec3(),
|
||||
SIZE_T_TO_VARIANT(block_data_size),
|
||||
.format(varray(lut_index, position, SIZE_T_TO_VARIANT(block_data_size),
|
||||
SIZE_T_TO_VARIANT(remaining_size))));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -58,8 +58,8 @@ VoxelStreamRegionFiles::~VoxelStreamRegionFiles() {
|
|||
close_all_regions();
|
||||
}
|
||||
|
||||
VoxelStream::Result VoxelStreamRegionFiles::emerge_block(VoxelBufferInternal &out_buffer, Vector3i origin_in_voxels,
|
||||
int lod) {
|
||||
VoxelStream::Result VoxelStreamRegionFiles::emerge_block(
|
||||
VoxelBufferInternal &out_buffer, Vector3i origin_in_voxels, int lod) {
|
||||
VoxelBlockRequest r{ out_buffer, origin_in_voxels, lod };
|
||||
Vector<Result> results;
|
||||
emerge_blocks(Span<VoxelBlockRequest>(&r, 1), results);
|
||||
|
@ -130,7 +130,7 @@ VoxelStreamRegionFiles::EmergeResult VoxelStreamRegionFiles::_emerge_block(
|
|||
|
||||
MutexLock lock(_mutex);
|
||||
|
||||
if (_directory_path.empty()) {
|
||||
if (_directory_path.is_empty()) {
|
||||
return EMERGE_OK_FALLBACK;
|
||||
}
|
||||
|
||||
|
@ -142,8 +142,8 @@ VoxelStreamRegionFiles::EmergeResult VoxelStreamRegionFiles::_emerge_block(
|
|||
}
|
||||
}
|
||||
|
||||
const Vector3i block_size = Vector3i(1 << _meta.block_size_po2);
|
||||
const Vector3i region_size = Vector3i(1 << _meta.region_size_po2);
|
||||
const Vector3i block_size = Vector3iUtil::create(1 << _meta.block_size_po2);
|
||||
const Vector3i region_size = Vector3iUtil::create(1 << _meta.region_size_po2);
|
||||
|
||||
CRASH_COND(!_meta_loaded);
|
||||
ERR_FAIL_COND_V(lod >= _meta.lod_count, EMERGE_FAILED);
|
||||
|
@ -163,7 +163,7 @@ VoxelStreamRegionFiles::EmergeResult VoxelStreamRegionFiles::_emerge_block(
|
|||
return EMERGE_OK_FALLBACK;
|
||||
}
|
||||
|
||||
const Vector3i block_rpos = block_pos.wrap(region_size);
|
||||
const Vector3i block_rpos = Vector3iUtil::wrap(block_pos, region_size);
|
||||
|
||||
const Error err = cache->region.load_block(block_rpos, out_buffer, _block_serializer);
|
||||
switch (err) {
|
||||
|
@ -183,7 +183,7 @@ void VoxelStreamRegionFiles::_immerge_block(VoxelBufferInternal &voxel_buffer, V
|
|||
|
||||
MutexLock lock(_mutex);
|
||||
|
||||
ERR_FAIL_COND(_directory_path.empty());
|
||||
ERR_FAIL_COND(_directory_path.is_empty());
|
||||
|
||||
if (!_meta_loaded) {
|
||||
// If it's not loaded, always try to load meta file first if it exists already,
|
||||
|
@ -207,16 +207,16 @@ void VoxelStreamRegionFiles::_immerge_block(VoxelBufferInternal &voxel_buffer, V
|
|||
}
|
||||
|
||||
// Verify format
|
||||
const Vector3i block_size = Vector3i(1 << _meta.block_size_po2);
|
||||
const Vector3i block_size = Vector3iUtil::create(1 << _meta.block_size_po2);
|
||||
ERR_FAIL_COND(voxel_buffer.get_size() != block_size);
|
||||
for (unsigned int i = 0; i < VoxelBufferInternal::MAX_CHANNELS; ++i) {
|
||||
ERR_FAIL_COND(voxel_buffer.get_channel_depth(i) != _meta.channel_depths[i]);
|
||||
}
|
||||
|
||||
const Vector3i region_size = Vector3i(1 << _meta.region_size_po2);
|
||||
const Vector3i region_size = Vector3iUtil::create(1 << _meta.region_size_po2);
|
||||
Vector3i block_pos = get_block_position_from_voxels(origin_in_voxels) >> lod;
|
||||
Vector3i region_pos = get_region_position_from_blocks(block_pos);
|
||||
Vector3i block_rpos = block_pos.wrap(region_size);
|
||||
Vector3i block_rpos = Vector3iUtil::wrap(block_pos, region_size);
|
||||
|
||||
CachedRegion *cache = open_region(region_pos, lod, true);
|
||||
ERR_FAIL_COND_MSG(cache == nullptr, "Could not save region file data");
|
||||
|
@ -236,12 +236,12 @@ void VoxelStreamRegionFiles::set_directory(String dirpath) {
|
|||
_meta_loaded = false;
|
||||
_meta_saved = false;
|
||||
load_meta();
|
||||
_change_notify();
|
||||
notify_property_list_changed();
|
||||
}
|
||||
}
|
||||
|
||||
static bool u8_from_json_variant(Variant v, uint8_t &i) {
|
||||
ERR_FAIL_COND_V(v.get_type() != Variant::INT && v.get_type() != Variant::REAL, false);
|
||||
ERR_FAIL_COND_V(v.get_type() != Variant::INT && v.get_type() != Variant::FLOAT, false);
|
||||
int n = v;
|
||||
ERR_FAIL_COND_V(n < 0 || n > 255, false);
|
||||
i = v;
|
||||
|
@ -249,7 +249,7 @@ static bool u8_from_json_variant(Variant v, uint8_t &i) {
|
|||
}
|
||||
|
||||
static bool u32_from_json_variant(Variant v, uint32_t &i) {
|
||||
ERR_FAIL_COND_V(v.get_type() != Variant::INT && v.get_type() != Variant::REAL, false);
|
||||
ERR_FAIL_COND_V(v.get_type() != Variant::INT && v.get_type() != Variant::FLOAT, false);
|
||||
ERR_FAIL_COND_V(v.operator int64_t() < 0, false);
|
||||
i = v;
|
||||
return true;
|
||||
|
@ -280,7 +280,8 @@ VoxelFileResult VoxelStreamRegionFiles::save_meta() {
|
|||
}
|
||||
d["channel_depths"] = channel_depths;
|
||||
|
||||
String json = JSON::print(d, "\t", true);
|
||||
JSON json;
|
||||
String json_string = json.stringify(d, "\t", true);
|
||||
|
||||
// Make sure the directory exists
|
||||
{
|
||||
|
@ -301,7 +302,7 @@ VoxelFileResult VoxelStreamRegionFiles::save_meta() {
|
|||
return VOXEL_FILE_CANT_OPEN;
|
||||
}
|
||||
|
||||
f->store_string(json);
|
||||
f->store_string(json_string);
|
||||
|
||||
_meta_saved = true;
|
||||
_meta_loaded = true;
|
||||
|
@ -337,7 +338,7 @@ VoxelFileResult VoxelStreamRegionFiles::load_meta() {
|
|||
CRASH_COND(_region_cache.size() > 0);
|
||||
|
||||
String meta_path = _directory_path.plus_file(META_FILE_NAME);
|
||||
String json;
|
||||
String json_string;
|
||||
|
||||
{
|
||||
Error err;
|
||||
|
@ -346,19 +347,20 @@ VoxelFileResult VoxelStreamRegionFiles::load_meta() {
|
|||
if (!f) {
|
||||
return VOXEL_FILE_CANT_OPEN;
|
||||
}
|
||||
json = f->get_as_utf8_string();
|
||||
json_string = f->get_as_utf8_string();
|
||||
}
|
||||
|
||||
// Note: I chose JSON purely for debugging purposes. This file is not meant to be edited by hand.
|
||||
// World configuration changes may need a full converter.
|
||||
|
||||
Variant res;
|
||||
String json_err_msg;
|
||||
int json_err_line;
|
||||
Error json_err = JSON::parse(json, res, json_err_msg, json_err_line);
|
||||
JSON json;
|
||||
const Error json_err = json.parse(json_string);
|
||||
Variant res = json.get_data();
|
||||
const String json_err_msg = json.get_error_message();
|
||||
const int json_err_line = json.get_error_line();
|
||||
if (json_err != OK) {
|
||||
ERR_PRINT(String("Error when parsing {0}: line {1}: {2}")
|
||||
.format(varray(meta_path, json_err_line, json_err_msg)));
|
||||
ERR_PRINT(
|
||||
String("Error when parsing {0}: line {1}: {2}").format(varray(meta_path, json_err_line, json_err_msg)));
|
||||
return VOXEL_FILE_INVALID_DATA;
|
||||
}
|
||||
|
||||
|
@ -464,7 +466,7 @@ VoxelStreamRegionFiles::CachedRegion *VoxelStreamRegionFiles::open_region(
|
|||
format.channel_depths = _meta.channel_depths;
|
||||
// TODO Palette support
|
||||
format.has_palette = false;
|
||||
format.region_size = Vector3i(1 << _meta.region_size_po2);
|
||||
format.region_size = Vector3iUtil::create(1 << _meta.region_size_po2);
|
||||
format.sector_size = _meta.sector_size;
|
||||
|
||||
cached_region->region.set_format(format);
|
||||
|
@ -494,10 +496,10 @@ VoxelStreamRegionFiles::CachedRegion *VoxelStreamRegionFiles::open_region(
|
|||
// Make sure it has correct format
|
||||
{
|
||||
const VoxelRegionFormat &format = cached_region->region.get_format();
|
||||
if (format.block_size_po2 != _meta.block_size_po2 ||
|
||||
format.channel_depths != _meta.channel_depths ||
|
||||
format.region_size != Vector3i(1 << _meta.region_size_po2) ||
|
||||
format.sector_size != _meta.sector_size) {
|
||||
if (format.block_size_po2 != _meta.block_size_po2 //
|
||||
|| format.channel_depths != _meta.channel_depths //
|
||||
|| format.region_size != Vector3iUtil::create(1 << _meta.region_size_po2) //
|
||||
|| format.sector_size != _meta.sector_size) {
|
||||
ERR_PRINT("Region file has unexpected format");
|
||||
memdelete(cached_region);
|
||||
return nullptr;
|
||||
|
@ -549,15 +551,15 @@ static inline int convert_block_coordinate(int p_x, int old_size, int new_size)
|
|||
}
|
||||
|
||||
static Vector3i convert_block_coordinates(Vector3i pos, Vector3i old_size, Vector3i new_size) {
|
||||
return Vector3i(
|
||||
convert_block_coordinate(pos.x, old_size.x, new_size.x),
|
||||
return Vector3i(convert_block_coordinate(pos.x, old_size.x, new_size.x),
|
||||
convert_block_coordinate(pos.y, old_size.y, new_size.y),
|
||||
convert_block_coordinate(pos.z, old_size.z, new_size.z));
|
||||
}
|
||||
|
||||
void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
||||
// TODO Converting across different block sizes is untested.
|
||||
// I wrote it because it would be too bad to loose large voxel worlds because of a setting change, so one day we may need it
|
||||
// I wrote it because it would be too bad to loose large voxel worlds because of a setting change, so one day we may
|
||||
// need it
|
||||
|
||||
PRINT_VERBOSE("Converting region files");
|
||||
// This can be a very long and slow operation. Better run this in a thread.
|
||||
|
@ -568,7 +570,7 @@ void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
|||
close_all_regions();
|
||||
|
||||
Ref<VoxelStreamRegionFiles> old_stream;
|
||||
old_stream.instance();
|
||||
old_stream.instantiate();
|
||||
// Keep file cache to a minimum for the old stream, we'll query all blocks once anyways
|
||||
old_stream->_max_open_regions = MAX(1, FOPEN_MAX);
|
||||
|
||||
|
@ -634,7 +636,8 @@ void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
|||
if (fname.ends_with(ext)) {
|
||||
Vector<String> parts = fname.split(".");
|
||||
// r.x.y.z.ext
|
||||
ERR_FAIL_COND_MSG(parts.size() < 4, String("Found invalid region file: '{0}'").format(varray(fname)));
|
||||
ERR_FAIL_COND_MSG(
|
||||
parts.size() < 4, String("Found invalid region file: '{0}'").format(varray(fname)));
|
||||
PositionAndLod p;
|
||||
p.position.x = parts[1].to_int();
|
||||
p.position.y = parts[2].to_int();
|
||||
|
@ -651,10 +654,10 @@ void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
|||
_meta = new_meta;
|
||||
ERR_FAIL_COND(save_meta() != VOXEL_FILE_OK);
|
||||
|
||||
const Vector3i old_block_size = Vector3i(1 << old_meta.block_size_po2);
|
||||
const Vector3i new_block_size = Vector3i(1 << _meta.block_size_po2);
|
||||
const Vector3i old_block_size = Vector3iUtil::create(1 << old_meta.block_size_po2);
|
||||
const Vector3i new_block_size = Vector3iUtil::create(1 << _meta.block_size_po2);
|
||||
|
||||
const Vector3i old_region_size = Vector3i(1 << old_meta.region_size_po2);
|
||||
const Vector3i old_region_size = Vector3iUtil::create(1 << old_meta.region_size_po2);
|
||||
|
||||
// Read all blocks from the old stream and write them into the new one
|
||||
|
||||
|
@ -666,8 +669,7 @@ void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
|||
continue;
|
||||
}
|
||||
|
||||
PRINT_VERBOSE(String("Converting region lod{0}/{1}")
|
||||
.format(varray(region_info.lod, region_info.position.to_vec3())));
|
||||
PRINT_VERBOSE(String("Converting region lod{0}/{1}").format(varray(region_info.lod, region_info.position)));
|
||||
|
||||
const unsigned int blocks_count = old_region->region.get_header_block_count();
|
||||
for (unsigned int j = 0; j < blocks_count; ++j) {
|
||||
|
@ -726,8 +728,8 @@ void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
|||
new_block.copy_from(old_block, src_min, src_max, Vector3i(), channel_index);
|
||||
}
|
||||
|
||||
immerge_block(new_block,
|
||||
(new_block_pos + rpos) * new_block_size << region_info.lod, region_info.lod);
|
||||
immerge_block(new_block, (new_block_pos + rpos) * new_block_size << region_info.lod,
|
||||
region_info.lod);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -743,11 +745,11 @@ void VoxelStreamRegionFiles::_convert_files(Meta new_meta) {
|
|||
|
||||
Vector3i VoxelStreamRegionFiles::get_region_size() const {
|
||||
MutexLock lock(_mutex);
|
||||
return Vector3i(1 << _meta.region_size_po2);
|
||||
return Vector3iUtil::create(1 << _meta.region_size_po2);
|
||||
}
|
||||
|
||||
Vector3 VoxelStreamRegionFiles::get_region_size_v() const {
|
||||
return get_region_size().to_vec3();
|
||||
return get_region_size();
|
||||
}
|
||||
|
||||
int VoxelStreamRegionFiles::get_region_size_po2() const {
|
||||
|
@ -781,7 +783,8 @@ void VoxelStreamRegionFiles::set_region_size_po2(int p_region_size_po2) {
|
|||
if (_meta.region_size_po2 == p_region_size_po2) {
|
||||
return;
|
||||
}
|
||||
ERR_FAIL_COND_MSG(_meta_loaded, "Can't change existing region size without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND_MSG(
|
||||
_meta_loaded, "Can't change existing region size without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND(p_region_size_po2 < 1);
|
||||
ERR_FAIL_COND(p_region_size_po2 > 8);
|
||||
_meta.region_size_po2 = p_region_size_po2;
|
||||
|
@ -795,8 +798,8 @@ void VoxelStreamRegionFiles::set_block_size_po2(int p_block_size_po2) {
|
|||
if (_meta.block_size_po2 == p_block_size_po2) {
|
||||
return;
|
||||
}
|
||||
ERR_FAIL_COND_MSG(_meta_loaded,
|
||||
"Can't change existing block size without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND_MSG(
|
||||
_meta_loaded, "Can't change existing block size without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND(p_block_size_po2 < 1);
|
||||
ERR_FAIL_COND(p_block_size_po2 > 8);
|
||||
_meta.block_size_po2 = p_block_size_po2;
|
||||
|
@ -810,8 +813,8 @@ void VoxelStreamRegionFiles::set_sector_size(int p_sector_size) {
|
|||
if (static_cast<int>(_meta.sector_size) == p_sector_size) {
|
||||
return;
|
||||
}
|
||||
ERR_FAIL_COND_MSG(_meta_loaded,
|
||||
"Can't change existing sector size without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND_MSG(
|
||||
_meta_loaded, "Can't change existing sector size without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND(p_sector_size < 256);
|
||||
ERR_FAIL_COND(p_sector_size > 65536);
|
||||
_meta.sector_size = p_sector_size;
|
||||
|
@ -825,8 +828,8 @@ void VoxelStreamRegionFiles::set_lod_count(int p_lod_count) {
|
|||
if (_meta.lod_count == p_lod_count) {
|
||||
return;
|
||||
}
|
||||
ERR_FAIL_COND_MSG(_meta_loaded,
|
||||
"Can't change existing LOD count without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND_MSG(
|
||||
_meta_loaded, "Can't change existing LOD count without heavy conversion. Use convert_files().");
|
||||
ERR_FAIL_COND(p_lod_count < 1);
|
||||
ERR_FAIL_COND(p_lod_count > 32);
|
||||
_meta.lod_count = p_lod_count;
|
||||
|
|
|
@ -26,10 +26,8 @@ struct BlockLocation {
|
|||
|
||||
uint64_t encode() const {
|
||||
// 0l xx yy zz
|
||||
return ((static_cast<uint64_t>(lod) & 0xffff) << 48) |
|
||||
((static_cast<uint64_t>(x) & 0xffff) << 32) |
|
||||
((static_cast<uint64_t>(y) & 0xffff) << 16) |
|
||||
(static_cast<uint64_t>(z) & 0xffff);
|
||||
return ((static_cast<uint64_t>(lod) & 0xffff) << 48) | ((static_cast<uint64_t>(x) & 0xffff) << 32) |
|
||||
((static_cast<uint64_t>(y) & 0xffff) << 16) | (static_cast<uint64_t>(z) & 0xffff);
|
||||
}
|
||||
|
||||
static BlockLocation decode(uint64_t id) {
|
||||
|
@ -61,10 +59,7 @@ public:
|
|||
FixedArray<Channel, VoxelBuffer::MAX_CHANNELS> channels;
|
||||
};
|
||||
|
||||
enum BlockType {
|
||||
VOXELS,
|
||||
INSTANCES
|
||||
};
|
||||
enum BlockType { VOXELS, INSTANCES };
|
||||
|
||||
VoxelStreamSQLiteInternal();
|
||||
~VoxelStreamSQLiteInternal();
|
||||
|
@ -72,7 +67,9 @@ public:
|
|||
bool open(const char *fpath);
|
||||
void close();
|
||||
|
||||
bool is_open() const { return _db != nullptr; }
|
||||
bool is_open() const {
|
||||
return _db != nullptr;
|
||||
}
|
||||
|
||||
// Returns the file path from SQLite
|
||||
const char *get_file_path() const;
|
||||
|
@ -90,10 +87,7 @@ public:
|
|||
VoxelStream::Result load_block(BlockLocation loc, std::vector<uint8_t> &out_block_data, BlockType type);
|
||||
|
||||
bool load_all_blocks(void *callback_data,
|
||||
void (*process_block_func)(
|
||||
void *callback_data,
|
||||
BlockLocation location,
|
||||
Span<const uint8_t> voxel_data,
|
||||
void (*process_block_func)(void *callback_data, BlockLocation location, Span<const uint8_t> voxel_data,
|
||||
Span<const uint8_t> instances_data));
|
||||
|
||||
Meta load_meta();
|
||||
|
@ -102,8 +96,7 @@ public:
|
|||
private:
|
||||
struct TransactionScope {
|
||||
VoxelStreamSQLiteInternal &db;
|
||||
TransactionScope(VoxelStreamSQLiteInternal &p_db) :
|
||||
db(p_db) {
|
||||
TransactionScope(VoxelStreamSQLiteInternal &p_db) : db(p_db) {
|
||||
db.begin_transaction();
|
||||
}
|
||||
~TransactionScope() {
|
||||
|
@ -142,8 +135,7 @@ private:
|
|||
sqlite3_stmt *_load_all_blocks_statement = nullptr;
|
||||
};
|
||||
|
||||
VoxelStreamSQLiteInternal::VoxelStreamSQLiteInternal() {
|
||||
}
|
||||
VoxelStreamSQLiteInternal::VoxelStreamSQLiteInternal() {}
|
||||
|
||||
VoxelStreamSQLiteInternal::~VoxelStreamSQLiteInternal() {
|
||||
close();
|
||||
|
@ -164,11 +156,9 @@ bool VoxelStreamSQLiteInternal::open(const char *fpath) {
|
|||
char *error_message = nullptr;
|
||||
|
||||
// Create tables if they dont exist
|
||||
const char *tables[3] = {
|
||||
"CREATE TABLE IF NOT EXISTS meta (version INTEGER, block_size_po2 INTEGER)",
|
||||
const char *tables[3] = { "CREATE TABLE IF NOT EXISTS meta (version INTEGER, block_size_po2 INTEGER)",
|
||||
"CREATE TABLE IF NOT EXISTS blocks (loc INTEGER PRIMARY KEY, vb BLOB, instances BLOB)",
|
||||
"CREATE TABLE IF NOT EXISTS channels (idx INTEGER PRIMARY KEY, depth INTEGER)"
|
||||
};
|
||||
"CREATE TABLE IF NOT EXISTS channels (idx INTEGER PRIMARY KEY, depth INTEGER)" };
|
||||
for (size_t i = 0; i < 3; ++i) {
|
||||
rc = sqlite3_exec(db, tables[i], nullptr, nullptr, &error_message);
|
||||
if (rc != SQLITE_OK) {
|
||||
|
@ -404,10 +394,7 @@ VoxelStream::Result VoxelStreamSQLiteInternal::load_block(
|
|||
}
|
||||
|
||||
bool VoxelStreamSQLiteInternal::load_all_blocks(void *callback_data,
|
||||
void (*process_block_func)(
|
||||
void *callback_data,
|
||||
BlockLocation location,
|
||||
Span<const uint8_t> voxel_data,
|
||||
void (*process_block_func)(void *callback_data, BlockLocation location, Span<const uint8_t> voxel_data,
|
||||
Span<const uint8_t> instances_data)) {
|
||||
VOXEL_PROFILE_SCOPE();
|
||||
CRASH_COND(process_block_func == nullptr);
|
||||
|
@ -589,12 +576,11 @@ thread_local VoxelBlockSerializerInternal VoxelStreamSQLite::_voxel_block_serial
|
|||
thread_local std::vector<uint8_t> VoxelStreamSQLite::_temp_block_data;
|
||||
thread_local std::vector<uint8_t> VoxelStreamSQLite::_temp_compressed_block_data;
|
||||
|
||||
VoxelStreamSQLite::VoxelStreamSQLite() {
|
||||
}
|
||||
VoxelStreamSQLite::VoxelStreamSQLite() {}
|
||||
|
||||
VoxelStreamSQLite::~VoxelStreamSQLite() {
|
||||
PRINT_VERBOSE("~VoxelStreamSQLite");
|
||||
if (!_connection_path.empty() && _cache.get_indicative_block_count() > 0) {
|
||||
if (!_connection_path.is_empty() && _cache.get_indicative_block_count() > 0) {
|
||||
PRINT_VERBOSE("~VoxelStreamSQLite flushy flushy");
|
||||
flush_cache();
|
||||
PRINT_VERBOSE("~VoxelStreamSQLite flushy done");
|
||||
|
@ -611,7 +597,7 @@ void VoxelStreamSQLite::set_database_path(String path) {
|
|||
if (path == _connection_path) {
|
||||
return;
|
||||
}
|
||||
if (!_connection_path.empty() && _cache.get_indicative_block_count() > 0) {
|
||||
if (!_connection_path.is_empty() && _cache.get_indicative_block_count() > 0) {
|
||||
// Save cached data before changing the path.
|
||||
// Not using get_connection() because it locks.
|
||||
VoxelStreamSQLiteInternal con;
|
||||
|
@ -636,7 +622,8 @@ String VoxelStreamSQLite::get_database_path() const {
|
|||
return _connection_path;
|
||||
}
|
||||
|
||||
VoxelStream::Result VoxelStreamSQLite::emerge_block(VoxelBufferInternal &out_buffer, Vector3i origin_in_voxels, int lod) {
|
||||
VoxelStream::Result VoxelStreamSQLite::emerge_block(
|
||||
VoxelBufferInternal &out_buffer, Vector3i origin_in_voxels, int lod) {
|
||||
VoxelBlockRequest r{ out_buffer, origin_in_voxels, lod };
|
||||
Vector<Result> results;
|
||||
emerge_blocks(Span<VoxelBlockRequest>(&r, 1), results);
|
||||
|
@ -721,7 +708,7 @@ void VoxelStreamSQLite::immerge_blocks(Span<VoxelBlockRequest> p_blocks) {
|
|||
const Vector3i pos = r.origin_in_voxels >> (bs_po2 + r.lod);
|
||||
|
||||
if (!BlockLocation::validate(pos, r.lod)) {
|
||||
ERR_PRINT(String("Block position {0} is outside of supported range").format(varray(pos.to_vec3())));
|
||||
ERR_PRINT(String("Block position {0} is outside of supported range").format(varray(pos)));
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -947,7 +934,7 @@ void VoxelStreamSQLite::flush_cache(VoxelStreamSQLiteInternal *con) {
|
|||
|
||||
VoxelStreamSQLiteInternal *VoxelStreamSQLite::get_connection() {
|
||||
_connection_mutex.lock();
|
||||
if (_connection_path.empty()) {
|
||||
if (_connection_path.is_empty()) {
|
||||
_connection_mutex.unlock();
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -960,7 +947,7 @@ VoxelStreamSQLiteInternal *VoxelStreamSQLite::get_connection() {
|
|||
String fpath = _connection_path;
|
||||
_connection_mutex.unlock();
|
||||
|
||||
if (fpath.empty()) {
|
||||
if (fpath.is_empty()) {
|
||||
return nullptr;
|
||||
}
|
||||
VoxelStreamSQLiteInternal *con = new VoxelStreamSQLiteInternal();
|
||||
|
@ -989,6 +976,6 @@ void VoxelStreamSQLite::_bind_methods() {
|
|||
ClassDB::bind_method(D_METHOD("set_database_path", "path"), &VoxelStreamSQLite::set_database_path);
|
||||
ClassDB::bind_method(D_METHOD("get_database_path"), &VoxelStreamSQLite::get_database_path);
|
||||
|
||||
ADD_PROPERTY(PropertyInfo(Variant::STRING, "database_path", PROPERTY_HINT_FILE),
|
||||
"set_database_path", "get_database_path");
|
||||
ADD_PROPERTY(PropertyInfo(Variant::STRING, "database_path", PROPERTY_HINT_FILE), "set_database_path",
|
||||
"get_database_path");
|
||||
}
|
||||
|
|
|
@ -2,14 +2,15 @@
|
|||
#include "../util/macros.h"
|
||||
#include "../util/profiling.h"
|
||||
|
||||
#include <core/os/file_access.h>
|
||||
#include <core/variant.h>
|
||||
#include <core/io/file_access.h>
|
||||
#include <core/variant/variant.h>
|
||||
#include <unordered_set>
|
||||
|
||||
namespace vox {
|
||||
|
||||
const uint32_t PALETTE_SIZE = 256;
|
||||
|
||||
// clang-format off
|
||||
uint32_t g_default_palette[PALETTE_SIZE] = {
|
||||
0x00000000, 0xffffffff, 0xffccffff, 0xff99ffff, 0xff66ffff, 0xff33ffff, 0xff00ffff, 0xffffccff,
|
||||
0xffccccff, 0xff99ccff, 0xff66ccff, 0xff33ccff, 0xff00ccff, 0xffff99ff, 0xffcc99ff, 0xff9999ff,
|
||||
|
@ -44,6 +45,7 @@ uint32_t g_default_palette[PALETTE_SIZE] = {
|
|||
0xff880000, 0xff770000, 0xff550000, 0xff440000, 0xff220000, 0xff110000, 0xffeeeeee, 0xffdddddd,
|
||||
0xffbbbbbb, 0xffaaaaaa, 0xff888888, 0xff777777, 0xff555555, 0xff444444, 0xff222222, 0xff111111
|
||||
};
|
||||
// clang-format on
|
||||
|
||||
static Error parse_string(FileAccess &f, String &s) {
|
||||
const int size = f.get_32();
|
||||
|
@ -154,16 +156,13 @@ static Basis parse_basis(uint8_t data) {
|
|||
y = magica_z;
|
||||
|
||||
Basis b;
|
||||
b.set(
|
||||
x.x, y.x, z.x,
|
||||
x.y, y.y, z.y,
|
||||
x.z, y.z, z.z);
|
||||
b.set(x.x, y.x, z.x, x.y, y.y, z.y, x.z, y.z, z.z);
|
||||
|
||||
return b;
|
||||
}
|
||||
|
||||
Error parse_node_common_header(Node &node, FileAccess &f,
|
||||
const std::unordered_map<int, std::unique_ptr<Node>> &scene_graph) {
|
||||
Error parse_node_common_header(
|
||||
Node &node, FileAccess &f, const std::unordered_map<int, std::unique_ptr<Node>> &scene_graph) {
|
||||
//
|
||||
const int node_id = f.get_32();
|
||||
ERR_FAIL_COND_V_MSG(scene_graph.find(node_id) != scene_graph.end(), ERR_INVALID_DATA,
|
||||
|
@ -216,7 +215,7 @@ Error Data::_load_from_file(String fpath) {
|
|||
const uint32_t version = f.get_32();
|
||||
ERR_FAIL_COND_V(version != 150, ERR_PARSE_ERROR);
|
||||
|
||||
const size_t file_length = f.get_len();
|
||||
const size_t file_length = f.get_length();
|
||||
|
||||
Vector3i last_size;
|
||||
|
||||
|
@ -259,7 +258,7 @@ Error Data::_load_from_file(String fpath) {
|
|||
ERR_FAIL_COND_V(pos.x >= model->size.x || pos.x < 0, ERR_PARSE_ERROR);
|
||||
ERR_FAIL_COND_V(pos.y >= model->size.y || pos.y < 0, ERR_PARSE_ERROR);
|
||||
ERR_FAIL_COND_V(pos.z >= model->size.z || pos.z < 0, ERR_PARSE_ERROR);
|
||||
model->color_indexes[pos.get_zxy_index(model->size)] = c;
|
||||
model->color_indexes[Vector3iUtil::get_zxy_index(pos, model->size)] = c;
|
||||
}
|
||||
|
||||
_models.push_back(std::move(model));
|
||||
|
|
|
@ -6,14 +6,13 @@
|
|||
#include "../util/math/vector3i.h"
|
||||
|
||||
#include <core/math/basis.h>
|
||||
#include <core/ustring.h>
|
||||
#include <core/string/ustring.h>
|
||||
#include <memory>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
#include <memory>
|
||||
|
||||
namespace std {
|
||||
template <>
|
||||
struct hash<String> {
|
||||
template <> struct hash<String> {
|
||||
size_t operator()(const String &v) const {
|
||||
return v.hash();
|
||||
}
|
||||
|
@ -31,19 +30,14 @@ struct Model {
|
|||
};
|
||||
|
||||
struct Node {
|
||||
enum Type {
|
||||
TYPE_TRANSFORM = 0,
|
||||
TYPE_GROUP,
|
||||
TYPE_SHAPE
|
||||
};
|
||||
enum Type { TYPE_TRANSFORM = 0, TYPE_GROUP, TYPE_SHAPE };
|
||||
|
||||
int id;
|
||||
// Depending on the type, a node pointer can be casted to different structs
|
||||
const Type type;
|
||||
std::unordered_map<String, String> attributes;
|
||||
|
||||
Node(Type p_type) :
|
||||
type(p_type) {}
|
||||
Node(Type p_type) : type(p_type) {}
|
||||
|
||||
virtual ~Node() {}
|
||||
};
|
||||
|
@ -62,23 +56,20 @@ struct TransformNode : public Node {
|
|||
String name;
|
||||
bool hidden;
|
||||
|
||||
TransformNode() :
|
||||
Node(Node::TYPE_TRANSFORM) {}
|
||||
TransformNode() : Node(Node::TYPE_TRANSFORM) {}
|
||||
};
|
||||
|
||||
struct GroupNode : public Node {
|
||||
std::vector<int> child_node_ids;
|
||||
|
||||
GroupNode() :
|
||||
Node(Node::TYPE_GROUP) {}
|
||||
GroupNode() : Node(Node::TYPE_GROUP) {}
|
||||
};
|
||||
|
||||
struct ShapeNode : public Node {
|
||||
int model_id; // corresponds to index in the array of models
|
||||
std::unordered_map<String, String> model_attributes;
|
||||
|
||||
ShapeNode() :
|
||||
Node(Node::TYPE_SHAPE) {}
|
||||
ShapeNode() : Node(Node::TYPE_SHAPE) {}
|
||||
};
|
||||
|
||||
struct Layer {
|
||||
|
@ -89,12 +80,7 @@ struct Layer {
|
|||
};
|
||||
|
||||
struct Material {
|
||||
enum Type {
|
||||
TYPE_DIFFUSE,
|
||||
TYPE_METAL,
|
||||
TYPE_GLASS,
|
||||
TYPE_EMIT
|
||||
};
|
||||
enum Type { TYPE_DIFFUSE, TYPE_METAL, TYPE_GLASS, TYPE_EMIT };
|
||||
int id;
|
||||
Type type = TYPE_DIFFUSE;
|
||||
float weight = 0.f;
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue