16 int xSize,
int ySize,
int zSize,
int numXThreads,
int numYThreads,
17 int numZThreads, std::shared_ptr<ConstantBuffer>
const& parameters)
19 mNumXGroups(xSize/numXThreads),
20 mNumYGroups(ySize/numYThreads),
21 mNumZGroups(zSize/numZThreads)
24 mVortex = std::make_shared<ConstantBuffer>(
sizeof(
Vortex),
true);
37 e.
gravity = { 0.0f, 0.0f, 0.0f, 0.0f };
38 e.
windData = { 0.001f, 0.0f, 0.0f, 0.0f };
40 mSource->SetUsage(Resource::SHADER_OUTPUT);
43 int i = factory->GetAPI();
44 factory->PushDefines();
45 factory->defines.Set(
"NUM_X_THREADS", numXThreads);
46 factory->defines.Set(
"NUM_Y_THREADS", numYThreads);
47 factory->defines.Set(
"NUM_Z_THREADS", numZThreads);
48 std::shared_ptr<ComputeShader> cshader;
54 cshader->Set(
"Parameters", parameters);
55 cshader->Set(
"Vortex",
mVortex);
65 cshader->Set(
"Parameters", parameters);
67 cshader->Set(
"source",
mSource);
70 factory->PopDefines();
77 std::uniform_real_distribution<float> unirnd(0.0
f, 1.0
f);
78 std::uniform_real_distribution<float> symrnd(-1.0
f, 1.0
f);
79 std::uniform_real_distribution<float> posrnd0(0.001
f, 0.01
f);
80 std::uniform_real_distribution<float> posrnd1(64.0
f, 128.0
f);
90 v.position[1] = unirnd(mte);
91 v.position[2] = unirnd(mte);
93 v.normal[0] = symrnd(mte);
94 v.normal[1] = symrnd(mte);
95 v.normal[2] = symrnd(mte);
98 v.data[0] = posrnd0(mte);
99 v.data[1] = posrnd1(mte);
119 "uniform Parameters\n" 121 " vec4 spaceDelta; // (dx, dy, dz, 0)\n" 122 " vec4 halfDivDelta; // (0.5/dx, 0.5/dy, 0.5/dz, 0)\n" 123 " vec4 timeDelta; // (dt/dx, dt/dy, dt/dz, dt)\n" 124 " vec4 viscosityX; // (velVX, velVX, velVX, denVX)\n" 125 " vec4 viscosityY; // (velVX, velVY, velVY, denVY)\n" 126 " vec4 viscosityZ; // (velVZ, velVZ, velVZ, denVZ)\n" 127 " vec4 epsilon; // (epsilonX, epsilonY, epsilonZ, epsilon0)\n" 132 " vec4 position; // (px, py, pz, *)\n" 133 " vec4 normal; // (nx, ny, nz, *)\n" 134 " vec4 data; // (variance, amplitude, *, *)\n" 137 "layout(rgba32f) uniform readonly image3D inVelocity;\n" 138 "layout(rgba32f) uniform writeonly image3D outVelocity;\n" 140 "layout (local_size_x = NUM_X_THREADS, local_size_y = NUM_Y_THREADS, local_size_z = NUM_Z_THREADS) in;\n" 143 " ivec3 c = ivec3(gl_GlobalInvocationID.xyz);\n" 144 " vec3 location = spaceDelta.xyz*(c + 0.5f);\n" 145 " vec3 diff = location - position.xyz;\n" 146 " float arg = -dot(diff, diff) / data.x;\n" 147 " float magnitude = data.y*exp(arg);\n" 148 " vec4 vortexVelocity = vec4(magnitude*cross(normal.xyz, diff), 0.0f);\n" 149 " imageStore(outVelocity, c, imageLoad(inVelocity, c) + vortexVelocity);\n" 153 "uniform Parameters\n" 155 " vec4 spaceDelta; // (dx, dy, dz, 0)\n" 156 " vec4 halfDivDelta; // (0.5/dx, 0.5/dy, 0.5/dz, 0)\n" 157 " vec4 timeDelta; // (dt/dx, dt/dy, dt/dz, dt)\n" 158 " vec4 viscosityX; // (velVX, velVX, velVX, denVX)\n" 159 " vec4 viscosityY; // (velVX, velVY, velVY, denVY)\n" 160 " vec4 viscosityZ; // (velVZ, velVZ, velVZ, denVZ)\n" 161 " vec4 epsilon; // (epsilonX, epsilonY, epsilonZ, epsilon0)\n" 166 " vec4 densityProducer; // (x, y, z, *)\n" 167 " vec4 densityPData; // (variance, amplitude, *, *)\n" 168 " vec4 densityConsumer; // (x, y, z, *)\n" 169 " vec4 densityCData; // (variance, amplitude, *, *)\n" 170 " vec4 gravity; // (x, y, z, *)\n" 171 " vec4 windData; // (variance, amplitude, *, *)\n" 174 "layout(rgba32f) uniform readonly image3D vortexVelocity;\n" 175 "layout(rgba32f) uniform writeonly image3D source;\n" 177 "layout (local_size_x = NUM_X_THREADS, local_size_y = NUM_Y_THREADS, local_size_z = NUM_Z_THREADS) in;\n" 180 " ivec3 c = ivec3(gl_GlobalInvocationID.xyz);\n" 182 " // Compute the location of the voxel (x,y,z) in normalized [0,1]^3.\n" 183 " vec3 location = spaceDelta.xyz*(c + 0.5f);\n" 185 " // Compute an input to the fluid simulation consisting of a producer of\n" 186 " // density and a consumer of density.\n" 187 " vec3 diff = location - densityProducer.xyz;\n" 188 " float arg = -dot(diff, diff) / densityPData.x;\n" 189 " float density = densityPData.y*exp(arg);\n" 190 " diff = location - densityConsumer.xyz;\n" 191 " arg = -dot(diff, diff) / densityCData.x;\n" 192 " density -= densityCData.y*exp(arg);\n" 194 " // Compute an input to the fluid simulation consisting of gravity,\n" 195 " // a single wind source, and vortex impulses.\n" 196 " float windArg = -dot(location.xz, location.xz) / windData.x;\n" 197 " vec3 windVelocity = vec3(0.0f, windData.y*exp(windArg), 0.0f);\n" 198 " vec3 velocity = gravity.xyz + windVelocity + imageLoad(vortexVelocity, c).xyz;\n" 200 " imageStore(source, c, vec4(velocity.xyz, density));\n" 204 "cbuffer Parameters\n" 206 " float4 spaceDelta; // (dx, dy, dz, 0)\n" 207 " float4 halfDivDelta; // (0.5/dx, 0.5/dy, 0.5/dz, 0)\n" 208 " float4 timeDelta; // (dt/dx, dt/dy, dt/dz, dt)\n" 209 " float4 viscosityX; // (velVX, velVX, velVX, denVX)\n" 210 " float4 viscosityY; // (velVX, velVY, velVY, denVY)\n" 211 " float4 viscosityZ; // (velVZ, velVZ, velVZ, denVZ)\n" 212 " float4 epsilon; // (epsilonX, epsilonY, epsilonZ, epsilon0)\n" 217 " float4 position; // (px, py, pz, *)\n" 218 " float4 normal; // (nx, ny, nz, *)\n" 219 " float4 data; // (variance, amplitude, *, *)\n" 222 "Texture3D<float4> inVelocity;\n" 223 "RWTexture3D<float4> outVelocity;\n" 225 "[numthreads(NUM_X_THREADS, NUM_Y_THREADS, NUM_Z_THREADS)]\n" 226 "void CSMain(uint3 c : SV_DispatchThreadID)\n" 228 " float3 location = spaceDelta.xyz*(c + 0.5f);\n" 229 " float3 diff = location - position.xyz;\n" 230 " float arg = -dot(diff, diff) / data.x;\n" 231 " float magnitude = data.y*exp(arg);\n" 232 " float4 vortexVelocity = float4(magnitude*cross(normal.xyz, diff), 0.0f);\n" 233 " outVelocity[c] = inVelocity[c] + vortexVelocity;\n" 237 "cbuffer Parameters\n" 239 " float4 spaceDelta; // (dx, dy, dz, 0)\n" 240 " float4 halfDivDelta; // (0.5/dx, 0.5/dy, 0.5/dz, 0)\n" 241 " float4 timeDelta; // (dt/dx, dt/dy, dt/dz, dt)\n" 242 " float4 viscosityX; // (velVX, velVX, velVX, denVX)\n" 243 " float4 viscosityY; // (velVX, velVY, velVY, denVY)\n" 244 " float4 viscosityZ; // (velVZ, velVZ, velVZ, denVZ)\n" 245 " float4 epsilon; // (epsilonX, epsilonY, epsilonZ, epsilon0)\n" 250 " float4 densityProducer; // (x, y, z, *)\n" 251 " float4 densityPData; // (variance, amplitude, *, *)\n" 252 " float4 densityConsumer; // (x, y, z, *)\n" 253 " float4 densityCData; // (variance, amplitude, *, *)\n" 254 " float4 gravity; // (x, y, z, *)\n" 255 " float4 windData; // (variance, amplitude, *, *)\n" 258 "Texture3D<float4> vortexVelocity;\n" 259 "RWTexture3D<float4> source;\n" 261 "[numthreads(NUM_X_THREADS, NUM_Y_THREADS, NUM_Z_THREADS)]\n" 262 "void CSMain(uint3 c : SV_DispatchThreadID)\n" 264 " // Compute the location of the voxel (x,y,z) in normalized [0,1]^3.\n" 265 " float3 location = spaceDelta.xyz*(c + 0.5f);\n" 267 " // Compute an input to the fluid simulation consisting of a producer of\n" 268 " // density and a consumer of density.\n" 269 " float3 diff = location - densityProducer.xyz;\n" 270 " float arg = -dot(diff, diff) / densityPData.x;\n" 271 " float density = densityPData.y*exp(arg);\n" 272 " diff = location - densityConsumer.xyz;\n" 273 " arg = -dot(diff, diff) / densityCData.x;\n" 274 " density -= densityCData.y*exp(arg);\n" 276 " // Compute an input to the fluid simulation consisting of gravity,\n" 277 " // a single wind source, and vortex impulses.\n" 278 " float windArg = -dot(location.xz, location.xz) / windData.x;\n" 279 " float3 windVelocity = float3(0.0f, windData.y*exp(windArg), 0.0f);\n" 280 " float3 velocity = gravity.xyz + windVelocity + vortexVelocity[c].xyz;\n" 282 " source[c] = float4(velocity.xyz, density);\n"
std::shared_ptr< Texture3 > mVelocity1
gte::Vector4< float > gravity
gte::Vector4< float > densityPData
std::shared_ptr< ComputeProgram > mInitializeSource
gte::Vector4< float > densityConsumer
static std::string const msGLSLInitializeSource
static std::string const msHLSLInitializeSource
Fluid3InitializeSource(std::shared_ptr< ProgramFactory > const &factory, int xSize, int ySize, int zSize, int numXThreads, int numYThreads, int numZThreads, std::shared_ptr< ConstantBuffer > const ¶meters)
gte::Vector4< float > densityProducer
std::shared_ptr< ConstantBuffer > mVortex
GLsizei const GLchar *const * string
Real Normalize(GVector< Real > &v, bool robust=false)
gte::Vector4< float > densityCData
static std::string const * msInitializeSource[ProgramFactory::PF_NUM_API]
gte::Vector4< float > windData
std::shared_ptr< Texture3 > mVelocity0
static std::string const msHLSLGenerateSource
std::shared_ptr< Texture3 > mSource
static std::string const * msGenerateSource[ProgramFactory::PF_NUM_API]
std::shared_ptr< ComputeProgram > mGenerateVortex
void Execute(std::shared_ptr< GraphicsEngine > const &engine)
std::shared_ptr< ConstantBuffer > mExternal
gte::Vector4< float > position
static std::string const msGLSLGenerateSource