Particles mostly completed, still need to attach emitters to the correct node and handle NiBSPArrayController

c++11
scrawl 10 years ago
parent 79c2138e53
commit f8422c3ed4

@ -13,6 +13,7 @@
#include <components/files/configurationmanager.hpp>
#include <osgGA/TrackballManipulator>
#include <osg/PositionAttitudeTransform>
#include <osgDB/WriteFile>
@ -120,9 +121,13 @@ int main(int argc, char** argv)
for (unsigned int i=0; i<loader.mControllers.size(); ++i)
controllers.push_back(loader.mControllers[i]);
osg::PositionAttitudeTransform* trans = new osg::PositionAttitudeTransform;
root->addChild(trans);
for (int x=0; x<1;++x)
{
root->addChild(newNode);
//root->addChild(newNode);
trans->addChild(newNode);
}
viewer.setSceneData(root);
@ -140,6 +145,8 @@ int main(int argc, char** argv)
while (!viewer.done())
{
//trans->setAttitude(osg::Quat(viewer.getFrameStamp()->getSimulationTime()*5, osg::Vec3f(0,0,1)));
viewer.frame();
for (unsigned int i=0; i<controllers.size(); ++i)

@ -43,7 +43,7 @@ add_component_dir (nif
)
add_component_dir (nifosg
nifloader controller
nifloader controller particle
)
#add_component_dir (nifcache

@ -8,6 +8,8 @@
#include <sstream>
#include <map>
#include "niffile.hpp"
namespace Nif
{

@ -4,8 +4,11 @@
#include <osg/TexMat>
#include <osg/Material>
#include <osg/Texture2D>
#include <osgAnimation/MorphGeometry>
#include <osgParticle/Emitter>
#include <osg/io_utils>
#include <components/nif/data.hpp>
@ -331,5 +334,15 @@ void FlipControllerValue::setValue(float time)
tex->setImage(mTextures[curTexture].get());
}
ParticleSystemControllerValue::ParticleSystemControllerValue(osgParticle::Emitter *emitter, const Nif::NiParticleSystemController *ctrl)
: mEmitter(emitter), mEmitStart(ctrl->startTime), mEmitStop(ctrl->stopTime)
{
}
void ParticleSystemControllerValue::setValue(float time)
{
mEmitter->setEnabled(time >= mEmitStart && time < mEmitStop);
}
}

@ -25,6 +25,11 @@ namespace osg
class StateSet;
}
namespace osgParticle
{
class Emitter;
}
namespace osgAnimation
{
class MorphGeometry;
@ -236,6 +241,19 @@ namespace NifOsg
virtual void setValue(float time);
};
class ParticleSystemControllerValue : public ControllerValue
{
public:
ParticleSystemControllerValue(osgParticle::Emitter* emitter, const Nif::NiParticleSystemController* ctrl);
virtual void setValue(float time);
private:
osgParticle::Emitter* mEmitter;
float mEmitStart;
float mEmitStop;
};
}
#endif

@ -22,6 +22,11 @@
// particle
#include <osgParticle/ParticleSystem>
#include <osgParticle/ParticleSystemUpdater>
#include <osgParticle/ConstantRateCounter>
#include <osgParticle/ModularEmitter>
#include <osgParticle/Shooter>
#include <osgParticle/BoxPlacer>
#include <osgParticle/ModularProgram>
#include <osg/BlendFunc>
#include <osg/AlphaFunc>
@ -36,6 +41,8 @@
#include <components/nif/node.hpp>
#include "particle.hpp"
namespace
{
osg::Matrixf toMatrix(const Nif::Transformation& nifTrafo)
@ -124,6 +131,14 @@ namespace
class UpdateBone : public osg::NodeCallback
{
public:
UpdateBone() {}
UpdateBone(const UpdateBone& copy, const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY)
: osg::Object(copy, copyop), osg::NodeCallback(copy, copyop)
{
}
META_Object(NifOsg, UpdateBone)
// Callback method called by the NodeVisitor when visiting a node.
void operator()(osg::Node* node, osg::NodeVisitor* nv)
{
@ -157,6 +172,7 @@ namespace
: mSkelRoot(skelRootNode)
{
}
// TODO: add copy constructor
void operator()(osg::Node* node, osg::NodeVisitor* nv)
{
@ -179,44 +195,9 @@ namespace
traverse(node,nv);
}
private:
osg::Node* mSkelRoot;
};
// HACK: Particle doesn't allow setting the initial age, but we need this for loading the particle system state
class ParticleAgeSetter : public osgParticle::Particle
{
public:
ParticleAgeSetter(float age)
: Particle()
{
_t0 = age;
}
};
// Node callback used to set the inverse of the parent's world matrix on the MatrixTransform
// that the callback is attached to. Used for certain particle systems,
// so that the particles do not move with the node they are attached to.
class InverseWorldMatrix : public osg::NodeCallback
{
public:
InverseWorldMatrix()
{
}
void operator()(osg::Node* node, osg::NodeVisitor* nv)
{
if (nv && nv->getVisitorType() == osg::NodeVisitor::UPDATE_VISITOR)
{
osg::NodePath path = nv->getNodePath();
path.pop_back();
osg::MatrixTransform* trans = dynamic_cast<osg::MatrixTransform*>(node);
osg::Matrix worldMat = osg::computeLocalToWorld( path );
trans->setMatrix(osg::Matrix::inverse(worldMat));
}
traverse(node,nv);
}
// TODO: keeping this pointer will break when copying the scene graph; maybe retrieve it while visiting if it's NULL?
osg::Node* mSkelRoot;
};
osg::ref_ptr<osg::Geometry> handleMorphGeometry(const Nif::NiGeomMorpherController* morpher)
@ -338,6 +319,8 @@ namespace NifOsg
if (nifNode->recType == Nif::RC_NiBSAnimationNode)
animflags |= nifNode->flags;
if (nifNode->recType == Nif::RC_NiBSParticleNode)
particleflags |= nifNode->flags;
// Hide collision shapes, but don't skip the subgraph
// We still need to animate the hidden bones so the physics system can access them
@ -370,7 +353,7 @@ namespace NifOsg
}
if(nifNode->recType == Nif::RC_NiAutoNormalParticles || nifNode->recType == Nif::RC_NiRotatingParticles)
handleParticleSystem(nifNode, transformNode, particleflags, animflags);
handleParticleSystem(nifNode, transformNode, animflags, particleflags);
if (!nifNode->controller.empty())
handleNodeControllers(nifNode, transformNode, animflags);
@ -495,9 +478,10 @@ namespace NifOsg
}
}
void Loader::handleParticleSystem(const Nif::Node *nifNode, osg::Group *parentNode, int particleflags, int animflags)
void Loader::handleParticleSystem(const Nif::Node *nifNode, osg::Group *parentNode, int animflags, int particleflags)
{
osg::ref_ptr<osgParticle::ParticleSystem> partsys (new osgParticle::ParticleSystem);
partsys->setSortMode(osgParticle::ParticleSystem::SORT_BACK_TO_FRONT);
const Nif::NiAutoNormalParticlesData *particledata = NULL;
if(nifNode->recType == Nif::RC_NiAutoNormalParticles)
@ -507,6 +491,8 @@ namespace NifOsg
else
return;
// TODO: add special handling for NiBSPArrayController
const Nif::NiParticleSystemController* partctrl = NULL;
for (Nif::ControllerPtr ctrl = nifNode->controller; !ctrl.empty(); ctrl = ctrl->next)
{
@ -516,10 +502,18 @@ namespace NifOsg
partctrl = static_cast<Nif::NiParticleSystemController*>(ctrl.getPtr());
}
if (!partctrl)
{
std::cerr << "No particle controller found " << std::endl;
return;
}
osgParticle::ParticleProcessor::ReferenceFrame rf = (particleflags & Nif::NiNode::ParticleFlag_LocalSpace)
? osgParticle::ParticleProcessor::RELATIVE_RF
: osgParticle::ParticleProcessor::ABSOLUTE_RF;
// TODO: also take into account the transform by placement in the scene
osg::Matrix particletransform;
if (!(particleflags & Nif::NiNode::ParticleFlag_LocalSpace))
if (rf == osgParticle::ParticleProcessor::ABSOLUTE_RF)
particletransform = getWorldTransform(nifNode);
int i=0;
@ -528,11 +522,12 @@ namespace NifOsg
{
const Nif::NiParticleSystemController::Particle& particle = *it;
ParticleAgeSetter particletemplate(std::max(0.f, particle.lifespan - particle.lifetime));
ParticleAgeSetter particletemplate(std::max(0.f, particle.lifetime));
osgParticle::Particle* created = partsys->createParticle(&particletemplate);
created->setLifeTime(500);//std::max(0.f, particle.lifespan));
created->setVelocity(particle.velocity * particletransform);
created->setLifeTime(std::max(0.f, particle.lifespan));
osg::Vec4f adjustedVelocity = osg::Vec4f(particle.velocity, 0.f) * particletransform;
created->setVelocity(osg::Vec3f(adjustedVelocity.x(), adjustedVelocity.y(), adjustedVelocity.z()));
created->setPosition(particledata->vertices.at(particle.vertex) * particletransform);
osg::Vec4f partcolor (1.f,1.f,1.f,1.f);
@ -544,10 +539,81 @@ namespace NifOsg
created->setSizeRange(osgParticle::rangef(size, size));
}
osg::NodeVisitor visitor;
partsys->update(0.f, visitor);
partsys->setFrozen(true);
partsys->setSortMode(osgParticle::ParticleSystem::SORT_BACK_TO_FRONT);
partsys->getDefaultParticleTemplate().setSizeRange(osgParticle::rangef(partctrl->size, partctrl->size));
partsys->getDefaultParticleTemplate().setColorRange(osgParticle::rangev4(osg::Vec4f(1.f,1.f,1.f,1.f), osg::Vec4f(1.f,1.f,1.f,1.f)));
partsys->getDefaultParticleTemplate().setAlphaRange(osgParticle::rangef(1.f, 1.f));
// ---- emitter
osgParticle::ModularEmitter* emitter = new osgParticle::ModularEmitter;
emitter->setParticleSystem(partsys);
emitter->setReferenceFrame(osgParticle::ParticleProcessor::RELATIVE_RF);
osgParticle::ConstantRateCounter* counter = new osgParticle::ConstantRateCounter;
if (partctrl->emitFlags & Nif::NiParticleSystemController::NoAutoAdjust)
counter->setNumberOfParticlesPerSecondToCreate(partctrl->emitRate);
else
counter->setNumberOfParticlesPerSecondToCreate(partctrl->numParticles / (partctrl->lifetime + partctrl->lifetimeRandom/2));
emitter->setCounter(counter);
ParticleShooter* shooter = new ParticleShooter(partctrl->velocity - partctrl->velocityRandom*0.5f,
partctrl->velocity + partctrl->velocityRandom*0.5f,
partctrl->horizontalDir, partctrl->horizontalAngle,
partctrl->verticalDir, partctrl->verticalAngle,
partctrl->lifetime, partctrl->lifetimeRandom);
emitter->setShooter(shooter);
osgParticle::BoxPlacer* placer = new osgParticle::BoxPlacer;
placer->setXRange(-partctrl->offsetRandom.x(), partctrl->offsetRandom.x());
placer->setYRange(-partctrl->offsetRandom.y(), partctrl->offsetRandom.y());
placer->setZRange(-partctrl->offsetRandom.z(), partctrl->offsetRandom.z());
emitter->setPlacer(placer);
// TODO: attach to the emitter node
// Note: we also assume that the Emitter node is placed *before* the Particle node in the scene graph.
// This seems to be true for all NIF files in the game that I've checked, suggesting that NIFs work similar to OSG with regards to update order.
// If something ever violates this assumption, the worst that could happen is the culling being one frame late, which wouldn't be a disaster.
parentNode->addChild(emitter);
createController(partctrl, boost::shared_ptr<ControllerValue>(new ParticleSystemControllerValue(emitter, partctrl)), animflags);
// ----------- affector (must be after emitters in the scene graph)
osgParticle::ModularProgram* program = new osgParticle::ModularProgram;
program->setParticleSystem(partsys);
program->setReferenceFrame(rf);
parentNode->addChild(program);
for (Nif::ExtraPtr e = partctrl->extra; !e.empty(); e = e->extra)
{
if (e->recType == Nif::RC_NiParticleGrowFade)
{
const Nif::NiParticleGrowFade *gf = static_cast<const Nif::NiParticleGrowFade*>(e.getPtr());
GrowFadeAffector* affector = new GrowFadeAffector(gf->growTime, gf->fadeTime);
program->addOperator(affector);
}
else if (e->recType == Nif::RC_NiGravity)
{
const Nif::NiGravity* gr = static_cast<const Nif::NiGravity*>(e.getPtr());
GravityAffector* affector = new GravityAffector(gr);
program->addOperator(affector);
}
else if (e->recType == Nif::RC_NiParticleColorModifier)
{
const Nif::NiParticleColorModifier *cl = static_cast<const Nif::NiParticleColorModifier*>(e.getPtr());
const Nif::NiColorData *clrdata = cl->data.getPtr();
ParticleColorAffector* affector = new ParticleColorAffector(clrdata);
program->addOperator(affector);
}
else if (e->recType == Nif::RC_NiParticleRotation)
{
// TODO: Implement?
}
else
std::cerr << "Unhandled particle modifier " << e->recName << std::endl;
}
// -----------
std::vector<const Nif::Property*> materialProps;
collectMaterialProperties(nifNode, materialProps);
@ -558,7 +624,7 @@ namespace NifOsg
osg::ref_ptr<osg::Geode> geode (new osg::Geode);
geode->addDrawable(partsys);
if (particleflags & Nif::NiNode::ParticleFlag_LocalSpace)
if (rf == osgParticle::ParticleProcessor::RELATIVE_RF)
parentNode->addChild(geode);
else
{
@ -568,6 +634,7 @@ namespace NifOsg
parentNode->addChild(trans);
}
// particle system updater (after the emitters and affectors in the scene graph)
osgParticle::ParticleSystemUpdater* updater = new osgParticle::ParticleSystemUpdater;
updater->addParticleSystem(partsys);
parentNode->addChild(updater);
@ -870,6 +937,7 @@ namespace NifOsg
osgDB::ReaderWriter::ReadResult result = reader->readImage(*resourceManager->get(filename.c_str()), opts);
osg::Image* image = result.getImage();
osg::Texture2D* texture2d = new osg::Texture2D;
texture2d->setUnRefImageDataAfterApply(true);
texture2d->setImage(image);
unsigned int clamp = static_cast<unsigned int>(tex.clamp);

@ -61,7 +61,7 @@ namespace NifOsg
void handleProperty (const Nif::Property* property, const Nif::Node* nifNode,
osg::Node* node, std::map<int, int>& boundTextures, int animflags);
void handleParticleSystem(const Nif::Node* nifNode, osg::Group* parentNode, int particleflags, int animflags);
void handleParticleSystem(const Nif::Node* nifNode, osg::Group* parentNode, int animflags, int particleflags);
// Creates an osg::Geometry object for the given TriShape, populates it, and attaches it to the given node.
void handleTriShape(const Nif::NiTriShape* triShape, osg::Group* parentNode, const std::map<int, int>& boundTextures, int animflags);

@ -0,0 +1,192 @@
#include "particle.hpp"
#include <osg/MatrixTransform>
#include <components/nif/controlled.hpp>
#include <osg/io_utils>
namespace NifOsg
{
void InverseWorldMatrix::operator()(osg::Node *node, osg::NodeVisitor *nv)
{
if (nv && nv->getVisitorType() == osg::NodeVisitor::UPDATE_VISITOR)
{
osg::NodePath path = nv->getNodePath();
path.pop_back();
osg::MatrixTransform* trans = dynamic_cast<osg::MatrixTransform*>(node);
osg::Matrix worldMat = osg::computeLocalToWorld( path );
trans->setMatrix(osg::Matrix::inverse(worldMat));
}
traverse(node,nv);
}
ParticleShooter::ParticleShooter(float minSpeed, float maxSpeed, float horizontalDir, float horizontalAngle, float verticalDir, float verticalAngle, float lifetime, float lifetimeRandom)
: mMinSpeed(minSpeed), mMaxSpeed(maxSpeed), mHorizontalDir(horizontalDir)
, mHorizontalAngle(horizontalAngle), mVerticalDir(verticalDir), mVerticalAngle(verticalAngle)
, mLifetime(lifetime), mLifetimeRandom(lifetimeRandom)
{
}
ParticleShooter::ParticleShooter()
: mMinSpeed(0.f), mMaxSpeed(0.f), mHorizontalDir(0.f)
, mHorizontalAngle(0.f), mVerticalDir(0.f), mVerticalAngle(0.f)
, mLifetime(0.f), mLifetimeRandom(0.f)
{
}
ParticleShooter::ParticleShooter(const osgParticle::Shooter &copy, const osg::CopyOp &copyop)
{
*this = copy;
}
void ParticleShooter::shoot(osgParticle::Particle *particle) const
{
// NOTE: We do not use mDirection/mAngle for the initial direction.
float hdir = mHorizontalDir + mHorizontalAngle * (2.f * (std::rand() / static_cast<double>(RAND_MAX)) - 1.f);
float vdir = mVerticalDir + mVerticalAngle * (2.f * (std::rand() / static_cast<double>(RAND_MAX)) - 1.f);
osg::Vec3f dir = osg::Quat(hdir, osg::Vec3f(0,0,1)) * osg::Quat(vdir, osg::Vec3f(1,0,0))
// ^ Vec3f(0,1,0) according to nifskope, TODO: test in mw
* osg::Vec3f(0,0,1);
float vel = mMinSpeed + (mMaxSpeed - mMinSpeed) * std::rand() / static_cast<float>(RAND_MAX);
particle->setVelocity(dir * vel);
// Not supposed to set this here, but there doesn't seem to be a better way of doing it
particle->setLifeTime(mLifetime + mLifetimeRandom * std::rand() / static_cast<float>(RAND_MAX));
}
GrowFadeAffector::GrowFadeAffector(float growTime, float fadeTime)
: mGrowTime(growTime)
, mFadeTime(fadeTime)
, mCachedDefaultSize(0.f)
{
}
GrowFadeAffector::GrowFadeAffector()
: mGrowTime(0.f)
, mFadeTime(0.f)
, mCachedDefaultSize(0.f)
{
}
GrowFadeAffector::GrowFadeAffector(const GrowFadeAffector& copy, const osg::CopyOp& copyop)
: osgParticle::Operator(copy, copyop)
{
*this = copy;
}
void GrowFadeAffector::beginOperate(osgParticle::Program *program)
{
mCachedDefaultSize = program->getParticleSystem()->getDefaultParticleTemplate().getSizeRange().minimum;
}
void GrowFadeAffector::operate(osgParticle::Particle* particle, double /* dt */)
{
float size = mCachedDefaultSize;
if (particle->getAge() < mGrowTime && mGrowTime != 0.f)
size *= particle->getAge() / mGrowTime;
if (particle->getLifeTime() - particle->getAge() < mFadeTime && mFadeTime != 0.f)
size *= (particle->getLifeTime() - particle->getAge()) / mFadeTime;
particle->setSizeRange(osgParticle::rangef(size, size));
}
ParticleColorAffector::ParticleColorAffector(const Nif::NiColorData *clrdata)
: mData(*clrdata)
{
}
ParticleColorAffector::ParticleColorAffector()
{
}
ParticleColorAffector::ParticleColorAffector(const ParticleColorAffector &copy, const osg::CopyOp &copyop)
: osgParticle::Operator(copy, copyop)
{
*this = copy;
}
osg::Vec4f ParticleColorAffector::interpolate(const float time, const Nif::Vector4KeyMap::MapType &keys)
{
if(time <= keys.begin()->first)
return keys.begin()->second.mValue;
Nif::Vector4KeyMap::MapType::const_iterator it = keys.lower_bound(time);
if (it != keys.end())
{
float aTime = it->first;
const Nif::KeyT<osg::Vec4f>* aKey = &it->second;
assert (it != keys.begin()); // Shouldn't happen, was checked at beginning of this function
Nif::Vector4KeyMap::MapType::const_iterator last = --it;
float aLastTime = last->first;
const Nif::KeyT<osg::Vec4f>* aLastKey = &last->second;
float a = (time - aLastTime) / (aTime - aLastTime);
return aLastKey->mValue + ((aKey->mValue - aLastKey->mValue) * a);
}
else
return keys.rbegin()->second.mValue;
}
void ParticleColorAffector::operate(osgParticle::Particle* particle, double /* dt */)
{
float time = static_cast<float>(particle->getAge()/particle->getLifeTime());
osg::Vec4f color = interpolate(time, mData.mKeyMap.mKeys);
particle->setColorRange(osgParticle::rangev4(color, color));
}
GravityAffector::GravityAffector(const Nif::NiGravity *gravity)
: mForce(gravity->mForce)
, mType(static_cast<ForceType>(gravity->mType))
, mPosition(gravity->mPosition)
, mDirection(gravity->mDirection)
{
}
GravityAffector::GravityAffector()
: mForce(0), mType(Type_Wind)
{
}
GravityAffector::GravityAffector(const GravityAffector &copy, const osg::CopyOp &copyop)
: osgParticle::Operator(copy, copyop)
{
*this = copy;
}
void GravityAffector::beginOperate(osgParticle::Program* program)
{
bool absolute = (program->getReferenceFrame() == osgParticle::ParticleProcessor::ABSOLUTE_RF);
if (mType == Type_Wind)
mCachedWorldPositionDirection = absolute ? program->rotateLocalToWorld(mDirection) : mDirection;
else // Type_Point
mCachedWorldPositionDirection = absolute ? program->transformLocalToWorld(mPosition) : mPosition;
}
void GravityAffector::operate(osgParticle::Particle *particle, double dt)
{
switch (mType)
{
case Type_Wind:
particle->addVelocity(mCachedWorldPositionDirection * mForce * dt);
break;
case Type_Point:
{
osg::Vec3f diff = mCachedWorldPositionDirection - particle->getPosition();
diff.normalize();
particle->addVelocity(diff * mForce * dt);
break;
}
}
}
}

@ -0,0 +1,137 @@
#ifndef OPENMW_COMPONENTS_NIFOSG_PARTICLE_H
#define OPENMW_COMPONENTS_NIFOSG_PARTICLE_H
#include <osgParticle/Particle>
#include <osgParticle/Shooter>
#include <osgParticle/Operator>
#include <osg/NodeCallback>
#include <components/nif/nifkey.hpp>
#include <components/nif/data.hpp>
namespace Nif
{
class NiGravity;
}
namespace NifOsg
{
// HACK: Particle doesn't allow setting the initial age, but we need this for loading the particle system state
class ParticleAgeSetter : public osgParticle::Particle
{
public:
ParticleAgeSetter(float age)
: Particle()
{
_t0 = age;
}
};
// Node callback used to set the inverse of the parent's world matrix on the MatrixTransform
// that the callback is attached to. Used for certain particle systems,
// so that the particles do not move with the node they are attached to.
class InverseWorldMatrix : public osg::NodeCallback
{
public:
InverseWorldMatrix()
{
}
InverseWorldMatrix(const InverseWorldMatrix& copy, const osg::CopyOp& op = osg::CopyOp::SHALLOW_COPY)
: osg::NodeCallback(), osg::Object()
{
}
META_Object(NifOsg, InverseWorldMatrix)
void operator()(osg::Node* node, osg::NodeVisitor* nv);
};
class ParticleShooter : public osgParticle::Shooter
{
public:
ParticleShooter(float minSpeed, float maxSpeed, float horizontalDir, float horizontalAngle, float verticalDir, float verticalAngle,
float lifetime, float lifetimeRandom);
ParticleShooter();
ParticleShooter(const Shooter& copy, const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY);
META_Object(NifOsg, ParticleShooter)
virtual void shoot(osgParticle::Particle* particle) const;
private:
float mMinSpeed;
float mMaxSpeed;
float mHorizontalDir;
float mHorizontalAngle;
float mVerticalDir;
float mVerticalAngle;
float mLifetime;
float mLifetimeRandom;
};
class GrowFadeAffector : public osgParticle::Operator
{
public:
GrowFadeAffector(float growTime, float fadeTime);
GrowFadeAffector();
GrowFadeAffector(const GrowFadeAffector& copy, const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY);
META_Object(NifOsg, GrowFadeAffector)
virtual void beginOperate(osgParticle::Program* program);
virtual void operate(osgParticle::Particle* particle, double dt);
private:
float mGrowTime;
float mFadeTime;
float mCachedDefaultSize;
};
class ParticleColorAffector : public osgParticle::Operator
{
public:
ParticleColorAffector(const Nif::NiColorData* clrdata);
ParticleColorAffector();
ParticleColorAffector(const ParticleColorAffector& copy, const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY);
META_Object(NifOsg, ParticleColorAffector)
// TODO: very similar to vec3 version, refactor to a template
osg::Vec4f interpolate(const float time, const Nif::Vector4KeyMap::MapType& keys);
virtual void operate(osgParticle::Particle* particle, double dt);
private:
Nif::NiColorData mData;
};
class GravityAffector : public osgParticle::Operator
{
public:
GravityAffector(const Nif::NiGravity* gravity);
GravityAffector();
GravityAffector(const GravityAffector& copy, const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY);
META_Object(NifOsg, GravityAffector)
virtual void operate(osgParticle::Particle* particle, double dt);
virtual void beginOperate(osgParticle::Program *);
private:
float mForce;
enum ForceType {
Type_Wind,
Type_Point
};
ForceType mType;
osg::Vec3f mPosition;
osg::Vec3f mDirection;
osg::Vec3f mCachedWorldPositionDirection;
};
}
#endif
Loading…
Cancel
Save