1) Animations can now be bullet rigid bodies, which means collisions are

possible.
2) The track exporter supports now exporting a single animation model only even
   if the model is used in several animations.
3) Changed the rad to/from degree macros to be uses as multiplication factors,
   i.e. RAD_TO_DEGREE*x instead if RAD_TO_DEGREE(x). This allows more compact
   code if vectors are convered (RAD_TO_DEGREE*vec3  instead of three separate
   macro invocations, once for each component)


git-svn-id: svn+ssh://svn.code.sf.net/p/supertuxkart/code/main/branches/irrlicht@3688 178a84e3-b1eb-0310-8ba1-8eac791a3b58
This commit is contained in:
hikerstk 2009-07-03 00:51:31 +00:00
parent 853bd9a0d3
commit 88600d7d2e
16 changed files with 150 additions and 52 deletions

View File

@ -48,6 +48,11 @@ private:
/** The current time in the cycle of a cyclic animation. */ /** The current time in the cycle of a cyclic animation. */
float m_current_time; float m_current_time;
/** The inital position of this object. */
core::vector3df m_initial_xyz;
/** The initial rotation of this object. */
core::vector3df m_initial_hpr;
protected: protected:
/** All IPOs for this animation. */ /** All IPOs for this animation. */
std::vector<Ipo*> m_all_ipos; std::vector<Ipo*> m_all_ipos;

View File

@ -110,16 +110,16 @@ void Ipo::reset()
void Ipo::update(float dt, core::vector3df *xyz, core::vector3df *hpr) void Ipo::update(float dt, core::vector3df *xyz, core::vector3df *hpr)
{ {
m_time += dt; m_time += dt;
if(m_time>m_max_time) m_time = 0; if(m_extend!=ET_CONST && m_time>m_max_time) m_time = 0;
switch(m_channel) switch(m_channel)
{ {
case Ipo::IPO_LOCX : xyz->X = get(); break; case Ipo::IPO_LOCX : xyz->X = get(); break;
case Ipo::IPO_LOCY : xyz->Y = get(); break; case Ipo::IPO_LOCY : xyz->Y = get(); break;
case Ipo::IPO_LOCZ : xyz->Z = get(); break; case Ipo::IPO_LOCZ : xyz->Z = get(); break;
case Ipo::IPO_ROTX : hpr->Y = get()*10.0f; break; case Ipo::IPO_ROTX : hpr->X = get(); break;
case Ipo::IPO_ROTY : hpr->Y = get()*10.0f; break; case Ipo::IPO_ROTY : hpr->Y = get(); break;
case Ipo::IPO_ROTZ : hpr->Z = get()*10.0f; break; case Ipo::IPO_ROTZ : hpr->Z = get(); break;
} // switch } // switch
} // update } // update

View File

@ -23,9 +23,15 @@
#include "animations/ipo.hpp" #include "animations/ipo.hpp"
#include "graphics/irr_driver.hpp" #include "graphics/irr_driver.hpp"
#include "graphics/mesh_tools.hpp"
#include "io/file_manager.hpp" #include "io/file_manager.hpp"
#include "io/xml_node.hpp" #include "io/xml_node.hpp"
#include "modes/world.hpp"
#include "physics/physics.hpp"
#include "physics/kart_motion_state.hpp"
#include "race/race_manager.hpp"
#include "tracks/bezier_curve.hpp" #include "tracks/bezier_curve.hpp"
#include "utils/constants.hpp"
ThreeDAnimation::ThreeDAnimation(const std::string &track_name, ThreeDAnimation::ThreeDAnimation(const std::string &track_name,
const XMLNode &node, float fps) const XMLNode &node, float fps)
@ -46,9 +52,69 @@ ThreeDAnimation::ThreeDAnimation(const std::string &track_name,
core::vector3df xyz; core::vector3df xyz;
node.get("xyz", &xyz); node.get("xyz", &xyz);
m_animated_node->setPosition(xyz); m_animated_node->setPosition(xyz);
core::vector3df hpr(0,0,0);
node.get("hpr", &hpr);
m_animated_node->setRotation(hpr);
/** Save the initial position and rotation in the base animation object. */
setInitialTransform(m_animated_node->getPosition(), m_animated_node->getRotation()); setInitialTransform(m_animated_node->getPosition(), m_animated_node->getRotation());
m_body = NULL;
m_motion_state = NULL;
m_collision_shape = NULL;
std::string shape;
node.get("shape", &shape);
if(shape!="")
{
createPhysicsBody(shape);
}
} // ThreeDAnimation } // ThreeDAnimation
// ----------------------------------------------------------------------------
/** Creates a bullet rigid body for this animated model. */
void ThreeDAnimation::createPhysicsBody(const std::string &shape)
{
// 1. Determine size of the object
// -------------------------------
Vec3 min, max;
MeshTools::minMax3D(m_mesh, &min, &max);
Vec3 extend = max-min;
if(shape=="box")
{
m_collision_shape = new btBoxShape(0.5*extend);
}
else if(shape=="cone")
{
float radius = 0.5f*std::max(extend.getX(), extend.getY());
m_collision_shape = new btConeShapeZ(radius, extend.getZ());
}
else
{
fprintf(stderr, "Shape '%s' is not supported, ignored.\n", shape.c_str());
return;
}
const core::vector3df &hpr=m_animated_node->getRotation()*DEGREE_TO_RAD;
btQuaternion q(hpr.X, hpr.Y, hpr.Z);
const core::vector3df &xyz=m_animated_node->getPosition();
Vec3 p(xyz);
btTransform trans(q,p);
m_motion_state = new KartMotionState(trans);
btRigidBody::btRigidBodyConstructionInfo info(0, m_motion_state,
m_collision_shape);
m_body = new btRigidBody(info);
m_user_pointer.set(this);
m_body->setUserPointer(&m_user_pointer);
RaceManager::getWorld()->getPhysics()->addBody(m_body);
m_body->setCollisionFlags( m_body->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
m_body->setActivationState(DISABLE_DEACTIVATION);
} // createPhysicsBody
// ----------------------------------------------------------------------------
/** Destructor. */
ThreeDAnimation::~ThreeDAnimation()
{
} // ~ThreeDAnimation
// ---------------------------------------------------------------------------- // ----------------------------------------------------------------------------
/** Updates position and rotation of this model. Called once per time step. /** Updates position and rotation of this model. Called once per time step.
* \param dt Time since last call. * \param dt Time since last call.
@ -60,4 +126,14 @@ void ThreeDAnimation::update(float dt)
AnimationBase::update(dt, &xyz, &hpr); //updates all IPOs AnimationBase::update(dt, &xyz, &hpr); //updates all IPOs
m_animated_node->setPosition(xyz); m_animated_node->setPosition(xyz);
m_animated_node->setRotation(hpr); m_animated_node->setRotation(hpr);
// Now update the position of the bullet body if there is one:
if(m_body)
{
hpr = DEGREE_TO_RAD*hpr;
btQuaternion q(hpr.X, hpr.Y, hpr.Z);
Vec3 p(xyz);
btTransform trans(q,p);
m_motion_state->setWorldTransform(trans);
}
} // update } // update

View File

@ -21,12 +21,14 @@
#define HEADER_THREE_D_ANIMATION_HPP #define HEADER_THREE_D_ANIMATION_HPP
#include <string> #include <string>
#include <vector>
#include "irrlicht.h" #include "irrlicht.h"
using namespace irr; using namespace irr;
#include "btBulletDynamicsCommon.h"
#include "animations/animation_base.hpp" #include "animations/animation_base.hpp"
#include "physics/user_pointer.hpp"
class XMLNode; class XMLNode;
class BezierCurve; class BezierCurve;
@ -40,10 +42,25 @@ private:
/** The scene node for the model. */ /** The scene node for the model. */
scene::IAnimatedMeshSceneNode *m_animated_node; scene::IAnimatedMeshSceneNode *m_animated_node;
/** The bullet collision shape for the physics. */
btCollisionShape *m_collision_shape;
/** The bullet rigid body. */
btRigidBody *m_body;
/** Motion state of the physical object. */
btMotionState *m_motion_state;
/** A user pointer to connect a bullet body with this object. */
UserPointer m_user_pointer;
void createPhysicsBody(const std::string &shape);
public: public:
ThreeDAnimation(const std::string &track_name, ThreeDAnimation(const std::string &track_name,
const XMLNode &node, float fps); const XMLNode &node, float fps);
virtual ~ThreeDAnimation(){} virtual ~ThreeDAnimation();
virtual void update(float dt); virtual void update(float dt);
}; // ThreeDAnimation }; // ThreeDAnimation

View File

@ -159,7 +159,7 @@ void Camera::update(float dt)
steering = m_kart->getSteerPercent() * (1.0f + (m_kart->getSkidding() - 1.0f)/2.3f ); // dampen skidding effect steering = m_kart->getSteerPercent() * (1.0f + (m_kart->getSkidding() - 1.0f)/2.3f ); // dampen skidding effect
dampened_steer = fabsf(steering) * steering; // quadratically to dampen small variations (but keep sign) dampened_steer = fabsf(steering) * steering; // quadratically to dampen small variations (but keep sign)
m_angle_around = m_kart->getHPR().getX() + m_rotation_range * dampened_steer * 0.5f; m_angle_around = m_kart->getHPR().getX() + m_rotation_range * dampened_steer * 0.5f;
m_angle_up = m_kart->getHPR().getY() - DEGREE_TO_RAD(30.0f); m_angle_up = m_kart->getHPR().getY() - 30.0f*DEGREE_TO_RAD;
m_target = m_kart->getXYZ(); m_target = m_kart->getXYZ();
m_target.setZ(m_target.getZ()+0.75f); m_target.setZ(m_target.getZ()+0.75f);
@ -173,7 +173,7 @@ void Camera::update(float dt)
break; break;
case CM_REVERSE: // Same as CM_NORMAL except it looks backwards case CM_REVERSE: // Same as CM_NORMAL except it looks backwards
m_angle_around = m_kart->getHPR().getX() - m_rotation_range * m_kart->getSteerPercent() * m_kart->getSkidding(); m_angle_around = m_kart->getHPR().getX() - m_rotation_range * m_kart->getSteerPercent() * m_kart->getSkidding();
m_angle_up = m_kart->getHPR().getY() + DEGREE_TO_RAD(30.0f); m_angle_up = m_kart->getHPR().getY() + 30.0f*DEGREE_TO_RAD;
m_target = m_kart->getXYZ(); m_target = m_kart->getXYZ();
m_target.setZ(m_target.getZ()+0.75f); m_target.setZ(m_target.getZ()+0.75f);
@ -187,7 +187,7 @@ void Camera::update(float dt)
break; break;
case CM_CLOSEUP: // Lower to the ground and closer to the kart case CM_CLOSEUP: // Lower to the ground and closer to the kart
m_angle_around = m_kart->getHPR().getX() + m_rotation_range * m_kart->getSteerPercent() * m_kart->getSkidding(); m_angle_around = m_kart->getHPR().getX() + m_rotation_range * m_kart->getSteerPercent() * m_kart->getSkidding();
m_angle_up = m_kart->getHPR().getY() - DEGREE_TO_RAD(20.0f); m_angle_up = m_kart->getHPR().getY() - 20.0f*DEGREE_TO_RAD;
m_target = m_kart->getXYZ(); m_target = m_kart->getXYZ();
m_target.setZ(m_target.getZ()+0.75f); m_target.setZ(m_target.getZ()+0.75f);
@ -202,7 +202,7 @@ void Camera::update(float dt)
case CM_LEADER_MODE: // Follows the leader kart, higher off of the ground, further from the kart, case CM_LEADER_MODE: // Follows the leader kart, higher off of the ground, further from the kart,
// and turns in the opposite direction from the kart for a nice effect. :) // and turns in the opposite direction from the kart for a nice effect. :)
m_angle_around = RaceManager::getKart(0)->getHPR().getX(); m_angle_around = RaceManager::getKart(0)->getHPR().getX();
m_angle_up = RaceManager::getKart(0)->getHPR().getY() + DEGREE_TO_RAD(40.0f); m_angle_up = RaceManager::getKart(0)->getHPR().getY() + 40.0f*DEGREE_TO_RAD;
m_target = RaceManager::getKart(0)->getXYZ(); m_target = RaceManager::getKart(0)->getXYZ();

View File

@ -72,9 +72,9 @@ void Nitro::update(float t)
// There seems to be no way to randomise the velocity for particles, // There seems to be no way to randomise the velocity for particles,
// so we have to do this manually, by changing the default velocity. // so we have to do this manually, by changing the default velocity.
// Irrlicht expects velocity (called 'direction') in m/ms!! // Irrlicht expects velocity (called 'direction') in m/ms!!
Vec3 dir(cos(DEGREE_TO_RAD(rand()%180))*0.001f, Vec3 dir(cos(DEGREE_TO_RAD*(rand()%180))*0.001f,
sin(DEGREE_TO_RAD(rand()%180))*0.001f, sin(DEGREE_TO_RAD*(rand()%180))*0.001f,
sin(DEGREE_TO_RAD(rand()%100))*0.001f); sin(DEGREE_TO_RAD*(rand()%100))*0.001f);
m_emitter->setDirection(dir.toIrrVector()); m_emitter->setDirection(dir.toIrrVector());
} // update } // update

View File

@ -84,9 +84,9 @@ void Smoke::update(float t)
// There seems to be no way to randomise the velocity for particles, // There seems to be no way to randomise the velocity for particles,
// so we have to do this manually, by changing the default velocity. // so we have to do this manually, by changing the default velocity.
// Irrlicht expects velocity (called 'direction') in m/ms!! // Irrlicht expects velocity (called 'direction') in m/ms!!
Vec3 dir(cos(DEGREE_TO_RAD(rand()%180))*0.002f, Vec3 dir(cos(DEGREE_TO_RAD*(rand()%180))*0.002f,
sin(DEGREE_TO_RAD(rand()%180))*0.002f, sin(DEGREE_TO_RAD*(rand()%180))*0.002f,
sin(DEGREE_TO_RAD(rand()%100))*0.002f); sin(DEGREE_TO_RAD*(rand()%100))*0.002f);
m_emitter->setDirection(dir.toIrrVector()); m_emitter->setDirection(dir.toIrrVector());
} // update } // update

View File

@ -97,8 +97,8 @@ void WaterSplash::update(float t)
float f=m_kart->getSpeed(); float f=m_kart->getSpeed();
if(f<1) return; // avoid problem with modulo 0 if(f<1) return; // avoid problem with modulo 0
Vec3 dir((rand()%int(f))*(left?-1:1)*0.004f, Vec3 dir((rand()%int(f))*(left?-1:1)*0.004f,
sin(DEGREE_TO_RAD(rand()%180))*0.004f, sin(DEGREE_TO_RAD*(rand()%180))*0.004f,
sin(DEGREE_TO_RAD(rand()%100))*0.004f); sin(DEGREE_TO_RAD*(rand()%100))*0.004f);
m_emitter->setDirection(dir.toIrrVector()); m_emitter->setDirection(dir.toIrrVector());
} // update } // update

View File

@ -616,8 +616,8 @@ void LinearWorld::checkForWrongDirection(unsigned int i)
else if (angle_diff < -M_PI) angle_diff += 2*M_PI; else if (angle_diff < -M_PI) angle_diff += 2*M_PI;
// Display a warning message if the kart is going back way (unless // Display a warning message if the kart is going back way (unless
// the kart has already finished the race). // the kart has already finished the race).
if (( angle_diff > DEGREE_TO_RAD( 120.0f) || if (( angle_diff > DEGREE_TO_RAD* 120.0f ||
angle_diff < DEGREE_TO_RAD(-120.0f)) && angle_diff < -DEGREE_TO_RAD*120.0f) &&
kart->getVelocityLC().getY() > 0.0f && kart->getVelocityLC().getY() > 0.0f &&
!kart->hasFinishedRace() ) !kart->hasFinishedRace() )
{ {

View File

@ -28,12 +28,18 @@ class Moveable;
class Flyable; class Flyable;
class Kart; class Kart;
class PhysicalObject; class PhysicalObject;
class ThreeDAnimation;
/** A UserPointer is stored as a user pointer in all bullet bodies. This
* allows easily finding the appropriate STK object for a bullet body.
*/
class UserPointer class UserPointer
{ {
public: public:
/** List of all possibles STK objects that are represented in the
* physics. */
enum UserPointerType {UP_UNDEF, UP_KART, UP_FLYABLE, UP_TRACK, enum UserPointerType {UP_UNDEF, UP_KART, UP_FLYABLE, UP_TRACK,
UP_PHYSICAL_OBJECT}; UP_PHYSICAL_OBJECT, UP_ANIMATION};
private: private:
void* m_pointer; void* m_pointer;
UserPointerType m_user_pointer_type; UserPointerType m_user_pointer_type;
@ -44,6 +50,7 @@ public:
Flyable* getPointerFlyable() const {return (Flyable*)m_pointer; } Flyable* getPointerFlyable() const {return (Flyable*)m_pointer; }
Kart* getPointerKart() const {return (Kart*)m_pointer; } Kart* getPointerKart() const {return (Kart*)m_pointer; }
PhysicalObject *getPointerPhysicalObject() const {return (PhysicalObject*)m_pointer; } PhysicalObject *getPointerPhysicalObject() const {return (PhysicalObject*)m_pointer; }
ThreeDAnimation*getPointerAnimation() const {return (ThreeDAnimation*)m_pointer;}
void set(PhysicalObject* p) { m_user_pointer_type=UP_PHYSICAL_OBJECT; void set(PhysicalObject* p) { m_user_pointer_type=UP_PHYSICAL_OBJECT;
m_pointer =p; } m_pointer =p; }
void set(Kart* p) { m_user_pointer_type=UP_KART; void set(Kart* p) { m_user_pointer_type=UP_KART;
@ -52,6 +59,8 @@ public:
m_pointer =p; } m_pointer =p; }
void set(TriangleMesh* p) { m_user_pointer_type=UP_TRACK; void set(TriangleMesh* p) { m_user_pointer_type=UP_TRACK;
m_pointer =p; } m_pointer =p; }
void set(ThreeDAnimation* p){ m_user_pointer_type=UP_ANIMATION;
m_pointer =p; }
UserPointer() { zero(); } UserPointer() { zero(); }
void zero() { m_user_pointer_type=UP_UNDEF; void zero() { m_user_pointer_type=UP_UNDEF;
m_pointer = NULL; } m_pointer = NULL; }

View File

@ -302,7 +302,7 @@ void DefaultRobot::handleBraking()
kart_ang_diff = normalizeAngle(kart_ang_diff); kart_ang_diff = normalizeAngle(kart_ang_diff);
kart_ang_diff = fabsf(kart_ang_diff); kart_ang_diff = fabsf(kart_ang_diff);
const float MIN_TRACK_ANGLE = DEGREE_TO_RAD(20.0f); const float MIN_TRACK_ANGLE = DEGREE_TO_RAD*20.0f;
const float CURVE_INSIDE_PERC = 0.25f; const float CURVE_INSIDE_PERC = 0.25f;
//Brake only if the road does not goes somewhat straight. //Brake only if the road does not goes somewhat straight.
@ -314,7 +314,7 @@ void DefaultRobot::handleBraking()
//out of the curve. //out of the curve.
if(!(m_world->getDistanceToCenterForKart(getWorldKartId()) if(!(m_world->getDistanceToCenterForKart(getWorldKartId())
> m_quad_graph->getNode(m_track_node).getPathWidth() * > m_quad_graph->getNode(m_track_node).getPathWidth() *
-CURVE_INSIDE_PERC || m_curve_angle > RAD_TO_DEGREE(getMaxSteerAngle()))) -CURVE_INSIDE_PERC || m_curve_angle > RAD_TO_DEGREE*getMaxSteerAngle()))
{ {
m_controls.m_brake = false; m_controls.m_brake = false;
return; return;
@ -324,7 +324,7 @@ void DefaultRobot::handleBraking()
{ {
if(!(m_world->getDistanceToCenterForKart( getWorldKartId() ) if(!(m_world->getDistanceToCenterForKart( getWorldKartId() )
< m_quad_graph->getNode(m_track_node).getPathWidth() * < m_quad_graph->getNode(m_track_node).getPathWidth() *
CURVE_INSIDE_PERC || m_curve_angle < -RAD_TO_DEGREE(getMaxSteerAngle()))) CURVE_INSIDE_PERC || m_curve_angle < -RAD_TO_DEGREE*getMaxSteerAngle()))
{ {
m_controls.m_brake = false; m_controls.m_brake = false;
return; return;

View File

@ -159,7 +159,7 @@ btTransform Track::getStartTransform(unsigned int pos) const
start.setOrigin(orig); start.setOrigin(orig);
start.setRotation(btQuaternion(btVector3(0, 0, 1), start.setRotation(btQuaternion(btVector3(0, 0, 1),
pos<m_start_heading.size() pos<m_start_heading.size()
? DEGREE_TO_RAD(m_start_heading[pos]) ? DEGREE_TO_RAD*m_start_heading[pos]
: 0.0f )); : 0.0f ));
return start; return start;
} // getStartTransform } // getStartTransform

View File

@ -54,7 +54,7 @@
#endif #endif
#define NINETY_DEGREE_RAD (M_PI/2.0f) #define NINETY_DEGREE_RAD (M_PI/2.0f)
#define DEGREE_TO_RAD(x) ((x)*M_PI/180.0f) #define DEGREE_TO_RAD (M_PI/180.0f)
#define RAD_TO_DEGREE(x) ((x)*180.0f/M_PI) #define RAD_TO_DEGREE (180.0f/M_PI)
#endif #endif

View File

@ -78,9 +78,9 @@ void Vec3::setHPR(const btMatrix3x3& m)
// ---------------------------------------------------------------------------- // ----------------------------------------------------------------------------
void Vec3::degreeToRad() void Vec3::degreeToRad()
{ {
m_x=DEGREE_TO_RAD(m_x); m_x=DEGREE_TO_RAD*m_x;
m_y=DEGREE_TO_RAD(m_y); m_y=DEGREE_TO_RAD*m_y;
m_z=DEGREE_TO_RAD(m_z); m_z=DEGREE_TO_RAD*m_z;
} // degreeToRad } // degreeToRad
// ---------------------------------------------------------------------------- // ----------------------------------------------------------------------------
@ -109,12 +109,11 @@ void Vec3::setPitchRoll(const Vec3 &normal)
* FIXME: this function should be inlined, but while debugging it's * FIXME: this function should be inlined, but while debugging it's
* easier (compile-time wise) to modify it here :) * easier (compile-time wise) to modify it here :)
*/ */
#ifdef HAVE_IRRLICHT
const core::vector3df Vec3::toIrrHPR() const const core::vector3df Vec3::toIrrHPR() const
{ {
core::vector3df r(RAD_TO_DEGREE(-getY()), // pitch core::vector3df r(RAD_TO_DEGREE*(-getY()), // pitch
RAD_TO_DEGREE(-getX()), // heading RAD_TO_DEGREE*(-getX()), // heading
RAD_TO_DEGREE(-getZ()) ); // roll RAD_TO_DEGREE*(-getZ()) ); // roll
return r; return r;
} // toIrrHPR } // toIrrHPR
@ -124,4 +123,3 @@ const core::vector3df Vec3::toIrrVector() const
core::vector3df v(m_x, m_z, m_y); core::vector3df v(m_x, m_z, m_y);
return v; return v;
} // toIrrVector } // toIrrVector
#endif

View File

@ -17,11 +17,8 @@
#ifndef HEADER_VEC3_HPP #ifndef HEADER_VEC3_HPP
#define HEADER_VEC3_HPP #define HEADER_VEC3_HPP
#ifdef HAVE_IRRLICHT
#include "irrlicht.h" #include "irrlicht.h"
using namespace irr; using namespace irr;
#endif
#include "LinearMath/btVector3.h" #include "LinearMath/btVector3.h"
#include "LinearMath/btMatrix3x3.h" #include "LinearMath/btMatrix3x3.h"
@ -35,7 +32,6 @@ private:
void setPitchRoll(const Vec3 &normal); void setPitchRoll(const Vec3 &normal);
public: public:
#ifdef HAVE_IRRLICHT
/** Convert an irrlicht vector3df into the internal (bullet) format. /** Convert an irrlicht vector3df into the internal (bullet) format.
* Irrlicht's and STK's axis are different (STK: Z up, irrlicht: Y up). * Irrlicht's and STK's axis are different (STK: Z up, irrlicht: Y up).
* We might want to change this as well, makes it easier to work with * We might want to change this as well, makes it easier to work with
@ -45,7 +41,6 @@ public:
* a vec3). * a vec3).
*/ */
inline Vec3(const core::vector3df &v) : btVector3(v.X, v.Z, v.Y) {} inline Vec3(const core::vector3df &v) : btVector3(v.X, v.Z, v.Y) {}
#endif
//inline Vec3(sgVec3 a) : btVector3(a[0], a[1], a[2]) {} //inline Vec3(sgVec3 a) : btVector3(a[0], a[1], a[2]) {}
inline Vec3(const btVector3& a) : btVector3(a) {} inline Vec3(const btVector3& a) : btVector3(a) {}
inline Vec3() : btVector3() {} inline Vec3() : btVector3() {}
@ -68,11 +63,9 @@ public:
inline const void setPitch(float f) {m_y = f;} inline const void setPitch(float f) {m_y = f;}
inline const void setRoll(float f) {m_z = f;} inline const void setRoll(float f) {m_z = f;}
float* toFloat() const {return (float*)this; } float* toFloat() const {return (float*)this; }
#ifdef HAVE_IRRLICHT
/** Converts a Vec3 to an irrlicht 3d floating point vector. */ /** Converts a Vec3 to an irrlicht 3d floating point vector. */
const core::vector3df toIrrVector() const; const core::vector3df toIrrVector() const;
const core::vector3df toIrrHPR() const; const core::vector3df toIrrHPR() const;
#endif
void degreeToRad(); void degreeToRad();
Vec3& operator=(const btVector3& a) {*(btVector3*)this=a; return *this;} Vec3& operator=(const btVector3& a) {*(btVector3*)this=a; return *this;}
Vec3& operator=(const btMatrix3x3& m) {setHPR(m); return *this;} Vec3& operator=(const btMatrix3x3& m) {setHPR(m); return *this;}