[DEV] update new interface physic engine
This commit is contained in:
parent
c770439228
commit
4a64ced041
@ -420,12 +420,10 @@ void ege::Environement::onCallbackPeriodicCall(const ewol::event::Time& _event)
|
|||||||
}
|
}
|
||||||
//EGE_DEBUG("stepSimulation (start)");
|
//EGE_DEBUG("stepSimulation (start)");
|
||||||
///step the simulation
|
///step the simulation
|
||||||
if (m_physicEngine.getDynamicWorld() != nullptr) {
|
EGE_VERBOSE(" step simulation : " << curentDelta);
|
||||||
EGE_VERBOSE(" step simulation : " << curentDelta);
|
m_physicEngine.update(curentDelta);
|
||||||
m_physicEngine.getDynamicWorld()->stepSimulation(curentDelta);
|
//optional but useful: debug drawing
|
||||||
//optional but useful: debug drawing
|
m_physicEngine.debugDrawWorld();
|
||||||
m_physicEngine.getDynamicWorld()->debugDrawWorld();
|
|
||||||
}
|
|
||||||
EGE_VERBOSE(" Update particule engine");
|
EGE_VERBOSE(" Update particule engine");
|
||||||
m_particuleEngine.update(curentDelta);
|
m_particuleEngine.update(curentDelta);
|
||||||
// remove all element that requested it ...
|
// remove all element that requested it ...
|
||||||
|
@ -232,6 +232,18 @@ namespace ege {
|
|||||||
* @brief remove this element from the physique engine
|
* @brief remove this element from the physique engine
|
||||||
*/
|
*/
|
||||||
virtual void dynamicDisable() {};
|
virtual void dynamicDisable() {};
|
||||||
|
|
||||||
|
// TODO: next step:
|
||||||
|
/*
|
||||||
|
public:
|
||||||
|
void addComponent(const std::string& _name, const ememory::SharedPtr<ElementComponent>& _ref);
|
||||||
|
example: addComponent("physic", componentPhysic);
|
||||||
|
addComponent("ia", componentIA);
|
||||||
|
addComponent("render", componentRendering);
|
||||||
|
addComponent("group", componentFormationMovingSquare); // << here we add a group to control the moving interface of the IA ...
|
||||||
|
if we want to remove the IA, just remove the component,
|
||||||
|
if the display (render) change (unit upgrade) just the render is change, if it is invisible, just remove the render ...
|
||||||
|
*/
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -49,30 +49,28 @@ ege::ElementPhysic::~ElementPhysic() {
|
|||||||
// same ...
|
// same ...
|
||||||
dynamicDisable();
|
dynamicDisable();
|
||||||
removeShape();
|
removeShape();
|
||||||
delete m_body;
|
// Destroy the rigid body
|
||||||
|
m_dynamicsWorld->destroyRigidBody(m_body);
|
||||||
m_body = nullptr;
|
m_body = nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void ege::ElementPhysic::createRigidBody(float _mass, bool _static) {
|
void ege::ElementPhysic::createRigidBody(float _mass, bool _static) {
|
||||||
/// Create Dynamic Objects
|
// Initial position and orientation of the rigid body
|
||||||
btTransform startTransform;
|
rp3d::Vector3 initPosition(0.0, 3.0, 0.0);
|
||||||
startTransform.setIdentity();
|
rp3d::Quaternion initOrientation = rp3d::Quaternion::identity();
|
||||||
vec3 localInertia(0,0,0);
|
rp3d::Transform transform(initPosition, initOrientation);
|
||||||
//rigidbody is dynamic if and only if mass is non zero, otherwise static
|
|
||||||
if ( _mass != 0.0f
|
// Create a rigid body in the world
|
||||||
&& getShape()!=nullptr) {
|
m_body = m_dynamicsWorld->createRigidBody(transform);
|
||||||
getShape()->calculateLocalInertia(_mass, localInertia);
|
|
||||||
}
|
if (_static = true) {
|
||||||
EGE_ERROR("Create The RIGID body ...");
|
m_body->setType(STATIC);
|
||||||
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
//m_body->setType(KINEMATIC);
|
||||||
btDefaultMotionState* motionState = new btDefaultMotionState(startTransform);
|
// Disable gravity for this body
|
||||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(_mass, motionState, getShape(), localInertia);
|
m_body->enableGravity(false);
|
||||||
m_body = new btRigidBody(rbInfo);
|
} else {
|
||||||
m_body->setUserPointer((void*)this);
|
m_body->setType(DYNAMIC);
|
||||||
m_body->setAngularVelocity(vec3(0,0,0));
|
|
||||||
if (_static == true) {
|
|
||||||
m_body->setCollisionFlags(m_body->getCollisionFlags() | btCollisionObject::CF_STATIC_OBJECT);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -359,18 +357,18 @@ void ege::ElementPhysic::draw(int32_t _pass) {
|
|||||||
//EGE_INFO("draw : " << _pass );
|
//EGE_INFO("draw : " << _pass );
|
||||||
if (_pass == 0) {
|
if (_pass == 0) {
|
||||||
if( m_body != nullptr
|
if( m_body != nullptr
|
||||||
&& m_mesh != nullptr
|
&& m_mesh != nullptr) {
|
||||||
&& m_body->getMotionState() ) {
|
|
||||||
//EGE_INFO("element pos = " << getPosition());
|
//EGE_INFO("element pos = " << getPosition());
|
||||||
btScalar mmm[16];
|
float mmm[16];
|
||||||
btDefaultMotionState* myMotionState = (btDefaultMotionState*)m_body->getMotionState();
|
// Get the interpolated transform of the rigid body
|
||||||
myMotionState->m_graphicsWorldTrans.getOpenGLMatrix(mmm);
|
rp3d::Transform transform = m_body->getInterpolatedTransform();
|
||||||
|
// Get the OpenGL matrix array of the transform
|
||||||
|
transform.getOpenGLMatrix(matrix);
|
||||||
|
|
||||||
//EGE_INFO(" mat = " << mat4(mmm));
|
//EGE_INFO(" mat = " << mat4(mmm));
|
||||||
mat4 transformationMatrix(mmm);
|
mat4 transformationMatrix(mmm);
|
||||||
//mat4 transformationMatrix = mat4(mmm) * etk::matScale(vec3(20,20,20));
|
//mat4 transformationMatrix = mat4(mmm) * etk::matScale(vec3(20,20,20));
|
||||||
transformationMatrix.transpose();
|
// TODO: check this : transformationMatrix.transpose();
|
||||||
m_mesh->draw(transformationMatrix);
|
m_mesh->draw(transformationMatrix);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -382,11 +380,11 @@ void ege::ElementPhysic::dynamicEnable() {
|
|||||||
}
|
}
|
||||||
if(m_body != nullptr) {
|
if(m_body != nullptr) {
|
||||||
EGE_VERBOSE("dynamicEnable : RigidBody");
|
EGE_VERBOSE("dynamicEnable : RigidBody");
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->addRigidBody(m_body);
|
//m_env->getPhysicEngine().getDynamicWorld()->addRigidBody(m_body);
|
||||||
}
|
}
|
||||||
if(m_IA != nullptr) {
|
if(m_IA != nullptr) {
|
||||||
EGE_VERBOSE("dynamicEnable : IA");
|
EGE_VERBOSE("dynamicEnable : IA");
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->addAction(m_IA);
|
//m_env->getPhysicEngine().getDynamicWorld()->addAction(m_IA);
|
||||||
}
|
}
|
||||||
m_elementInPhysicsSystem = true;
|
m_elementInPhysicsSystem = true;
|
||||||
}
|
}
|
||||||
@ -397,13 +395,13 @@ void ege::ElementPhysic::dynamicDisable() {
|
|||||||
}
|
}
|
||||||
if(m_IA != nullptr) {
|
if(m_IA != nullptr) {
|
||||||
EGE_VERBOSE("dynamicDisable : IA");
|
EGE_VERBOSE("dynamicDisable : IA");
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->removeAction(m_IA);
|
//m_env->getPhysicEngine().getDynamicWorld()->removeAction(m_IA);
|
||||||
}
|
}
|
||||||
if(m_body != nullptr) {
|
if(m_body != nullptr) {
|
||||||
EGE_VERBOSE("dynamicDisable : RigidBody");
|
EGE_VERBOSE("dynamicDisable : RigidBody");
|
||||||
// Unlink element from the engine
|
// Unlink element from the engine
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->removeRigidBody(m_body);
|
//m_env->getPhysicEngine().getDynamicWorld()->removeRigidBody(m_body);
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->removeCollisionObject(m_body);
|
//m_env->getPhysicEngine().getDynamicWorld()->removeCollisionObject(m_body);
|
||||||
}
|
}
|
||||||
m_elementInPhysicsSystem = false;
|
m_elementInPhysicsSystem = false;
|
||||||
}
|
}
|
||||||
@ -415,11 +413,11 @@ void ege::ElementPhysic::iaEnable() {
|
|||||||
}
|
}
|
||||||
m_IA = new localIA(*this);
|
m_IA = new localIA(*this);
|
||||||
if (m_IA == nullptr) {
|
if (m_IA == nullptr) {
|
||||||
EGE_ERROR("Can not start the IA == > allocation error");
|
EGE_ERROR("Can not start the IA == > allocation error");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (m_elementInPhysicsSystem == true) {
|
if (m_elementInPhysicsSystem == true) {
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->addAction(m_IA);
|
//m_env->getPhysicEngine().getDynamicWorld()->addAction(m_IA);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -429,9 +427,9 @@ void ege::ElementPhysic::iaDisable() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (m_elementInPhysicsSystem == true) {
|
if (m_elementInPhysicsSystem == true) {
|
||||||
m_env->getPhysicEngine().getDynamicWorld()->removeAction(m_IA);
|
//m_env->getPhysicEngine().getDynamicWorld()->removeAction(m_IA);
|
||||||
}
|
}
|
||||||
// remove IA :
|
// remove IA:
|
||||||
delete(m_IA);
|
delete(m_IA);
|
||||||
m_IA = nullptr;
|
m_IA = nullptr;
|
||||||
}
|
}
|
||||||
@ -442,10 +440,10 @@ void ege::ElementPhysic::setMass(float _value) {
|
|||||||
}
|
}
|
||||||
vec3 localInertia(0,0,0);
|
vec3 localInertia(0,0,0);
|
||||||
if (_value != 0.0f && getShape()!=nullptr) {
|
if (_value != 0.0f && getShape()!=nullptr) {
|
||||||
getShape()->calculateLocalInertia(_value, localInertia);
|
//getShape()->calculateLocalInertia(_value, localInertia);
|
||||||
EWOL_ERROR("Update inertia calculated : " << localInertia);
|
EWOL_ERROR("Update inertia calculated : " << localInertia);
|
||||||
}
|
}
|
||||||
m_body->setMassProps(_value, localInertia);
|
//m_body->setMassProps(_value, localInertia);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ege::ElementPhysic::setLinearVelocity(const vec3& _value) {
|
void ege::ElementPhysic::setLinearVelocity(const vec3& _value) {
|
||||||
@ -453,7 +451,10 @@ void ege::ElementPhysic::setLinearVelocity(const vec3& _value) {
|
|||||||
EGE_WARNING("no body");
|
EGE_WARNING("no body");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
m_body->setLinearVelocity(_value);
|
// Force vector (in Newton)
|
||||||
|
rp3d::Vector3 force(_value.x(), _value.y(), _value.z());
|
||||||
|
// Apply a force to the center of the body
|
||||||
|
m_body->applyForceToCenter(force);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ege::ElementPhysic::setTorqueImpulse(const vec3& _value) {
|
void ege::ElementPhysic::setTorqueImpulse(const vec3& _value) {
|
||||||
@ -461,7 +462,10 @@ void ege::ElementPhysic::setTorqueImpulse(const vec3& _value) {
|
|||||||
EGE_WARNING("no body");
|
EGE_WARNING("no body");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
m_body->applyTorqueImpulse(_value);
|
// Torque vector
|
||||||
|
rp3d::Vector3 torque(_value.x(), _value.y(), _value.z());
|
||||||
|
// Apply a torque to the body
|
||||||
|
m_body->applyTorque(torque);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ege::ElementPhysic::setAngularVelocity(const vec3& _value) {
|
void ege::ElementPhysic::setAngularVelocity(const vec3& _value) {
|
||||||
@ -469,7 +473,7 @@ void ege::ElementPhysic::setAngularVelocity(const vec3& _value) {
|
|||||||
EGE_WARNING("no body");
|
EGE_WARNING("no body");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
m_body->setAngularVelocity(_value);
|
//m_body->setAngularVelocity(_value);
|
||||||
}
|
}
|
||||||
|
|
||||||
btQuaternion ege::ElementPhysic::getOrientation() const {
|
btQuaternion ege::ElementPhysic::getOrientation() const {
|
||||||
@ -477,13 +481,16 @@ btQuaternion ege::ElementPhysic::getOrientation() const {
|
|||||||
EGE_WARNING("no body");
|
EGE_WARNING("no body");
|
||||||
return btQuaternion(0,0,0,0);
|
return btQuaternion(0,0,0,0);
|
||||||
}
|
}
|
||||||
return m_body->getOrientation();
|
//return m_body->getOrientation();
|
||||||
|
return btQuaternion(0,0,0,0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ege::ElementPhysic::setCollisionDetectionStatus(bool _status) {
|
void ege::ElementPhysic::setCollisionDetectionStatus(bool _status) {
|
||||||
if (m_body == nullptr) {
|
if (m_body == nullptr) {
|
||||||
EGE_WARNING("no body");
|
EGE_WARNING("no body");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
/*
|
||||||
if (m_detectCollisionEnable == _status) {
|
if (m_detectCollisionEnable == _status) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -495,5 +502,6 @@ void ege::ElementPhysic::setCollisionDetectionStatus(bool _status) {
|
|||||||
m_body->setCollisionFlags(m_body->getCollisionFlags() - btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
|
m_body->setCollisionFlags(m_body->getCollisionFlags() - btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -19,7 +19,6 @@
|
|||||||
#include <ege/Environement.hpp>
|
#include <ege/Environement.hpp>
|
||||||
#include <ege/elements/Element.hpp>
|
#include <ege/elements/Element.hpp>
|
||||||
|
|
||||||
#include <LinearMath/btDefaultMotionState.h>
|
|
||||||
|
|
||||||
#define INDEX_RIGHT_AXIS (0)
|
#define INDEX_RIGHT_AXIS (0)
|
||||||
#define INDEX_FORWARD_AXIS (1)
|
#define INDEX_FORWARD_AXIS (1)
|
||||||
@ -32,7 +31,7 @@ namespace ege {
|
|||||||
private:
|
private:
|
||||||
static void FunctionFreeShape(void* _pointer);
|
static void FunctionFreeShape(void* _pointer);
|
||||||
protected:
|
protected:
|
||||||
btRigidBody* m_body; //!< all the element have a body == > otherwise it will be not manage with this system...
|
rp3d::RigidBody* m_body; //!< all the element have a body == > otherwise it will be not manage with this system...
|
||||||
public:
|
public:
|
||||||
void createRigidBody(float _mass=400000000.0f, bool _static=false);
|
void createRigidBody(float _mass=400000000.0f, bool _static=false);
|
||||||
public:
|
public:
|
||||||
|
@ -49,70 +49,47 @@ static bool handleContactsProcess(btManifoldPoint& _point, btCollisionObject* _b
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
ege::physics::Engine::Engine() {
|
ege::physics::Engine::Engine():
|
||||||
setBulletConfig();
|
m_dynamicsWorld(nullptr),
|
||||||
// set callback for collisions ...
|
m_accumulator(0.0f) {
|
||||||
gContactProcessedCallback = (ContactProcessedCallback)handleContactsProcess;
|
// Start engine with no gravity
|
||||||
|
//rp3d::Vector3 gravity(0.0, -9.81, 0.0); // generic earth gravity
|
||||||
|
rp3d::Vector3 gravity(0.0f, 0.0f, 0.0f);
|
||||||
|
// Create the dynamics world
|
||||||
|
m_dynamicsWorld = new rp3d::DynamicsWorld(gravity);
|
||||||
}
|
}
|
||||||
|
|
||||||
ege::physics::Engine::~Engine() {
|
ege::physics::Engine::~Engine() {
|
||||||
/*
|
if (m_dynamicsWorld != nullptr) {
|
||||||
m_dynamicsWorld.release();
|
delete m_dynamicsWorld;
|
||||||
m_solver.release();
|
m_dynamicsWorld = nullptr;
|
||||||
m_broadphase.release();
|
|
||||||
m_dispatcher.release();
|
|
||||||
m_collisionConfiguration.release();
|
|
||||||
*/
|
|
||||||
}
|
|
||||||
|
|
||||||
void ege::physics::Engine::setBulletConfig(ememory::SharedPtr<btDefaultCollisionConfiguration> _collisionConfiguration,
|
|
||||||
ememory::SharedPtr<btCollisionDispatcher> _dispatcher,
|
|
||||||
ememory::SharedPtr<btBroadphaseInterface> _broadphase,
|
|
||||||
ememory::SharedPtr<btConstraintSolver> _solver,
|
|
||||||
ememory::SharedPtr<btDynamicsWorld> _dynamicsWorld) {
|
|
||||||
if (_collisionConfiguration != nullptr) {
|
|
||||||
m_collisionConfiguration = _collisionConfiguration;
|
|
||||||
} else {
|
|
||||||
m_collisionConfiguration = ememory::makeShared<btDefaultCollisionConfiguration>();
|
|
||||||
}
|
}
|
||||||
///use the default collision dispatcher.
|
|
||||||
if (_dispatcher != nullptr) {
|
|
||||||
m_dispatcher = _dispatcher;
|
|
||||||
} else {
|
|
||||||
m_dispatcher = ememory::makeShared<btCollisionDispatcher>(m_collisionConfiguration.get());
|
|
||||||
}
|
|
||||||
if (_broadphase != nullptr) {
|
|
||||||
m_broadphase = _broadphase;
|
|
||||||
} else {
|
|
||||||
m_broadphase = ememory::makeShared<btDbvtBroadphase>();
|
|
||||||
}
|
|
||||||
|
|
||||||
///the default constraint solver.
|
|
||||||
if (_solver != nullptr) {
|
|
||||||
m_solver = _solver;
|
|
||||||
} else {
|
|
||||||
m_solver = ememory::makeShared<btSequentialImpulseConstraintSolver>();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (_dynamicsWorld != nullptr) {
|
|
||||||
m_dynamicsWorld = _dynamicsWorld;
|
|
||||||
} else {
|
|
||||||
m_dynamicsWorld = ememory::makeShared<btDiscreteDynamicsWorld>(m_dispatcher.get(),m_broadphase.get(),m_solver.get(),m_collisionConfiguration.get());
|
|
||||||
// By default we set no gravity
|
|
||||||
m_dynamicsWorld->setGravity(btVector3(0,0,0));
|
|
||||||
}
|
|
||||||
//m_env.setDynamicWorld(m_dynamicsWorld);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ege::physics::Engine::setGravity(const vec3& _axePower) {
|
void ege::physics::Engine::setGravity(const vec3& _axePower) {
|
||||||
if (m_dynamicsWorld != nullptr) {
|
if (m_dynamicsWorld != nullptr) {
|
||||||
m_dynamicsWorld->setGravity(_axePower);
|
m_dynamicsWorld->setGravity(rp3d::Vector3(_axePower.x(), _axePower.y(), _axePower.z()));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Constant physics time step
|
||||||
|
const float timeStep = 1.0 / 60.0;
|
||||||
|
|
||||||
|
void ege::physics::Engine::update(float _delta) {
|
||||||
|
// Add the time difference in the accumulator
|
||||||
|
m_accumulator += _delta;
|
||||||
|
// While there is enough accumulated time to take one or several physics steps
|
||||||
|
while (m_accumulator >= timeStep) {
|
||||||
|
// Update the Dynamics world with a constant time step
|
||||||
|
m_dynamicsWorld->update(timeStep);
|
||||||
|
// Decrease the accumulated time
|
||||||
|
m_accumulator -= timeStep;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// some doccumantation : http://www.bulletphysics.org/mediawiki-1.5.8/index.php?title=Collision_Callbacks_and_Triggers
|
|
||||||
std::vector<ege::physics::Engine::collisionPoints> ege::physics::Engine::getListOfCollision() {
|
std::vector<ege::physics::Engine::collisionPoints> ege::physics::Engine::getListOfCollision() {
|
||||||
std::vector<collisionPoints> out;
|
std::vector<collisionPoints> out;
|
||||||
|
/*
|
||||||
if (m_dynamicsWorld != nullptr) {
|
if (m_dynamicsWorld != nullptr) {
|
||||||
int32_t numManifolds = m_dynamicsWorld->getDispatcher()->getNumManifolds();
|
int32_t numManifolds = m_dynamicsWorld->getDispatcher()->getNumManifolds();
|
||||||
for (int i=0;i<numManifolds;i++) {
|
for (int i=0;i<numManifolds;i++) {
|
||||||
@ -138,5 +115,6 @@ std::vector<ege::physics::Engine::collisionPoints> ege::physics::Engine::getList
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
@ -22,52 +22,15 @@ namespace ege {
|
|||||||
#include <gale/Dimension.hpp>
|
#include <gale/Dimension.hpp>
|
||||||
|
|
||||||
|
|
||||||
class btBroadphaseInterface;
|
|
||||||
class btCollisionShape;
|
|
||||||
class btOverlappingPairCache;
|
|
||||||
class btCollisionDispatcher;
|
|
||||||
class btConstraintSolver;
|
|
||||||
struct btCollisionAlgorithmCreateFunc;
|
|
||||||
class btDefaultCollisionConfiguration;
|
|
||||||
class btDynamicsWorld;
|
|
||||||
#include <LinearMath/btScalar.h>
|
|
||||||
class btVector3;
|
|
||||||
|
|
||||||
|
|
||||||
//#include <ege/elements/Element.h>
|
|
||||||
|
|
||||||
namespace ege {
|
namespace ege {
|
||||||
namespace physics {
|
namespace physics {
|
||||||
class Engine {
|
class Engine {
|
||||||
private:
|
private:
|
||||||
///this is the most important class
|
rp3d::DynamicsWorld* m_dynamicsWorld;
|
||||||
ememory::SharedPtr<btDefaultCollisionConfiguration> m_collisionConfiguration;
|
float m_accumulator; // limit call of the step rendering
|
||||||
ememory::SharedPtr<btCollisionDispatcher> m_dispatcher;
|
|
||||||
ememory::SharedPtr<btBroadphaseInterface> m_broadphase;
|
|
||||||
ememory::SharedPtr<btConstraintSolver> m_solver;
|
|
||||||
ememory::SharedPtr<btDynamicsWorld> m_dynamicsWorld;
|
|
||||||
public:
|
public:
|
||||||
Engine();
|
Engine();
|
||||||
~Engine();
|
~Engine();
|
||||||
void setBulletConfig(ememory::SharedPtr<btDefaultCollisionConfiguration> _collisionConfiguration=nullptr,
|
|
||||||
ememory::SharedPtr<btCollisionDispatcher> _dispatcher=nullptr,
|
|
||||||
ememory::SharedPtr<btBroadphaseInterface> _broadphase=nullptr,
|
|
||||||
ememory::SharedPtr<btConstraintSolver> _solver=nullptr,
|
|
||||||
ememory::SharedPtr<btDynamicsWorld> _dynamicsWorld=nullptr);
|
|
||||||
/**
|
|
||||||
* @brief set the curent world
|
|
||||||
* @param[in] _newWorld Pointer on the current world
|
|
||||||
*/
|
|
||||||
void setDynamicWorld(const ememory::SharedPtr<btDynamicsWorld>& _newWorld) {
|
|
||||||
m_dynamicsWorld=_newWorld;
|
|
||||||
};
|
|
||||||
/**
|
|
||||||
* @brief get the curent world
|
|
||||||
* @return pointer on the current world
|
|
||||||
*/
|
|
||||||
ememory::SharedPtr<btDynamicsWorld> getDynamicWorld() {
|
|
||||||
return m_dynamicsWorld;
|
|
||||||
};
|
|
||||||
public:
|
public:
|
||||||
// Define a collision point ==> for debug only ...
|
// Define a collision point ==> for debug only ...
|
||||||
//! @not_in_doc
|
//! @not_in_doc
|
||||||
@ -99,6 +62,12 @@ namespace ege {
|
|||||||
* @param[in] _axePower energy of this gravity
|
* @param[in] _axePower energy of this gravity
|
||||||
*/
|
*/
|
||||||
void setGravity(const vec3& _axePower);
|
void setGravity(const vec3& _axePower);
|
||||||
|
// update cycle
|
||||||
|
void update(float _delta);
|
||||||
|
|
||||||
|
void debugDrawWorld() {
|
||||||
|
// TODO: later ...
|
||||||
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -15,18 +15,6 @@
|
|||||||
#include <ewol/object/Manager.hpp>
|
#include <ewol/object/Manager.hpp>
|
||||||
#include <gale/renderer/openGL/openGL.hpp>
|
#include <gale/renderer/openGL/openGL.hpp>
|
||||||
#include <etk/math/Matrix4.hpp>
|
#include <etk/math/Matrix4.hpp>
|
||||||
#include <BulletDynamics/Dynamics/btRigidBody.h>
|
|
||||||
#include <LinearMath/btDefaultMotionState.h>
|
|
||||||
#include <BulletDynamics/Dynamics/btDynamicsWorld.h>
|
|
||||||
#include <BulletCollision/CollisionShapes/btCollisionShape.h>
|
|
||||||
#include <LinearMath/btIDebugDraw.h>
|
|
||||||
#include <btBulletCollisionCommon.h>
|
|
||||||
#include <BulletCollision/CollisionShapes/btConvexPolyhedron.h>
|
|
||||||
#include <BulletCollision/CollisionShapes/btShapeHull.h>
|
|
||||||
#include <LinearMath/btTransformUtil.h>
|
|
||||||
#include <LinearMath/btIDebugDraw.h>
|
|
||||||
#include <btBulletDynamicsCommon.h>
|
|
||||||
#include <BulletCollision/CollisionDispatch/btCollisionObject.h>
|
|
||||||
|
|
||||||
namespace etk {
|
namespace etk {
|
||||||
template<> std::string to_string<ememory::SharedPtr<ewol::resource::Colored3DObject> >(const ememory::SharedPtr<ewol::resource::Colored3DObject>& _value) {
|
template<> std::string to_string<ememory::SharedPtr<ewol::resource::Colored3DObject> >(const ememory::SharedPtr<ewol::resource::Colored3DObject>& _value) {
|
||||||
@ -84,7 +72,7 @@ void ege::widget::Scene::onDraw() {
|
|||||||
g_startTime = echrono::Steady::now();
|
g_startTime = echrono::Steady::now();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// draw constant object :
|
// draw constant object:
|
||||||
{
|
{
|
||||||
mat4 tmpMatrix;
|
mat4 tmpMatrix;
|
||||||
for (auto &it : m_env->getStaticMeshToDraw()) {
|
for (auto &it : m_env->getStaticMeshToDraw()) {
|
||||||
@ -102,55 +90,49 @@ void ege::widget::Scene::onDraw() {
|
|||||||
}
|
}
|
||||||
//EGE_DEBUG("Draw (start)");
|
//EGE_DEBUG("Draw (start)");
|
||||||
mat4 tmpMatrix;
|
mat4 tmpMatrix;
|
||||||
ememory::SharedPtr<btDynamicsWorld> world = m_env->getPhysicEngine().getDynamicWorld();
|
m_env->getOrderedElementForDisplay(m_displayElementOrdered, camera->getEye(), camera->getViewVector());
|
||||||
if (world != nullptr) {
|
EGE_VERBOSE("DRAW : " << m_displayElementOrdered.size() << "/" << m_env->getElement().size() << " elements");
|
||||||
|
|
||||||
m_env->getOrderedElementForDisplay(m_displayElementOrdered, camera->getEye(), camera->getViewVector());
|
// TODO : remove this == > no more needed ==> checked in the generate the list of the element ordered
|
||||||
EGE_VERBOSE("DRAW : " << m_displayElementOrdered.size() << "/" << m_env->getElement().size() << " elements");
|
for (size_t iii=0; iii<m_displayElementOrdered.size(); iii++) {
|
||||||
|
m_displayElementOrdered[iii].element->preCalculationDraw(*camera);
|
||||||
// TODO : remove this == > no more needed ==> checked in the generate the list of the element ordered
|
}
|
||||||
|
// note : the first pass is done at the reverse way to prevent multiple display od the same point in the screen
|
||||||
|
// (and we remember that the first pass is to display all the non transparent elements)
|
||||||
|
for (int32_t iii=m_displayElementOrdered.size()-1; iii >= 0; iii--) {
|
||||||
|
m_displayElementOrdered[iii].element->draw(0);
|
||||||
|
}
|
||||||
|
// for the other pass the user can draw transparent elements ...
|
||||||
|
for (int32_t pass=1; pass <= NUMBER_OF_SUB_PASS+1; pass++) {
|
||||||
for (size_t iii=0; iii<m_displayElementOrdered.size(); iii++) {
|
for (size_t iii=0; iii<m_displayElementOrdered.size(); iii++) {
|
||||||
m_displayElementOrdered[iii].element->preCalculationDraw(*camera);
|
m_displayElementOrdered[iii].element->draw(pass);
|
||||||
}
|
}
|
||||||
// note : the first pass is done at the reverse way to prevent multiple display od the same point in the screen
|
}
|
||||||
// (and we remember that the first pass is to display all the non transparent elements)
|
if (propertyDebugPhysic.get() == true) {
|
||||||
|
// Draw debug ... (Object)
|
||||||
for (int32_t iii=m_displayElementOrdered.size()-1; iii >= 0; iii--) {
|
for (int32_t iii=m_displayElementOrdered.size()-1; iii >= 0; iii--) {
|
||||||
m_displayElementOrdered[iii].element->draw(0);
|
m_displayElementOrdered[iii].element->drawDebug(m_debugDrawProperty, camera);
|
||||||
}
|
}
|
||||||
// for the other pass the user can draw transparent elements ...
|
// Draw debug ... (Camera)
|
||||||
for (int32_t pass=1; pass <= NUMBER_OF_SUB_PASS+1; pass++) {
|
/*
|
||||||
for (size_t iii=0; iii<m_displayElementOrdered.size(); iii++) {
|
std::map<std::string, ememory::SharedPtr<ege::Camera>> listCamera = m_env->getCameraList();
|
||||||
m_displayElementOrdered[iii].element->draw(pass);
|
for (auto &itCam : listCamera) {
|
||||||
|
if (itCam.second != nullptr) {
|
||||||
|
itCam.second->drawDebug(m_debugDrawProperty, camera);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (propertyDebugPhysic.get() == true) {
|
*/
|
||||||
// Draw debug ... (Object)
|
}
|
||||||
for (int32_t iii=m_displayElementOrdered.size()-1; iii >= 0; iii--) {
|
if (propertyDebugNormal.get() == true) {
|
||||||
m_displayElementOrdered[iii].element->drawDebug(m_debugDrawProperty, camera);
|
// Draw debug ... (Object)
|
||||||
}
|
for (int32_t iii=m_displayElementOrdered.size()-1; iii >= 0; iii--) {
|
||||||
// Draw debug ... (Camera)
|
m_displayElementOrdered[iii].element->drawNormalDebug(m_debugDrawProperty, camera);
|
||||||
/*
|
|
||||||
std::map<std::string, ememory::SharedPtr<ege::Camera>> listCamera = m_env->getCameraList();
|
|
||||||
for (auto &itCam : listCamera) {
|
|
||||||
if (itCam.second != nullptr) {
|
|
||||||
itCam.second->drawDebug(m_debugDrawProperty, camera);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
}
|
}
|
||||||
if (propertyDebugNormal.get() == true) {
|
}
|
||||||
// Draw debug ... (Object)
|
|
||||||
for (int32_t iii=m_displayElementOrdered.size()-1; iii >= 0; iii--) {
|
if (propertyDebugApplication.get() == true) {
|
||||||
m_displayElementOrdered[iii].element->drawNormalDebug(m_debugDrawProperty, camera);
|
// Draw debug ... (User)
|
||||||
}
|
signalDisplayDebug.emit(m_debugDrawProperty);
|
||||||
}
|
|
||||||
|
|
||||||
if (propertyDebugApplication.get() == true) {
|
|
||||||
// Draw debug ... (User)
|
|
||||||
signalDisplayDebug.emit(m_debugDrawProperty);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
EGE_WARNING("No Dynamic world ...");
|
|
||||||
}
|
}
|
||||||
if (camera != nullptr) {
|
if (camera != nullptr) {
|
||||||
m_env->getParticuleEngine().draw(*camera);
|
m_env->getParticuleEngine().draw(*camera);
|
||||||
@ -165,13 +147,6 @@ void ege::widget::Scene::onDraw() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// I really does not know what is this ...
|
|
||||||
btRigidBody& btActionInterface::getFixedBody() {
|
|
||||||
static btRigidBody s_fixed(0, 0,0);
|
|
||||||
s_fixed.setMassProps(btScalar(0.),btVector3(btScalar(0.),btScalar(0.),btScalar(0.)));
|
|
||||||
return s_fixed;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ege::widget::Scene::periodicCall(const ewol::event::Time& _event) {
|
void ege::widget::Scene::periodicCall(const ewol::event::Time& _event) {
|
||||||
markToRedraw();
|
markToRedraw();
|
||||||
}
|
}
|
||||||
|
@ -16,17 +16,6 @@
|
|||||||
#include <gale/resource/Manager.hpp>
|
#include <gale/resource/Manager.hpp>
|
||||||
#include <ege/elements/Element.hpp>
|
#include <ege/elements/Element.hpp>
|
||||||
#include <gale/Dimension.hpp>
|
#include <gale/Dimension.hpp>
|
||||||
|
|
||||||
class btBroadphaseInterface;
|
|
||||||
class btCollisionShape;
|
|
||||||
class btOverlappingPairCache;
|
|
||||||
class btCollisionDispatcher;
|
|
||||||
class btConstraintSolver;
|
|
||||||
struct btCollisionAlgorithmCreateFunc;
|
|
||||||
class btDefaultCollisionConfiguration;
|
|
||||||
class btDynamicsWorld;
|
|
||||||
#include <LinearMath/btScalar.h>
|
|
||||||
class btVector3;
|
|
||||||
#include <ewol/widget/Widget.hpp>
|
#include <ewol/widget/Widget.hpp>
|
||||||
#include <esignal/Signal.hpp>
|
#include <esignal/Signal.hpp>
|
||||||
|
|
||||||
|
@ -65,7 +65,7 @@ def configure(target, my_module):
|
|||||||
])
|
])
|
||||||
my_module.copy_path('data/ParticuleMesh.*')
|
my_module.copy_path('data/ParticuleMesh.*')
|
||||||
my_module.copy_path('data/material3D.*')
|
my_module.copy_path('data/material3D.*')
|
||||||
my_module.add_depend(['ewol', 'bullet-physics', 'echrono'])
|
my_module.add_depend(['ewol', 'ephysics', 'echrono'])
|
||||||
my_module.add_flag('c++', [
|
my_module.add_flag('c++', [
|
||||||
'-Wno-write-strings',
|
'-Wno-write-strings',
|
||||||
'-Wmissing-field-initializers',
|
'-Wmissing-field-initializers',
|
||||||
|
Loading…
x
Reference in New Issue
Block a user