git-svn-id: https://reactphysics3d.googlecode.com/svn/trunk@176 92aac97c-a6ce-11dd-a772-7fcde58d38e6
This commit is contained in:
parent
7ed1e2c241
commit
83d82b7699
|
@ -42,14 +42,14 @@ class Body {
|
||||||
Body(const Body& body); // Copy-constructor
|
Body(const Body& body); // Copy-constructor
|
||||||
virtual ~Body(); // Destructor
|
virtual ~Body(); // Destructor
|
||||||
|
|
||||||
Kilogram getMass(); // Return the mass of the body
|
Kilogram getMass() const; // Return the mass of the body
|
||||||
void setMass(Kilogram mass); // Set the mass of the body
|
void setMass(Kilogram mass); // Set the mass of the body
|
||||||
};
|
};
|
||||||
|
|
||||||
// --- Inlines function --- //
|
// --- Inlines function --- //
|
||||||
|
|
||||||
// Method that return the mass of the body
|
// Method that return the mass of the body
|
||||||
inline Kilogram Body::getMass() {
|
inline Kilogram Body::getMass() const {
|
||||||
return mass;
|
return mass;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -86,7 +86,7 @@ void BodyState::computeAtTime(const Time& timeStep, const DerivativeBodyState& l
|
||||||
// Return the force on the body at time t
|
// Return the force on the body at time t
|
||||||
Vector3D BodyState::computeForce(Time time) const {
|
Vector3D BodyState::computeForce(Time time) const {
|
||||||
// TODO : Implement this method
|
// TODO : Implement this method
|
||||||
return force + Vector3D(0.0, 0.0, 0.0);
|
return force * (1.0 / massInverse.getValue());
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the torque on the body at time
|
// Return the torque on the body at time
|
||||||
|
|
|
@ -71,7 +71,7 @@ class BodyState {
|
||||||
void setInertiaTensorInverse(const Matrix3x3& inertiaTensorInverse); // Set the inverse of the inertia tensor
|
void setInertiaTensorInverse(const Matrix3x3& inertiaTensorInverse); // Set the inverse of the inertia tensor
|
||||||
Vector3D getForce() const; // Return the force over the body
|
Vector3D getForce() const; // Return the force over the body
|
||||||
void setForce(const Vector3D force); // Set the force over the body
|
void setForce(const Vector3D force); // Set the force over the body
|
||||||
|
Kilogram getMassInverse() const; // TODO : Delete this
|
||||||
void recalculate(); // Recalculate the secondary values
|
void recalculate(); // Recalculate the secondary values
|
||||||
// of the BodyState from the primary ones
|
// of the BodyState from the primary ones
|
||||||
void computeAtTime(const Time& timeStep,
|
void computeAtTime(const Time& timeStep,
|
||||||
|
@ -155,7 +155,11 @@ inline Vector3D BodyState::getForce() const {
|
||||||
// Set the force over the body
|
// Set the force over the body
|
||||||
inline void BodyState::setForce(const Vector3D force) {
|
inline void BodyState::setForce(const Vector3D force) {
|
||||||
this->force = force;
|
this->force = force;
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO : Delete this
|
||||||
|
inline Kilogram BodyState::getMassInverse() const {
|
||||||
|
return massInverse;
|
||||||
}
|
}
|
||||||
|
|
||||||
} // End of the ReactPhysics3D namespace
|
} // End of the ReactPhysics3D namespace
|
||||||
|
|
|
@ -20,6 +20,10 @@
|
||||||
#ifndef BOUNDING_VOLUME_H
|
#ifndef BOUNDING_VOLUME_H
|
||||||
#define BOUNDING_VOLUME_H
|
#define BOUNDING_VOLUME_H
|
||||||
|
|
||||||
|
// Libraries
|
||||||
|
#include "../mathematics/mathematics.h"
|
||||||
|
#include "Body.h"
|
||||||
|
|
||||||
// ReactPhysics3D namespace
|
// ReactPhysics3D namespace
|
||||||
namespace reactphysics3d {
|
namespace reactphysics3d {
|
||||||
|
|
||||||
|
@ -32,12 +36,30 @@ namespace reactphysics3d {
|
||||||
*/
|
*/
|
||||||
class BoundingVolume {
|
class BoundingVolume {
|
||||||
private :
|
private :
|
||||||
|
Body* body; // Pointer to the body
|
||||||
|
|
||||||
public :
|
public :
|
||||||
BoundingVolume(); // Constructor
|
BoundingVolume(); // Constructor
|
||||||
virtual ~BoundingVolume(); // Destructor
|
virtual ~BoundingVolume(); // Destructor
|
||||||
|
|
||||||
|
Body* getBodyPointer() const; // Return the body pointer
|
||||||
|
void setBodyPointer(Body* body); // Set the body pointer
|
||||||
|
|
||||||
|
virtual void updateOrientation(const Vector3D& newCenter, const Quaternion& rotationQuaternion)=0; // Update the orientation of the bounding volume according to the new orientation of the body
|
||||||
|
virtual void draw() const =0; // Display the bounding volume (only for testing purpose)
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Return the body pointer
|
||||||
|
inline Body* BoundingVolume::getBodyPointer() const {
|
||||||
|
return body;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set the body pointer
|
||||||
|
inline void BoundingVolume::setBodyPointer(Body* body) {
|
||||||
|
this->body = body;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
} // End of the ReactPhysics3D namespace
|
} // End of the ReactPhysics3D namespace
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -20,6 +20,9 @@
|
||||||
// Libraries
|
// Libraries
|
||||||
#include "OBB.h"
|
#include "OBB.h"
|
||||||
|
|
||||||
|
#include <GL/freeglut.h> // TODO : Remove this in the final version
|
||||||
|
#include <GL/gl.h> // TODO : Remove this in the final version
|
||||||
|
|
||||||
// We want to use the ReactPhysics3D namespace
|
// We want to use the ReactPhysics3D namespace
|
||||||
using namespace reactphysics3d;
|
using namespace reactphysics3d;
|
||||||
|
|
||||||
|
@ -28,6 +31,10 @@ OBB::OBB(const Vector3D& center, const Vector3D& axis1, const Vector3D& axis2,
|
||||||
const Vector3D& axis3, double extent1, double extent2, double extent3) {
|
const Vector3D& axis3, double extent1, double extent2, double extent3) {
|
||||||
this->center = center;
|
this->center = center;
|
||||||
|
|
||||||
|
oldAxis[0] = axis1;
|
||||||
|
oldAxis[1] = axis2;
|
||||||
|
oldAxis[2] = axis3;
|
||||||
|
|
||||||
this->axis[0] = axis1;
|
this->axis[0] = axis1;
|
||||||
this->axis[1] = axis2;
|
this->axis[1] = axis2;
|
||||||
this->axis[2] = axis3;
|
this->axis[2] = axis3;
|
||||||
|
@ -41,6 +48,10 @@ OBB::OBB(const Vector3D& center, const Vector3D& axis1, const Vector3D& axis2,
|
||||||
OBB::OBB(const OBB& obb) {
|
OBB::OBB(const OBB& obb) {
|
||||||
this->center = obb.center;
|
this->center = obb.center;
|
||||||
|
|
||||||
|
oldAxis[0] = obb.oldAxis[0];
|
||||||
|
oldAxis[1] = obb.oldAxis[1];
|
||||||
|
oldAxis[2] = obb.oldAxis[2];
|
||||||
|
|
||||||
this->axis[0] = obb.axis[0];
|
this->axis[0] = obb.axis[0];
|
||||||
this->axis[1] = obb.axis[1];
|
this->axis[1] = obb.axis[1];
|
||||||
this->axis[2] = obb.axis[2];
|
this->axis[2] = obb.axis[2];
|
||||||
|
@ -54,3 +65,66 @@ OBB::OBB(const OBB& obb) {
|
||||||
OBB::~OBB() {
|
OBB::~OBB() {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// TODO : Remove this method in the final version
|
||||||
|
// Draw the OBB (only for testing purpose)
|
||||||
|
void OBB::draw() const {
|
||||||
|
double e0 = extent[0];
|
||||||
|
double e1 = extent[1];
|
||||||
|
double e2 = extent[2];
|
||||||
|
|
||||||
|
Vector3D s1 = center + (axis[0]*e0) + (axis[1]*e1) - (axis[2]*e2);
|
||||||
|
Vector3D s2 = center + (axis[0]*e0) + (axis[1]*e1) + (axis[2]*e2);
|
||||||
|
Vector3D s3 = center - (axis[0]*e0) + (axis[1]*e1) + (axis[2]*e2);
|
||||||
|
Vector3D s4 = center - (axis[0]*e0) + (axis[1]*e1) - (axis[2]*e2);
|
||||||
|
Vector3D s5 = center + (axis[0]*e0) - (axis[1]*e1) - (axis[2]*e2);
|
||||||
|
Vector3D s6 = center + (axis[0]*e0) - (axis[1]*e1) + (axis[2]*e2);
|
||||||
|
Vector3D s7 = center - (axis[0]*e0) - (axis[1]*e1) + (axis[2]*e2);
|
||||||
|
Vector3D s8 = center - (axis[0]*e0) - (axis[1]*e1) - (axis[2]*e2);
|
||||||
|
|
||||||
|
// Draw in red
|
||||||
|
glColor3f(1.0, 0.0, 0.0);
|
||||||
|
|
||||||
|
// Draw the OBB
|
||||||
|
glBegin(GL_LINES);
|
||||||
|
glVertex3f(s1.getX(), s1.getY(), s1.getZ());
|
||||||
|
glVertex3f(s2.getX(), s2.getY(), s2.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s2.getX(), s2.getY(), s2.getZ());
|
||||||
|
glVertex3f(s3.getX(), s3.getY(), s3.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s3.getX(), s3.getY(), s3.getZ());
|
||||||
|
glVertex3f(s4.getX(), s4.getY(), s4.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s4.getX(), s4.getY(), s4.getZ());
|
||||||
|
glVertex3f(s1.getX(), s1.getY(), s1.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s5.getX(), s5.getY(), s5.getZ());
|
||||||
|
glVertex3f(s6.getX(), s6.getY(), s6.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s6.getX(), s6.getY(), s6.getZ());
|
||||||
|
glVertex3f(s7.getX(), s7.getY(), s7.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s7.getX(), s7.getY(), s7.getZ());
|
||||||
|
glVertex3f(s8.getX(), s8.getY(), s8.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s8.getX(), s8.getY(), s8.getZ());
|
||||||
|
glVertex3f(s5.getX(), s5.getY(), s5.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s1.getX(), s1.getY(), s1.getZ());
|
||||||
|
glVertex3f(s5.getX(), s5.getY(), s5.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s4.getX(), s4.getY(), s4.getZ());
|
||||||
|
glVertex3f(s8.getX(), s8.getY(), s8.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s3.getX(), s3.getY(), s3.getZ());
|
||||||
|
glVertex3f(s7.getX(), s7.getY(), s7.getZ());
|
||||||
|
|
||||||
|
glVertex3f(s2.getX(), s2.getY(), s2.getZ());
|
||||||
|
glVertex3f(s6.getX(), s6.getY(), s6.getZ());
|
||||||
|
|
||||||
|
glVertex3f(center.getX(), center.getY(), center.getZ());
|
||||||
|
glVertex3f(center.getX() + 8.0 * axis[1].getX(), center.getY() + 8.0 * axis[1].getY(), center.getZ() + 8.0 * axis[1].getZ());
|
||||||
|
|
||||||
|
glEnd();
|
||||||
|
}
|
||||||
|
|
|
@ -30,27 +30,34 @@ namespace reactphysics3d {
|
||||||
/* -------------------------------------------------------------------
|
/* -------------------------------------------------------------------
|
||||||
Class OBB :
|
Class OBB :
|
||||||
This class represents a bounding volume of type "Oriented Bounding
|
This class represents a bounding volume of type "Oriented Bounding
|
||||||
Box". It's a box that has a given orientation is space.
|
Box". It's a box that has a given orientation is space. The three
|
||||||
|
axis of the OBB are three axis that give the orientation of the
|
||||||
|
OBB. The three axis are normal vectors to the faces of the OBB.
|
||||||
|
Those axis are unit length. The three extents are half-widths
|
||||||
|
of the box along the three axis of the OBB.
|
||||||
-------------------------------------------------------------------
|
-------------------------------------------------------------------
|
||||||
*/
|
*/
|
||||||
class OBB : public BoundingVolume {
|
class OBB : public BoundingVolume {
|
||||||
private :
|
private :
|
||||||
Vector3D center; // Center point of the OBB
|
Vector3D center; // Center point of the OBB
|
||||||
Vector3D axis[3]; // Array that contains the three axis of the OBB
|
Vector3D oldAxis[3]; // Array that contains the three unit length axis at the beginning
|
||||||
|
Vector3D axis[3]; // Array that contains the three unit length axis of the OBB
|
||||||
double extent[3]; // Array that contains the three extents size of the OBB
|
double extent[3]; // Array that contains the three extents size of the OBB
|
||||||
|
|
||||||
public :
|
public :
|
||||||
OBB(const Vector3D& center, const Vector3D& axis1, const Vector3D& axis2,
|
OBB(const Vector3D& center, const Vector3D& axis1, const Vector3D& axis2,
|
||||||
const Vector3D& axis3, double extent1, double extent2, double extent3); // Constructor
|
const Vector3D& axis3, double extent1, double extent2, double extent3); // Constructor
|
||||||
OBB(const OBB& obb); // Copy-Constructor
|
OBB(const OBB& obb); // Copy-Constructor
|
||||||
virtual ~OBB(); // Destructor
|
virtual ~OBB(); // Destructor
|
||||||
|
|
||||||
Vector3D getCenter() const; // Return the center point of the OBB
|
Vector3D getCenter() const; // Return the center point of the OBB
|
||||||
void setCenter(const Vector3D& center); // Set the center point
|
void setCenter(const Vector3D& center); // Set the center point
|
||||||
Vector3D getAxis(unsigned int index) const throw(std::invalid_argument); // Return an axis of the OBB
|
Vector3D getAxis(unsigned int index) const throw(std::invalid_argument); // Return an axis of the OBB
|
||||||
void setAxis(unsigned int index, const Vector3D& axis) throw(std::invalid_argument); // Set an axis
|
void setAxis(unsigned int index, const Vector3D& axis) throw(std::invalid_argument); // Set an axis
|
||||||
double getExtent(unsigned int index) const throw(std::invalid_argument); // Return an extent value
|
double getExtent(unsigned int index) const throw(std::invalid_argument); // Return an extent value
|
||||||
void setExtent(unsigned int index, double extent) throw(std::invalid_argument); // Set an extent value
|
void setExtent(unsigned int index, double extent) throw(std::invalid_argument); // Set an extent value
|
||||||
|
virtual void updateOrientation(const Vector3D& newCenter, const Quaternion& rotationQuaternion); // Update the orientation of the OBB according to the orientation of the rigid body // Update the oriented bounding box orientation according to a new orientation of the rigid body
|
||||||
|
virtual void draw() const; // Draw the OBB (only for testing purpose)
|
||||||
};
|
};
|
||||||
|
|
||||||
// TODO : Don't forget that we need to code a way that a change in the orientation of a rigid body imply
|
// TODO : Don't forget that we need to code a way that a change in the orientation of a rigid body imply
|
||||||
|
@ -114,6 +121,18 @@ inline void OBB::setExtent(unsigned int index, double extent) throw(std::invalid
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// TODO : Test this method
|
||||||
|
// Update the orientation of the OBB according to the orientation of the rigid body
|
||||||
|
inline void OBB::updateOrientation(const Vector3D& newCenter, const Quaternion& rotationQuaternion) {
|
||||||
|
// Update the center of the OBB
|
||||||
|
center = newCenter;
|
||||||
|
|
||||||
|
// Update the three axis of the OBB by rotating and normalize then
|
||||||
|
axis[0] = rotateVectorWithQuaternion(oldAxis[0], rotationQuaternion).getUnit();
|
||||||
|
axis[1] = rotateVectorWithQuaternion(oldAxis[1], rotationQuaternion).getUnit();
|
||||||
|
axis[2] = rotateVectorWithQuaternion(oldAxis[2], rotationQuaternion).getUnit();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
}; // End of the ReactPhysics3D namespace
|
}; // End of the ReactPhysics3D namespace
|
||||||
|
|
||||||
|
|
|
@ -24,18 +24,21 @@
|
||||||
using namespace reactphysics3d;
|
using namespace reactphysics3d;
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
RigidBody::RigidBody(const Vector3D& position, const Kilogram& mass, const Matrix3x3& inertiaTensor)
|
RigidBody::RigidBody(const Vector3D& position, const Kilogram& mass, const Matrix3x3& inertiaTensor, const OBB& obb)
|
||||||
: Body(mass), inertiaTensor(inertiaTensor),
|
: Body(mass), inertiaTensor(inertiaTensor), obb(obb),
|
||||||
currentBodyState(position, inertiaTensor.getInverse(),Kilogram(1.0/mass.getValue())),
|
currentBodyState(position, inertiaTensor.getInverse(),Kilogram(1.0/mass.getValue())),
|
||||||
previousBodyState(position, inertiaTensor.getInverse(), Kilogram(1.0/mass.getValue())) {
|
previousBodyState(position, inertiaTensor.getInverse(), Kilogram(1.0/mass.getValue())) {
|
||||||
isMotionEnabled = true;
|
isMotionEnabled = true;
|
||||||
isCollisionEnabled = true;
|
isCollisionEnabled = true;
|
||||||
interpolationFactor = 0.0;
|
interpolationFactor = 0.0;
|
||||||
|
|
||||||
|
// Set the body pointer to the OBB
|
||||||
|
this->obb.setBodyPointer(this);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Copy-constructor
|
// Copy-constructor
|
||||||
RigidBody::RigidBody(const RigidBody& rigidBody) : Body(rigidBody), inertiaTensor(rigidBody.inertiaTensor),
|
RigidBody::RigidBody(const RigidBody& rigidBody) : Body(rigidBody), inertiaTensor(rigidBody.inertiaTensor),
|
||||||
currentBodyState(rigidBody.currentBodyState), previousBodyState(rigidBody.previousBodyState) {
|
currentBodyState(rigidBody.currentBodyState), previousBodyState(rigidBody.previousBodyState), obb(rigidBody.obb) {
|
||||||
this->isMotionEnabled = rigidBody.isMotionEnabled;
|
this->isMotionEnabled = rigidBody.isMotionEnabled;
|
||||||
this->isCollisionEnabled = rigidBody.isCollisionEnabled;
|
this->isCollisionEnabled = rigidBody.isCollisionEnabled;
|
||||||
interpolationFactor = rigidBody.interpolationFactor;
|
interpolationFactor = rigidBody.interpolationFactor;
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/****************************************************************************
|
/***************************************************************************
|
||||||
* Copyright (C) 2009 Daniel Chappuis *
|
* Copyright (C) 2009 Daniel Chappuis *
|
||||||
****************************************************************************
|
****************************************************************************
|
||||||
* This file is part of ReactPhysics3D. *
|
* This file is part of ReactPhysics3D. *
|
||||||
|
@ -24,6 +24,7 @@
|
||||||
#include <cassert>
|
#include <cassert>
|
||||||
#include "Body.h"
|
#include "Body.h"
|
||||||
#include "BodyState.h"
|
#include "BodyState.h"
|
||||||
|
#include "OBB.h"
|
||||||
#include "../mathematics/mathematics.h"
|
#include "../mathematics/mathematics.h"
|
||||||
#include "../physics/physics.h"
|
#include "../physics/physics.h"
|
||||||
|
|
||||||
|
@ -45,20 +46,23 @@ class RigidBody : public Body {
|
||||||
bool isMotionEnabled; // True if the body can move
|
bool isMotionEnabled; // True if the body can move
|
||||||
bool isCollisionEnabled; // True if the body can collide with others bodies
|
bool isCollisionEnabled; // True if the body can collide with others bodies
|
||||||
double interpolationFactor; // Interpolation factor used for the state interpolation
|
double interpolationFactor; // Interpolation factor used for the state interpolation
|
||||||
|
OBB obb; // Oriented bounding box that contains the rigid body
|
||||||
|
|
||||||
public :
|
public :
|
||||||
RigidBody(const Vector3D& position, const Kilogram& mass, const Matrix3x3& inertiaTensor); // Constructor
|
RigidBody(const Vector3D& position, const Kilogram& mass, const Matrix3x3& inertiaTensor, const OBB& obb); // Constructor
|
||||||
RigidBody(const RigidBody& rigidBody); // Copy-constructor
|
RigidBody(const RigidBody& rigidBody); // Copy-constructor
|
||||||
virtual ~RigidBody(); // Destructor
|
virtual ~RigidBody(); // Destructor
|
||||||
|
|
||||||
Matrix3x3 getInertiaTensor() const; // Return the inertia tensor of the body
|
Matrix3x3 getInertiaTensor() const; // Return the inertia tensor of the body
|
||||||
void setInertiaTensor(const Matrix3x3& inertiaTensor); // Set the inertia tensor of the body
|
void setInertiaTensor(const Matrix3x3& inertiaTensor); // Set the inertia tensor of the body
|
||||||
BodyState& getCurrentBodyState(); // Return a reference to the current state of the body
|
BodyState& getCurrentBodyState(); // Return a reference to the current state of the body
|
||||||
void setInterpolationFactor(double factor); // Set the interpolation factor of the body
|
void setInterpolationFactor(double factor); // Set the interpolation factor of the body
|
||||||
BodyState getInterpolatedState() const; // Compute and return the interpolated state
|
BodyState getInterpolatedState() const; // Compute and return the interpolated state
|
||||||
bool getIsMotionEnabled() const; // Return if the rigid body can move
|
bool getIsMotionEnabled() const; // Return if the rigid body can move
|
||||||
void setIsMotionEnabled(bool isMotionEnabled); // Set the value to true if the body can move
|
void setIsMotionEnabled(bool isMotionEnabled); // Set the value to true if the body can move
|
||||||
void updatePreviousBodyState(); // Update the previous body state of the body
|
void updatePreviousBodyState(); // Update the previous body state of the body
|
||||||
|
OBB getOBB() const; // Return the oriented bounding box of the rigid body
|
||||||
|
void update(); // Update the rigid body in order to reflect a change in the body state
|
||||||
};
|
};
|
||||||
|
|
||||||
// --- Inline functions --- //
|
// --- Inline functions --- //
|
||||||
|
@ -103,6 +107,17 @@ inline void RigidBody::updatePreviousBodyState() {
|
||||||
previousBodyState = currentBodyState;
|
previousBodyState = currentBodyState;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Return the oriented bounding box of the rigid body
|
||||||
|
inline OBB RigidBody::getOBB() const {
|
||||||
|
return obb;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update the rigid body in order to reflect a change in the body state
|
||||||
|
inline void RigidBody::update() {
|
||||||
|
// Update the orientation of the corresponding bounding volume of the rigid body
|
||||||
|
obb.updateOrientation(currentBodyState.getPosition(), currentBodyState.getOrientation());
|
||||||
|
}
|
||||||
|
|
||||||
} // End of the ReactPhyscis3D namespace
|
} // End of the ReactPhyscis3D namespace
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue
Block a user