15     int xSize, 
int ySize, 
int zSize, 
int numXThreads, 
int numYThreads, 
int numZThreads,
    16     std::shared_ptr<ConstantBuffer> 
const& parameters)
    18     mNumXGroups(xSize/numXThreads),
    19     mNumYGroups(ySize/numYThreads),
    20     mNumZGroups(zSize/numZThreads)
    32     int i = factory->GetAPI();
    33     factory->PushDefines();
    34     factory->defines.Set(
"NUM_X_THREADS", numXThreads);
    35     factory->defines.Set(
"NUM_Y_THREADS", numYThreads);
    36     factory->defines.Set(
"NUM_Z_THREADS", numZThreads);
    42         cshader->Set(
"Parameters", parameters);
    43 #if defined(GTE_DEV_OPENGL)    51     factory->PopDefines();
    55     std::shared_ptr<Texture3> 
const& 
source,
    56     std::shared_ptr<Texture3> 
const& stateTm1,
    57     std::shared_ptr<Texture3> 
const& stateT)
    59     std::shared_ptr<ComputeShader> cshader =
    61     cshader->Set(
"source", source);
    62     cshader->Set(
"stateTm1", stateTm1);
    63     cshader->Set(
"stateT", stateT);
    69 "uniform Parameters\n"    71 "    vec4 spaceDelta;    // (dx, dy, dz, 0)\n"    72 "    vec4 halfDivDelta;  // (0.5/dx, 0.5/dy, 0.5/dz, 0)\n"    73 "    vec4 timeDelta;     // (dt/dx, dt/dy, dt/dz, dt)\n"    74 "    vec4 viscosityX;    // (velVX, velVX, velVX, denVX)\n"    75 "    vec4 viscosityY;    // (velVX, velVY, velVY, denVY)\n"    76 "    vec4 viscosityZ;    // (velVZ, velVZ, velVZ, denVZ)\n"    77 "    vec4 epsilon;       // (epsilonX, epsilonY, epsilonZ, epsilon0)\n"    80 "layout(rgba32f) uniform readonly image3D source;\n"    81 "layout(rgba32f) uniform readonly image3D stateT;\n"    82 "uniform sampler3D stateTm1;\n"    83 "layout(rgba32f) uniform writeonly image3D updateState;\n"    85 "layout (local_size_x = NUM_X_THREADS, local_size_y = NUM_Y_THREADS, local_size_z = NUM_Z_THREADS) in;\n"    88 "    ivec3 c = ivec3(gl_GlobalInvocationID.xyz);\n"    89 "    ivec3 dim = imageSize(stateT);\n"    91 "    int x = int(c.x);\n"    92 "    int y = int(c.y);\n"    93 "    int z = int(c.z);\n"    94 "    int xm = max(x - 1, 0);\n"    95 "    int xp = min(x + 1, dim.x - 1);\n"    96 "    int ym = max(y - 1, 0);\n"    97 "    int yp = min(y + 1, dim.y - 1);\n"    98 "    int zm = max(z - 1, 0);\n"    99 "    int zp = min(z + 1, dim.z - 1);\n"   101 "    // Sample states at (x,y,z) and immediate neighbors.\n"   102 "    vec4 stateZZZ = imageLoad(stateT, c);\n"   103 "    vec4 statePZZ = imageLoad(stateT, ivec3(xp, y, z));\n"   104 "    vec4 stateMZZ = imageLoad(stateT, ivec3(xm, y, z));\n"   105 "    vec4 stateZPZ = imageLoad(stateT, ivec3(x, yp, z));\n"   106 "    vec4 stateZMZ = imageLoad(stateT, ivec3(x, ym, z));\n"   107 "    vec4 stateZZP = imageLoad(stateT, ivec3(x, y, zp));\n"   108 "    vec4 stateZZM = imageLoad(stateT, ivec3(x, y, zm));\n"   110 "    // Sample the source state at (x,y,z).\n"   111 "    vec4 src = imageLoad(source, c);\n"   113 "    // Estimate second-order derivatives of state at (x,y,z).\n"   114 "    vec4 stateDXX = statePZZ - 2.0f*stateZZZ + stateMZZ;\n"   115 "    vec4 stateDYY = stateZPZ - 2.0f*stateZZZ + stateZMZ;\n"   116 "    vec4 stateDZZ = stateZZP - 2.0f*stateZZZ + stateZZM;\n"   118 "    // Compute advection.\n"   119 "    vec3 tcd = spaceDelta.xyz*(c - timeDelta.xyz*stateZZZ.xyz + 0.5f);\n"   120 "    vec4 advection = textureLod(stateTm1, tcd, 0.0f);\n"   122 "    // Update the state.\n"   123 "    imageStore(updateState, c, advection +\n"   124 "        (viscosityX*stateDXX + viscosityY*stateDYY + viscosityZ*stateDZZ +\n"   125 "        timeDelta.w*src));\n"   129 "cbuffer Parameters\n"   131 "    float4 spaceDelta;    // (dx, dy, dz, 0)\n"   132 "    float4 halfDivDelta;  // (0.5/dx, 0.5/dy, 0.5/dz, 0)\n"   133 "    float4 timeDelta;     // (dt/dx, dt/dy, dt/dz, dt)\n"   134 "    float4 viscosityX;    // (velVX, velVX, velVX, denVX)\n"   135 "    float4 viscosityY;    // (velVX, velVY, velVY, denVY)\n"   136 "    float4 viscosityZ;    // (velVZ, velVZ, velVZ, denVZ)\n"   137 "    float4 epsilon;       // (epsilonX, epsilonY, epsilonZ, epsilon0)\n"   140 "Texture3D<float4> source;\n"   141 "Texture3D<float4> stateTm1;\n"   142 "Texture3D<float4> stateT;\n"   143 "SamplerState advectionSampler;  // trilinear, clamp\n"   144 "RWTexture3D<float4> updateState;\n"   146 "[numthreads(NUM_X_THREADS, NUM_Y_THREADS, NUM_Z_THREADS)]\n"   147 "void CSMain(uint3 c : SV_DispatchThreadID)\n"   150 "    stateT.GetDimensions(dim.x, dim.y, dim.z);\n"   152 "    int x = int(c.x);\n"   153 "    int y = int(c.y);\n"   154 "    int z = int(c.z);\n"   155 "    int xm = max(x - 1, 0);\n"   156 "    int xp = min(x + 1, dim.x - 1);\n"   157 "    int ym = max(y - 1, 0);\n"   158 "    int yp = min(y + 1, dim.y - 1);\n"   159 "    int zm = max(z - 1, 0);\n"   160 "    int zp = min(z + 1, dim.z - 1);\n"   162 "    // Sample states at (x,y,z) and immediate neighbors.\n"   163 "    float4 stateZZZ = stateT[c];\n"   164 "    float4 statePZZ = stateT[int3(xp, y, z)];\n"   165 "    float4 stateMZZ = stateT[int3(xm, y, z)];\n"   166 "    float4 stateZPZ = stateT[int3(x, yp, z)];\n"   167 "    float4 stateZMZ = stateT[int3(x, ym, z)];\n"   168 "    float4 stateZZP = stateT[int3(x, y, zp)];\n"   169 "    float4 stateZZM = stateT[int3(x, y, zm)];\n"   171 "    // Sample the source state at (x,y,z).\n"   172 "    float4 src = source[c];\n"   174 "    // Estimate second-order derivatives of state at (x,y,z).\n"   175 "    float4 stateDXX = statePZZ - 2.0f*stateZZZ + stateMZZ;\n"   176 "    float4 stateDYY = stateZPZ - 2.0f*stateZZZ + stateZMZ;\n"   177 "    float4 stateDZZ = stateZZP - 2.0f*stateZZZ + stateZZM;\n"   179 "    // Compute advection.\n"   180 "    float3 tcd = spaceDelta.xyz*(c - timeDelta.xyz*stateZZZ.xyz + 0.5f);\n"   181 "    float4 advection = stateTm1.SampleLevel(advectionSampler, tcd, 0.0f);\n"   183 "    // Update the state.\n"   184 "    updateState[c] = advection +\n"   185 "        (viscosityX*stateDXX + viscosityY*stateDYY + +viscosityZ*stateDZZ +\n"   186 "        timeDelta.w*src);\n" std::shared_ptr< ComputeProgram > mComputeUpdateState
 
static std::string const * msSource[ProgramFactory::PF_NUM_API]
 
static std::string const msHLSLSource
 
std::shared_ptr< SamplerState > mAdvectionSampler
 
Fluid3UpdateState(std::shared_ptr< ProgramFactory > const &factory, int xSize, int ySize, int zSize, int numXThreads, int numYThreads, int numZThreads, std::shared_ptr< ConstantBuffer > const ¶meters)
 
std::shared_ptr< Texture3 > mUpdateState
 
static std::string const msGLSLSource
 
GLsizei GLsizei GLchar * source
 
GLsizei const GLchar *const * string
 
void Execute(std::shared_ptr< GraphicsEngine > const &engine, std::shared_ptr< Texture3 > const &source, std::shared_ptr< Texture3 > const &stateTm1, std::shared_ptr< Texture3 > const &stateT)