Make possible to access Vector3 members by using x,y and z instead of getX(), getY() and getZ()
This commit is contained in:
parent
33a084c816
commit
cdc384db68
|
@ -147,7 +147,7 @@ bool EPAAlgorithm::computePenetrationDepthAndContactPoints(const Simplex& simple
|
|||
|
||||
// Create a rotation quaternion to rotate the vector v1 to get the vectors
|
||||
// v2 and v3
|
||||
Quaternion rotationQuat(d.getX() * sin60, d.getY() * sin60, d.getZ() * sin60, 0.5);
|
||||
Quaternion rotationQuat(d.x * sin60, d.y * sin60, d.z * sin60, 0.5);
|
||||
|
||||
// Construct the corresponding rotation matrix
|
||||
Matrix3x3 rotationMat = rotationQuat.getMatrix();
|
||||
|
|
|
@ -74,41 +74,41 @@ void AABB::draw() const {
|
|||
|
||||
// Draw the AABB
|
||||
glBegin(GL_LINES);
|
||||
glVertex3f(mMaxCoordinates.getX(), mMinCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMaxCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.x, mMinCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMaxCoordinates.y, mMinCoordinates.z);
|
||||
|
||||
glVertex3f(mMaxCoordinates.getX(), mMinCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMinCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.x, mMinCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMinCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMaxCoordinates.getX(), mMinCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMaxCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.x, mMinCoordinates.y, mMaxCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMaxCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMaxCoordinates.getX(), mMaxCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMaxCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.x, mMaxCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMaxCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMinCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.getX(), mMaxCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMinCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMinCoordinates.x, mMaxCoordinates.y, mMinCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMinCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.getX(), mMinCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMinCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMinCoordinates.x, mMinCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMinCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.getX(), mMaxCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMinCoordinates.y, mMaxCoordinates.z);
|
||||
glVertex3f(mMinCoordinates.x, mMaxCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMaxCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.getX(), mMaxCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMaxCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMinCoordinates.x, mMaxCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMinCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMinCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMinCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMinCoordinates.y, mMinCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMaxCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMaxCoordinates.getY(), mMinCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMaxCoordinates.y, mMinCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMaxCoordinates.y, mMinCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMaxCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMaxCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMaxCoordinates.y, mMaxCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMaxCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glVertex3f(mMinCoordinates.getX(), mMinCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMaxCoordinates.getX(), mMinCoordinates.getY(), mMaxCoordinates.getZ());
|
||||
glVertex3f(mMinCoordinates.x, mMinCoordinates.y, mMaxCoordinates.z);
|
||||
glVertex3f(mMaxCoordinates.x, mMinCoordinates.y, mMaxCoordinates.z);
|
||||
|
||||
glEnd();
|
||||
}
|
||||
|
|
|
@ -139,12 +139,12 @@ inline void AABB::setBodyPointer(Body* bodyPointer) {
|
|||
// Return true if the current AABB is overlapping with the AABB in argument
|
||||
// Two AABB overlap if they overlap in the three x, y and z axis at the same time
|
||||
inline bool AABB::testCollision(const AABB& aabb) const {
|
||||
if (mMaxCoordinates.getX() < aabb.mMinCoordinates.getX() ||
|
||||
aabb.mMaxCoordinates.getX() < mMinCoordinates.getX()) return false;
|
||||
if (mMaxCoordinates.getY() < aabb.mMinCoordinates.getY() ||
|
||||
aabb.mMaxCoordinates.getY() < mMinCoordinates.getY()) return false;
|
||||
if (mMaxCoordinates.getZ() < aabb.mMinCoordinates.getZ() ||
|
||||
aabb.mMaxCoordinates.getZ() < mMinCoordinates.getZ()) return false;
|
||||
if (mMaxCoordinates.x < aabb.mMinCoordinates.x ||
|
||||
aabb.mMaxCoordinates.x < mMinCoordinates.x) return false;
|
||||
if (mMaxCoordinates.y < aabb.mMinCoordinates.y ||
|
||||
aabb.mMaxCoordinates.y < mMinCoordinates.y) return false;
|
||||
if (mMaxCoordinates.z < aabb.mMinCoordinates.z||
|
||||
aabb.mMaxCoordinates.z < mMinCoordinates.z) return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -58,9 +58,9 @@ BoxShape::~BoxShape() {
|
|||
// Return the local inertia tensor of the collision shape
|
||||
void BoxShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const {
|
||||
decimal factor = (decimal(1.0) / decimal(3.0)) * mass;
|
||||
decimal xSquare = mExtent.getX() * mExtent.getX();
|
||||
decimal ySquare = mExtent.getY() * mExtent.getY();
|
||||
decimal zSquare = mExtent.getZ() * mExtent.getZ();
|
||||
decimal xSquare = mExtent.x * mExtent.x;
|
||||
decimal ySquare = mExtent.y * mExtent.y;
|
||||
decimal zSquare = mExtent.z * mExtent.z;
|
||||
tensor.setAllValues(factor * (ySquare + zSquare), 0.0, 0.0,
|
||||
0.0, factor * (xSquare + zSquare), 0.0,
|
||||
0.0, 0.0, factor * (xSquare + ySquare));
|
||||
|
@ -69,9 +69,9 @@ void BoxShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const
|
|||
#ifdef VISUAL_DEBUG
|
||||
// Draw the Box (only for testing purpose)
|
||||
void BoxShape::draw() const {
|
||||
decimal e1 = mExtent.getX();
|
||||
decimal e2 = mExtent.getY();
|
||||
decimal e3 = mExtent.getZ();
|
||||
decimal e1 = mExtent.x;
|
||||
decimal e2 = mExtent.y;
|
||||
decimal e3 = mExtent.z;
|
||||
|
||||
// Draw in red
|
||||
glColor3f(1.0, 0.0, 0.0);
|
||||
|
|
|
@ -111,9 +111,9 @@ inline Vector3 BoxShape::getLocalExtents(decimal margin) const {
|
|||
inline Vector3 BoxShape::getLocalSupportPoint(const Vector3& direction, decimal margin) const {
|
||||
assert(margin >= 0.0);
|
||||
|
||||
return Vector3(direction.getX() < 0.0 ? -mExtent.getX()-margin : mExtent.getX()+margin,
|
||||
direction.getY() < 0.0 ? -mExtent.getY()-margin : mExtent.getY()+margin,
|
||||
direction.getZ() < 0.0 ? -mExtent.getZ()-margin : mExtent.getZ()+margin);
|
||||
return Vector3(direction.x < 0.0 ? -mExtent.x - margin : mExtent.x + margin,
|
||||
direction.y < 0.0 ? -mExtent.y - margin : mExtent.y + margin,
|
||||
direction.z < 0.0 ? -mExtent.z - margin : mExtent.z + margin);
|
||||
}
|
||||
|
||||
}; // End of the ReactPhysics3D namespace
|
||||
|
|
|
@ -66,14 +66,14 @@ inline Vector3 ConeShape::getLocalSupportPoint(const Vector3& direction, decimal
|
|||
decimal sinThetaTimesLengthV = mSinTheta * v.length();
|
||||
Vector3 supportPoint;
|
||||
|
||||
if (v.getY() >= sinThetaTimesLengthV) {
|
||||
if (v.y >= sinThetaTimesLengthV) {
|
||||
supportPoint = Vector3(0.0, mHalfHeight, 0.0);
|
||||
}
|
||||
else {
|
||||
decimal projectedLength = sqrt(v.getX() * v.getX() + v.getZ() * v.getZ());
|
||||
decimal projectedLength = sqrt(v.x * v.x + v.z * v.z);
|
||||
if (projectedLength > MACHINE_EPSILON) {
|
||||
decimal d = mRadius / projectedLength;
|
||||
supportPoint = Vector3(v.getX() * d, -mHalfHeight, v.getZ() * d);
|
||||
supportPoint = Vector3(v.x * d, -mHalfHeight, v.z * d);
|
||||
}
|
||||
else {
|
||||
supportPoint = Vector3(mRadius, -mHalfHeight, 0.0);
|
||||
|
|
|
@ -58,18 +58,18 @@ Vector3 CylinderShape::getLocalSupportPoint(const Vector3& direction, decimal ma
|
|||
assert(margin >= 0.0);
|
||||
|
||||
Vector3 supportPoint(0.0, 0.0, 0.0);
|
||||
decimal uDotv = direction.getY();
|
||||
Vector3 w(direction.getX(), 0.0, direction.getZ());
|
||||
decimal lengthW = sqrt(direction.getX() * direction.getX() + direction.getZ() * direction.getZ());
|
||||
decimal uDotv = direction.y;
|
||||
Vector3 w(direction.x, 0.0, direction.z);
|
||||
decimal lengthW = sqrt(direction.x * direction.x + direction.z * direction.z);
|
||||
|
||||
if (lengthW != 0.0) {
|
||||
if (uDotv < 0.0) supportPoint.setY(-mHalfHeight);
|
||||
else supportPoint.setY(mHalfHeight);
|
||||
if (uDotv < 0.0) supportPoint.y = -mHalfHeight;
|
||||
else supportPoint.y = mHalfHeight;
|
||||
supportPoint += (mRadius / lengthW) * w;
|
||||
}
|
||||
else {
|
||||
if (uDotv < 0.0) supportPoint.setY(-mHalfHeight);
|
||||
else supportPoint.setY(mHalfHeight);
|
||||
if (uDotv < 0.0) supportPoint.y = -mHalfHeight;
|
||||
else supportPoint.y = mHalfHeight;
|
||||
}
|
||||
|
||||
// Add the margin to the support point
|
||||
|
|
|
@ -228,16 +228,7 @@ inline void ContactManifold::setFrictionTwistImpulse(decimal frictionTwistImpuls
|
|||
inline ContactPoint* ContactManifold::getContactPoint(uint index) const {
|
||||
assert(index >= 0 && index < mNbContactPoints);
|
||||
return mContactPoints[index];
|
||||
}
|
||||
|
||||
// Return true if two vectors are approximatively equal
|
||||
inline bool ContactManifold::isApproxEqual(const Vector3& vector1,
|
||||
const Vector3& vector2) const {
|
||||
const decimal epsilon = decimal(0.1);
|
||||
return (approxEqual(vector1.getX(), vector2.getX(), epsilon) &&
|
||||
approxEqual(vector1.getY(), vector2.getY(), epsilon) &&
|
||||
approxEqual(vector1.getZ(), vector2.getZ(), epsilon));
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -140,7 +140,10 @@ void DynamicsWorld::updateRigidBodiesPositionAndOrientation() {
|
|||
|
||||
// Compute the new position of the body
|
||||
Vector3 newPosition = currentPosition + newLinVelocity * dt;
|
||||
Quaternion newOrientation = currentOrientation + Quaternion(newAngVelocity.getX(), newAngVelocity.getY(), newAngVelocity.getZ(), 0) * currentOrientation * 0.5 * dt;
|
||||
Quaternion newOrientation = currentOrientation + Quaternion(newAngVelocity.x,
|
||||
newAngVelocity.y,
|
||||
newAngVelocity.z, 0) *
|
||||
currentOrientation * 0.5 * dt;
|
||||
|
||||
// Update the Transform of the body
|
||||
Transform newTransform(newPosition, newOrientation.getUnit());
|
||||
|
|
|
@ -276,12 +276,12 @@ inline Matrix3x3 operator*(const Matrix3x3& matrix1, const Matrix3x3& matrix2) {
|
|||
|
||||
// Overloaded operator for multiplication with a vector
|
||||
inline Vector3 operator*(const Matrix3x3& matrix, const Vector3& vector) {
|
||||
return Vector3(matrix.mArray[0][0]*vector.getX() + matrix.mArray[0][1]*vector.getY() +
|
||||
matrix.mArray[0][2]*vector.getZ(),
|
||||
matrix.mArray[1][0]*vector.getX() + matrix.mArray[1][1]*vector.getY() +
|
||||
matrix.mArray[1][2]*vector.getZ(),
|
||||
matrix.mArray[2][0]*vector.getX() + matrix.mArray[2][1]*vector.getY() +
|
||||
matrix.mArray[2][2]*vector.getZ());
|
||||
return Vector3(matrix.mArray[0][0]*vector.x + matrix.mArray[0][1]*vector.y +
|
||||
matrix.mArray[0][2]*vector.z,
|
||||
matrix.mArray[1][0]*vector.x + matrix.mArray[1][1]*vector.y +
|
||||
matrix.mArray[1][2]*vector.z,
|
||||
matrix.mArray[2][0]*vector.x + matrix.mArray[2][1]*vector.y +
|
||||
matrix.mArray[2][2]*vector.z);
|
||||
}
|
||||
|
||||
// Overloaded operator for equality condition
|
||||
|
|
4
src/mathematics/Quaternion.cpp
Executable file → Normal file
4
src/mathematics/Quaternion.cpp
Executable file → Normal file
|
@ -45,7 +45,7 @@ Quaternion::Quaternion(decimal x, decimal y, decimal z, decimal w)
|
|||
|
||||
// Constructor with the component w and the vector v=(x y z)
|
||||
Quaternion::Quaternion(decimal w, const Vector3& v)
|
||||
:mX(v.getX()), mY(v.getY()), mZ(v.getZ()), mW(w) {
|
||||
:mX(v.x), mY(v.y), mZ(v.z), mW(w) {
|
||||
|
||||
}
|
||||
|
||||
|
@ -157,7 +157,7 @@ void Quaternion::getRotationAngleAxis(decimal& angle, Vector3& axis) const {
|
|||
rotationAxis = rotationAxis.getUnit();
|
||||
|
||||
// Set the rotation axis values
|
||||
axis.setAllValues(rotationAxis.getX(), rotationAxis.getY(), rotationAxis.getZ());
|
||||
axis.setAllValues(rotationAxis.x, rotationAxis.y, rotationAxis.z);
|
||||
}
|
||||
|
||||
// Return the orientation matrix corresponding to this quaternion
|
||||
|
|
|
@ -160,8 +160,8 @@ inline void Transform::getOpenGLMatrix(decimal* openglMatrix) const {
|
|||
openglMatrix[6] = matrix.getValue(2, 1); openglMatrix[7] = 0.0;
|
||||
openglMatrix[8] = matrix.getValue(0, 2); openglMatrix[9] = matrix.getValue(1, 2);
|
||||
openglMatrix[10] = matrix.getValue(2, 2); openglMatrix[11] = 0.0;
|
||||
openglMatrix[12] = mPosition.getX(); openglMatrix[13] = mPosition.getY();
|
||||
openglMatrix[14] = mPosition.getZ(); openglMatrix[15] = 1.0;
|
||||
openglMatrix[12] = mPosition.x; openglMatrix[13] = mPosition.y;
|
||||
openglMatrix[14] = mPosition.z; openglMatrix[15] = 1.0;
|
||||
}
|
||||
|
||||
// Return the inverse of the transform
|
||||
|
|
|
@ -32,24 +32,18 @@
|
|||
using namespace reactphysics3d;
|
||||
|
||||
// Constructor of the class Vector3D
|
||||
Vector3::Vector3() {
|
||||
mValues[0] = 0.0;
|
||||
mValues[1] = 0.0;
|
||||
mValues[2] = 0.0;
|
||||
Vector3::Vector3() : x(0.0), y(0.0), z(0.0) {
|
||||
|
||||
}
|
||||
|
||||
// Constructor with arguments
|
||||
Vector3::Vector3(decimal x, decimal y, decimal z) {
|
||||
mValues[0] = x;
|
||||
mValues[1] = y;
|
||||
mValues[2] = z;
|
||||
Vector3::Vector3(decimal newX, decimal newY, decimal newZ) : x(newX), y(newY), z(newZ) {
|
||||
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
Vector3::Vector3(const Vector3& vector) {
|
||||
mValues[0] = vector.mValues[0];
|
||||
mValues[1] = vector.mValues[1];
|
||||
mValues[2] = vector.mValues[2];
|
||||
Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) {
|
||||
|
||||
}
|
||||
|
||||
// Destructor
|
||||
|
@ -61,49 +55,17 @@ Vector3::~Vector3() {
|
|||
Vector3 Vector3::getUnit() const {
|
||||
decimal lengthVector = length();
|
||||
|
||||
assert(lengthVector != 0.0);
|
||||
assert(lengthVector > std::numeric_limits<decimal>::epsilon());
|
||||
|
||||
// Compute and return the unit vector
|
||||
decimal lengthInv = 1.0 / lengthVector;
|
||||
return Vector3(mValues[0] * lengthInv, mValues[1] * lengthInv, mValues[2] * lengthInv);
|
||||
}
|
||||
|
||||
// Return two unit orthogonal vectors of the current vector
|
||||
Vector3 Vector3::getOneOrthogonalVector() const {
|
||||
assert(!this->isZero());
|
||||
|
||||
// Compute a first orthogonal vector
|
||||
Vector3 vector1;
|
||||
if (!approxEqual(mValues[0], 0.0)) { // If x != 0
|
||||
vector1.setY(mValues[0]);
|
||||
vector1.setZ((-2*mValues[0]*mValues[1]*mValues[2] +
|
||||
2*mValues[0]*mValues[2])/(2*(mValues[2]*mValues[2] + mValues[0]*mValues[0])));
|
||||
vector1.setX((-mValues[0]*mValues[1]-mValues[2]*vector1.getZ())/mValues[0]);
|
||||
}
|
||||
else if (!approxEqual(mValues[1], 0.0)) { // If y != 0
|
||||
vector1.setZ(mValues[1]);
|
||||
vector1.setX((-2*mValues[0]*mValues[1]*mValues[2] +
|
||||
2*mValues[0]*mValues[1])/(2*(mValues[1]*mValues[1] + mValues[0]*mValues[0])));
|
||||
vector1.setY((-mValues[2]*mValues[1]-mValues[0]*vector1.getX())/mValues[1]);
|
||||
}
|
||||
else if (!approxEqual(mValues[2], 0.0)) { // If z != 0
|
||||
vector1.setX(mValues[2]);
|
||||
vector1.setY((-2*mValues[0]*mValues[1]*mValues[2] +
|
||||
2*mValues[1]*mValues[2])/(2*(mValues[2]*mValues[2] + mValues[1]*mValues[1])));
|
||||
vector1.setZ((-mValues[0]*mValues[2]-mValues[1]*vector1.getY())/mValues[2]);
|
||||
}
|
||||
|
||||
//assert(vector1.isUnit());
|
||||
return vector1;
|
||||
return Vector3(x * lengthInv, y * lengthInv, z * lengthInv);
|
||||
}
|
||||
|
||||
// Return one unit orthogonal vector of the current vector
|
||||
Vector3 Vector3::getOneUnitOrthogonalVector() const {
|
||||
assert(!this->isZero());
|
||||
|
||||
decimal x = mValues[0];
|
||||
decimal y = mValues[1];
|
||||
decimal z = mValues[2];
|
||||
assert(length() > std::numeric_limits<decimal>::epsilon());
|
||||
|
||||
// Get the minimum element of the vector
|
||||
Vector3 vectorAbs(fabs(x), fabs(y), fabs(z));
|
||||
|
|
|
@ -37,20 +37,18 @@
|
|||
namespace reactphysics3d {
|
||||
|
||||
/* -------------------------------------------------------------------
|
||||
Class Vector3 :
|
||||
This class represents 3D vector in space.
|
||||
Structure Vector3 :
|
||||
This class represents a 3D vector.
|
||||
-------------------------------------------------------------------
|
||||
*/
|
||||
class Vector3 {
|
||||
struct Vector3 {
|
||||
|
||||
private :
|
||||
public:
|
||||
|
||||
// -------------------- Attributes -------------------- //
|
||||
|
||||
// Values of the 3D vector
|
||||
decimal mValues[3];
|
||||
|
||||
public :
|
||||
decimal x, y, z;
|
||||
|
||||
// -------------------- Methods -------------------- //
|
||||
|
||||
|
@ -58,7 +56,7 @@ class Vector3 {
|
|||
Vector3();
|
||||
|
||||
// Constructor with arguments
|
||||
Vector3(decimal x, decimal y, decimal z);
|
||||
Vector3(decimal newX, decimal newY, decimal newZ);
|
||||
|
||||
// Copy-constructor
|
||||
Vector3(const Vector3& vector);
|
||||
|
@ -66,26 +64,8 @@ class Vector3 {
|
|||
// Destructor
|
||||
~Vector3();
|
||||
|
||||
// Get the x component of the vector
|
||||
decimal getX() const;
|
||||
|
||||
// Get the y component of the vector
|
||||
decimal getY() const;
|
||||
|
||||
// Get the z component of the vector
|
||||
decimal getZ() const;
|
||||
|
||||
// Set the x component of the vector
|
||||
void setX(decimal x);
|
||||
|
||||
// Set the y component of the vector
|
||||
void setY(decimal y);
|
||||
|
||||
// Set the z component of the vector
|
||||
void setZ(decimal z);
|
||||
|
||||
// Set all the values of the vector
|
||||
void setAllValues(decimal x, decimal y, decimal z);
|
||||
void setAllValues(decimal newX, decimal newY, decimal newZ);
|
||||
|
||||
// Return the lenght of the vector
|
||||
decimal length() const;
|
||||
|
@ -105,9 +85,6 @@ class Vector3 {
|
|||
// Return true if the current vector is the zero vector
|
||||
bool isZero() const;
|
||||
|
||||
// Return one unit orthogonal vectors of the current vector
|
||||
Vector3 getOneOrthogonalVector() const;
|
||||
|
||||
// Dot product of two vectors
|
||||
decimal dot(const Vector3& vector) const;
|
||||
|
||||
|
@ -166,80 +143,47 @@ class Vector3 {
|
|||
friend Vector3 operator/(const Vector3& vector, decimal number);
|
||||
};
|
||||
|
||||
// Get the x component of the vector
|
||||
inline decimal Vector3::getX() const {
|
||||
return mValues[0];
|
||||
// Set all the values of the vector
|
||||
inline void Vector3::setAllValues(decimal newX, decimal newY, decimal newZ) {
|
||||
x = newX;
|
||||
y = newY;
|
||||
z = newZ;
|
||||
}
|
||||
|
||||
// Get the y component of the vector
|
||||
inline decimal Vector3::getY() const {
|
||||
return mValues[1];
|
||||
}
|
||||
|
||||
// Get the z component of the vector
|
||||
inline decimal Vector3::getZ() const {
|
||||
return mValues[2];
|
||||
}
|
||||
|
||||
// Set the x component of the vector
|
||||
inline void Vector3::setX(decimal x) {
|
||||
this->mValues[0] = x;
|
||||
}
|
||||
|
||||
// Set the y component of the vector
|
||||
inline void Vector3::setY(decimal y) {
|
||||
this->mValues[1] = y;
|
||||
}
|
||||
|
||||
// Set the z component of the vector
|
||||
inline void Vector3::setZ(decimal z) {
|
||||
this->mValues[2] = z;
|
||||
}
|
||||
|
||||
// Set all the values of the vector (inline)
|
||||
inline void Vector3::setAllValues(decimal x, decimal y, decimal z) {
|
||||
mValues[0]= x;
|
||||
mValues[1] = y;
|
||||
mValues[2] = z;
|
||||
}
|
||||
|
||||
// Return the length of the vector (inline)
|
||||
// Return the length of the vector
|
||||
inline decimal Vector3::length() const {
|
||||
// Compute and return the length of the vector
|
||||
return sqrt(mValues[0]*mValues[0] + mValues[1]*mValues[1] + mValues[2]*mValues[2]);
|
||||
return sqrt(x*x + y*y + z*z);
|
||||
}
|
||||
|
||||
// Return the square of the length of the vector
|
||||
inline decimal Vector3::lengthSquare() const {
|
||||
return mValues[0]*mValues[0] + mValues[1]*mValues[1] + mValues[2]*mValues[2];
|
||||
return x*x + y*y + z*z;
|
||||
}
|
||||
|
||||
// Scalar product of two vectors (inline)
|
||||
inline decimal Vector3::dot(const Vector3& vector) const {
|
||||
// Compute and return the result of the scalar product
|
||||
return (mValues[0] * vector.mValues[0] + mValues[1] * vector.mValues[1] + mValues[2] * vector.mValues[2]);
|
||||
return (x*vector.x + y*vector.y + z*vector.z);
|
||||
}
|
||||
|
||||
// Cross product of two vectors (inline)
|
||||
inline Vector3 Vector3::cross(const Vector3& vector) const {
|
||||
// Compute and return the cross product
|
||||
return Vector3(mValues[1] * vector.mValues[2] - mValues[2] * vector.mValues[1],
|
||||
mValues[2] * vector.mValues[0] - mValues[0] * vector.mValues[2],
|
||||
mValues[0] * vector.mValues[1] - mValues[1] * vector.mValues[0]);
|
||||
return Vector3(y * vector.z - z * vector.y,
|
||||
z * vector.x - x * vector.z,
|
||||
x * vector.y - y * vector.x);
|
||||
}
|
||||
|
||||
// Normalize the vector
|
||||
inline void Vector3::normalize() {
|
||||
decimal l = length();
|
||||
assert(l != 0.0);
|
||||
mValues[0] /= l;
|
||||
mValues[1] /= l;
|
||||
mValues[2] /= l;
|
||||
assert(l > std::numeric_limits<decimal>::epsilon());
|
||||
x /= l;
|
||||
y /= l;
|
||||
z /= l;
|
||||
}
|
||||
|
||||
// Return the corresponding absolute value vector
|
||||
inline Vector3 Vector3::getAbsoluteVector() const {
|
||||
return Vector3(std::abs(mValues[0]), std::abs(mValues[1]), std::abs(mValues[2]));
|
||||
return Vector3(std::abs(x), std::abs(y), std::abs(z));
|
||||
}
|
||||
|
||||
// Return true if two vectors are parallel
|
||||
|
@ -251,27 +195,27 @@ inline bool Vector3::isParallelWith(const Vector3& vector) const {
|
|||
|
||||
// Return the axis with the minimal value
|
||||
inline int Vector3::getMinAxis() const {
|
||||
return (mValues[0] < mValues[1] ? (mValues[0] < mValues[2] ? 0 : 2) : (mValues[1] < mValues[2] ? 1 : 2));
|
||||
return (x < y ? (x < z ? 0 : 2) : (y < z ? 1 : 2));
|
||||
}
|
||||
|
||||
// Return the axis with the maximal value
|
||||
inline int Vector3::getMaxAxis() const {
|
||||
return (mValues[0] < mValues[1] ? (mValues[1] < mValues[2] ? 2 : 1) : (mValues[0] < mValues[2] ? 2 : 0));
|
||||
return (x < y ? (y < z ? 2 : 1) : (x < z ? 2 : 0));
|
||||
}
|
||||
|
||||
// Return true if the vector is unit and false otherwise
|
||||
inline bool Vector3::isUnit() const {
|
||||
return approxEqual(mValues[0] * mValues[0] + mValues[1] * mValues[1] + mValues[2] * mValues[2], 1.0);
|
||||
return approxEqual(lengthSquare(), 1.0);
|
||||
}
|
||||
|
||||
// Return true if the vector is the zero vector
|
||||
inline bool Vector3::isZero() const {
|
||||
return approxEqual(mValues[0] * mValues[0] + mValues[1] * mValues[1] + mValues[2] * mValues[2], 0.0);
|
||||
return approxEqual(lengthSquare(), 0.0);
|
||||
}
|
||||
|
||||
// Overloaded operator for the equality condition
|
||||
inline bool Vector3::operator== (const Vector3& vector) const {
|
||||
return (mValues[0] == vector.mValues[0] && mValues[1] == vector.mValues[1] && mValues[2] == vector.mValues[2]);
|
||||
return (x == vector.x && y == vector.y && z == vector.z);
|
||||
}
|
||||
|
||||
// Overloaded operator for the is different condition
|
||||
|
@ -281,69 +225,71 @@ inline bool Vector3::operator!= (const Vector3& vector) const {
|
|||
|
||||
// Overloaded operator for addition with assignment
|
||||
inline Vector3& Vector3::operator+=(const Vector3& vector) {
|
||||
mValues[0] += vector.mValues[0];
|
||||
mValues[1] += vector.mValues[1];
|
||||
mValues[2] += vector.mValues[2];
|
||||
x += vector.x;
|
||||
y += vector.y;
|
||||
z += vector.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded operator for substraction with assignment
|
||||
inline Vector3& Vector3::operator-=(const Vector3& vector) {
|
||||
mValues[0] -= vector.mValues[0];
|
||||
mValues[1] -= vector.mValues[1];
|
||||
mValues[2] -= vector.mValues[2];
|
||||
x -= vector.x;
|
||||
y -= vector.y;
|
||||
z -= vector.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded operator for multiplication with a number with assignment
|
||||
inline Vector3& Vector3::operator*=(decimal number) {
|
||||
mValues[0] *= number;
|
||||
mValues[1] *= number;
|
||||
mValues[2] *= number;
|
||||
x *= number;
|
||||
y *= number;
|
||||
z *= number;
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded operator for division by a number with assignment
|
||||
inline Vector3& Vector3::operator/=(decimal number) {
|
||||
mValues[0] /= number;
|
||||
mValues[1] /= number;
|
||||
mValues[2] /= number;
|
||||
assert(number > std::numeric_limits<decimal>::epsilon());
|
||||
x /= number;
|
||||
y /= number;
|
||||
z /= number;
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded operator for value access
|
||||
inline decimal& Vector3::operator[] (int index) {
|
||||
return mValues[index];
|
||||
return (&x)[index];
|
||||
}
|
||||
|
||||
// Overloaded operator for value access
|
||||
inline const decimal& Vector3::operator[] (int index) const {
|
||||
return mValues[index];
|
||||
return (&x)[index];
|
||||
}
|
||||
|
||||
// Overloaded operator for addition
|
||||
inline Vector3 operator+(const Vector3& vector1, const Vector3& vector2) {
|
||||
return Vector3(vector1.mValues[0] + vector2.mValues[0], vector1.mValues[1] + vector2.mValues[1], vector1.mValues[2] + vector2.mValues[2]);
|
||||
return Vector3(vector1.x + vector2.x, vector1.y + vector2.y, vector1.z + vector2.z);
|
||||
}
|
||||
|
||||
// Overloaded operator for substraction
|
||||
inline Vector3 operator-(const Vector3& vector1, const Vector3& vector2) {
|
||||
return Vector3(vector1.mValues[0] - vector2.mValues[0], vector1.mValues[1] - vector2.mValues[1], vector1.mValues[2] - vector2.mValues[2]);
|
||||
return Vector3(vector1.x - vector2.x, vector1.y - vector2.y, vector1.z - vector2.z);
|
||||
}
|
||||
|
||||
// Overloaded operator for the negative of a vector
|
||||
inline Vector3 operator-(const Vector3& vector) {
|
||||
return Vector3(-vector.mValues[0], -vector.mValues[1], -vector.mValues[2]);
|
||||
return Vector3(-vector.x, -vector.y, -vector.z);
|
||||
}
|
||||
|
||||
// Overloaded operator for multiplication with a number
|
||||
inline Vector3 operator*(const Vector3& vector, decimal number) {
|
||||
return Vector3(number * vector.mValues[0], number * vector.mValues[1], number * vector.mValues[2]);
|
||||
return Vector3(number * vector.x, number * vector.y, number * vector.z);
|
||||
}
|
||||
|
||||
// Overloaded operator for division by a number
|
||||
inline Vector3 operator/(const Vector3& vector, decimal number) {
|
||||
return Vector3(vector.mValues[0] / number, vector.mValues[1] / number, vector.mValues[2] / number);
|
||||
assert(number > std::numeric_limits<decimal>::epsilon());
|
||||
return Vector3(vector.x / number, vector.y / number, vector.z / number);
|
||||
}
|
||||
|
||||
// Overloaded operator for multiplication with a number
|
||||
|
@ -354,13 +300,13 @@ inline Vector3 operator*(decimal number, const Vector3& vector) {
|
|||
// Assignment operator
|
||||
inline Vector3& Vector3::operator=(const Vector3& vector) {
|
||||
if (&vector != this) {
|
||||
mValues[0] = vector.mValues[0];
|
||||
mValues[1] = vector.mValues[1];
|
||||
mValues[2] = vector.mValues[2];
|
||||
x = vector.x;
|
||||
y = vector.y;
|
||||
z = vector.z;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
} // End of the ReactPhysics3D namespace
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue
Block a user