6#include "CustomHinge.h"
7#include "CustomSlider.h"
8#include "CustomBallAndSocket.h"
9#include "CustomUpVector.h"
10#include "CustomKinematicController.h"
12#include <OgreLogManager.h>
13#include <OgreStringConverter.h>
23 CustomJoint* suppportJoint;
26 dMatrix pinsAndPivoFrame(dGetIdentityMatrix());
27 pinsAndPivoFrame.m_posit = dVector(pos.x, pos.y, pos.z);
30 suppportJoint =
new CustomLimitBallAndSocket(pinsAndPivoFrame, child->
getNewtonBody(), parent ? parent->
getNewtonBody() : NULL);
41 CustomLimitBallAndSocket* joint = (CustomLimitBallAndSocket*)
m_joint;
42 joint->SetConeAngle((
float)maxCone.valueRadians());
43 joint->SetTwistAngle((
float)minTwist.valueRadians(), (float)maxTwist.valueRadians());
48 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
50 NewtonBallGetJointAngle(
m_joint->GetJoint(), &fvec.m_x);
51 if (!_isnan(fvec.m_x))
52 ret.x = Ogre::Real(fvec.m_x);
53 if (!_isnan(fvec.m_y))
54 ret.y = Ogre::Real(fvec.m_y);
55 if (!_isnan(fvec.m_z))
56 ret.z = Ogre::Real(fvec.m_z);
62 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
64 NewtonBallGetJointOmega(
m_joint->GetJoint(), &fvec.m_x);
65 if (!_isnan(fvec.m_x))
66 ret.x = Ogre::Real(fvec.m_x);
67 if (!_isnan(fvec.m_y))
68 ret.y = Ogre::Real(fvec.m_y);
69 if (!_isnan(fvec.m_z))
70 ret.z = Ogre::Real(fvec.m_z);
76 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
78 NewtonBallGetJointForce(
m_joint->GetJoint(), &fvec.m_x);
79 if (!_isnan(fvec.m_x))
80 ret.x = Ogre::Real(fvec.m_x);
81 if (!_isnan(fvec.m_y))
82 ret.y = Ogre::Real(fvec.m_y);
83 if (!_isnan(fvec.m_z))
84 ret.z = Ogre::Real(fvec.m_z);
90 CustomJoint* suppportJoint;
93 dMatrix pinsAndPivoFrame(dGetIdentityMatrix());
94 pinsAndPivoFrame.m_posit = dVector(pos.x, pos.y, pos.z, 1.0f);
108 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
110 NewtonBallGetJointAngle(
m_joint->GetJoint(), &fvec.m_x);
111 if (!_isnan(fvec.m_x))
112 ret.x = Ogre::Real(fvec.m_x);
113 if (!_isnan(fvec.m_y))
114 ret.y = Ogre::Real(fvec.m_y);
115 if (!_isnan(fvec.m_z))
116 ret.z = Ogre::Real(fvec.m_z);
122 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
124 NewtonBallGetJointOmega(
m_joint->GetJoint(), &fvec.m_x);
125 if (!_isnan(fvec.m_x))
126 ret.x = Ogre::Real(fvec.m_x);
127 if (!_isnan(fvec.m_y))
128 ret.y = Ogre::Real(fvec.m_y);
129 if (!_isnan(fvec.m_z))
130 ret.z = Ogre::Real(fvec.m_z);
136 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
138 NewtonBallGetJointForce(
m_joint->GetJoint(), &fvec.m_x);
139 if (!_isnan(fvec.m_x))
140 ret.x = Ogre::Real(fvec.m_x);
141 if (!_isnan(fvec.m_y))
142 ret.y = Ogre::Real(fvec.m_y);
143 if (!_isnan(fvec.m_z))
144 ret.z = Ogre::Real(fvec.m_z);
150 CustomJoint* suppportJoint;
153 dMatrix pinsAndPivoFrame(dGetIdentityMatrix());
154 pinsAndPivoFrame.m_posit = dVector(pos.x, pos.y, pos.z, 1.0f);
157 suppportJoint =
new CustomControlledBallAndSocket(pinsAndPivoFrame, child->
getNewtonBody(), parent ? parent->
getNewtonBody() : NULL);
168 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
170 NewtonBallGetJointAngle(
m_joint->GetJoint(), &fvec.m_x);
171 if (!_isnan(fvec.m_x))
172 ret.x = Ogre::Real(fvec.m_x);
173 if (!_isnan(fvec.m_y))
174 ret.y = Ogre::Real(fvec.m_y);
175 if (!_isnan(fvec.m_z))
176 ret.z = Ogre::Real(fvec.m_z);
182 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
184 NewtonBallGetJointOmega(
m_joint->GetJoint(), &fvec.m_x);
185 if (!_isnan(fvec.m_x))
186 ret.x = Ogre::Real(fvec.m_x);
187 if (!_isnan(fvec.m_y))
188 ret.y = Ogre::Real(fvec.m_y);
189 if (!_isnan(fvec.m_z))
190 ret.z = Ogre::Real(fvec.m_z);
196 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
198 NewtonBallGetJointForce(
m_joint->GetJoint(), &fvec.m_x);
199 if (!_isnan(fvec.m_x))
200 ret.x = Ogre::Real(fvec.m_x);
201 if (!_isnan(fvec.m_y))
202 ret.y = Ogre::Real(fvec.m_y);
203 if (!_isnan(fvec.m_z))
204 ret.z = Ogre::Real(fvec.m_z);
210 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
211 joint->SetAngularVelocity(dFloat(omegaMag));
221 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
222 return Ogre::Real(joint->GetAngularVelocity());
227 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
228 joint->SetPitchAngle(dFloat(angle));
238 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
239 return Ogre::Real(joint->SetPitchAngle());
244 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
245 joint->SetYawAngle(dFloat(angle));
255 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
256 return Ogre::Real(joint->SetYawAngle());
261 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
262 joint->SetRollAngle(dFloat(angle));
272 CustomControlledBallAndSocket* joint = (CustomControlledBallAndSocket*)
m_joint;
273 return Ogre::Real(joint->SetRollAngle());
280 CustomJoint* suppportJoint;
283 dVector dir(pin.x, pin.y, pin.z, 0.0f);
284 dMatrix pinsAndPivoFrame(dGrammSchmidt(dir));
285 pinsAndPivoFrame.m_posit = dVector(pos.x, pos.y, pos.z, 1.0f);
347 if (_isnan(omega.valueRadians()) || _isnan(strength))
404 if (_isnan(maxForce))
418 return Ogre::Radian(Ogre::Real(joint->GetJointAngle()));
423 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
425 NewtonHingeGetJointForce(
m_joint->GetJoint(), &fvec.m_x);
426 if (!_isnan(fvec.m_x))
427 ret.x = Ogre::Real(fvec.m_x);
428 if (!_isnan(fvec.m_y))
429 ret.y = Ogre::Real(fvec.m_y);
430 if (!_isnan(fvec.m_z))
431 ret.z = Ogre::Real(fvec.m_z);
438 if (_isnan(joint->GetJointOmega()))
439 return Ogre::Radian(0.0);
440 return Ogre::Radian(Ogre::Real(joint->GetJointOmega()));
446 dVector pin(joint->GetPinAxis());
448 return Ogre::Vector3(Ogre::Real(pin.m_x), Ogre::Real(pin.m_y), Ogre::Real(pin.m_z));
453 Ogre::Real invTimestep = (timestep > 0.0f) ? 1.0f / timestep : 1.0f;
474 Ogre::Real acceleration = relativeOmega.valueRadians() * invTimestep;
629 CustomJoint* suppportJoint;
635 m_springStrength = 0.0f;
636 m_springDamping = 0.0f;
639 dVector dir(pin.x, pin.y, pin.z, 0.0f);
640 dMatrix pinsAndPivoFrame(dGrammSchmidt(dir));
641 pinsAndPivoFrame.m_posit = dVector(pos.x, pos.y, pos.z, 1.0f);
657 joint->EnableLimits(state);
669 joint->EnableMotor(state);
679 if (_isnan(velocity) || _isnan(strength))
682 joint->SetMotorVelocity(velocity, strength);
692 m_minDist = minStopDist;
693 m_maxDist = maxStopDist;
696 joint->SetLimis(minStopDist, maxStopDist);
711 m_springStrength = springStrength;
712 m_springDamping = springDamping;
717 Ogre::Vector3 ret = Ogre::Vector3::ZERO;
719 NewtonSliderGetJointForce(
m_joint->GetJoint(), &fvec.m_x);
720 if (!_isnan(fvec.m_x))
721 ret.x = Ogre::Real(fvec.m_x);
722 if (!_isnan(fvec.m_y))
723 ret.y = Ogre::Real(fvec.m_y);
724 if (!_isnan(fvec.m_z))
725 ret.z = Ogre::Real(fvec.m_z);
731 return Ogre::Real(NewtonSliderGetJointVeloc(
m_joint->GetJoint()));
737 return Ogre::Real(joint->GetDistance());
743 joint->SetFriction(friction);
758 dVector dPin(m_pin.x, m_pin.y, m_pin.z, 1.0f);
759 CustomUpVector* support_joint =
new CustomUpVector(dPin, body->
getNewtonBody());
769 CustomUpVector* up_vector =
static_cast<CustomUpVector*
>(
m_joint);
770 m_pin = pin.normalisedCopy();
771 dVector dPin(m_pin.x, m_pin.y, m_pin.z, 1.0f);
772 up_vector->SetPinDir(dPin);
783 CustomJoint* suppportJoint;
786 dVector attachement(pos.x, pos.y, pos.z, 0.0f);
789 suppportJoint =
new CustomKinematicController(child->
getNewtonBody(), attachement);
799 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
800 joint->SetPickMode(mode);
805 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
806 joint->SetMaxLinearFriction(accel);
811 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
812 joint->SetMaxAngularFriction(alpha);
818 dVector posit(position.x, position.y, position.z, 0.0f);
819 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
820 joint->SetTargetPosit(posit);
825 dQuaternion rotat(rotation.w, rotation.x, rotation.y, rotation.z);
827 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
828 joint->SetTargetRotation(rotat);
837 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
838 joint->SetTargetMatrix(matrix);
843 CustomKinematicController* joint = (CustomKinematicController*)
GetSupportJoint();
844 dMatrix matrix(joint->GetTargetMatrix());
856 NewtonSliderGetJointForce(
m_joint, &ret.x);
861 unsigned _CDECL Slider::newtonCallback(
const NewtonJoint* slider, NewtonHingeSliderUpdateDesc* desc)
863 Slider* me = (Slider*)NewtonJointGetUserData(slider);
869 (*me->m_callback)(me);
878 void Slider::setCallbackAccel(Ogre::Real accel)
883 m_desc->m_accel = (float)accel;
887 void Slider::setCallbackFrictionMin(Ogre::Real min)
892 m_desc->m_minFriction = (float)min;
896 void Slider::setCallbackFrictionMax(Ogre::Real max)
901 m_desc->m_maxFriction = (float)max;
905 Ogre::Real Slider::getCallbackTimestep()
const
908 return (Ogre::Real)m_desc->m_timestep;
913 Ogre::Real Slider::calculateStopAccel(Ogre::Real dist)
const
916 return (Ogre::Real)NewtonSliderCalculateStopAccel(
m_joint, m_desc, (
float)dist);
943 NewtonJointSetUserData(
m_joint,
this);
944 NewtonJointSetDestructor(
m_joint, destructor);
958 NewtonUniversalGetJointForce(
m_joint, &ret.x);
982 if (axis > 1) {
return; }
987 m_desc[axis].m_accel = (float)accel;
993 if (axis > 1) {
return; }
998 m_desc[axis].m_maxFriction = (float)max;
1004 if (axis > 1) {
return; }
1009 m_desc[axis].m_minFriction = (float)min;
1016 return (Ogre::Real)
m_desc->m_timestep;
1024 return (Ogre::Real)NewtonUniversalCalculateStopAlpha0(
m_joint,
m_desc, (
float)angle);
1032 return (Ogre::Real)NewtonUniversalCalculateStopAlpha1(
m_joint,
m_desc, (
float)angle);
1049 NewtonJointSetUserData(
m_joint,
this);
1050 NewtonJointSetDestructor(
m_joint, destructor);
1062 NewtonUpVectorGetPin(
m_joint, &ret.x);
1087 namespace PrebuiltCustomJoints
1093 Ogre::Quaternion bodyorient;
1094 Ogre::Vector3 bodypos;
1098 pinAndDirToLocal(bodypos, pin, mLocalOrient0, mLocalPos0, mLocalOrient1, mLocalPos1);
1101 mMin = mMax = Ogre::Degree(0);
1111 Ogre::Quaternion globalOrient0, globalOrient1;
1112 Ogre::Vector3 globalPos0, globalPos1;
1114 localToGlobal(mLocalOrient0, mLocalPos0, globalOrient0, globalPos0, 0);
1115 localToGlobal(mLocalOrient1, mLocalPos1, globalOrient1, globalPos1, 1);
1118 Ogre::Vector3 bod0X = globalOrient0 * Ogre::Vector3(Ogre::Vector3::UNIT_X);
1119 Ogre::Vector3 bod0Y = globalOrient0 * Ogre::Vector3(Ogre::Vector3::UNIT_Y);
1120 Ogre::Vector3 bod0Z = globalOrient0 * Ogre::Vector3(Ogre::Vector3::UNIT_Z);
1122 Ogre::Vector3 bod1X = globalOrient1 * Ogre::Vector3(Ogre::Vector3::UNIT_X);
1123 Ogre::Vector3 bod1Y = globalOrient1 * Ogre::Vector3(Ogre::Vector3::UNIT_Y);
1124 Ogre::Vector3 bod1Z = globalOrient1 * Ogre::Vector3(Ogre::Vector3::UNIT_Z);
1127 Ogre::LogManager::getSingletonPtr()->logMessage(
" Submit Constraint bod0X:" + Ogre::StringConverter::toString(bod0X) +
1128 " bod1X:" + Ogre::StringConverter::toString(bod1X));
1136 Ogre::Plane thePlane(bod0X, globalPos0);
1137 Ogre::Real stray = thePlane.getDistance(globalPos1);
1138 if (stray > 0.0001f)
1141 Ogre::Real accel = (stray / timeStep);
1142 if (thePlane.getSide(globalPos1) == Ogre::Plane::NEGATIVE_SIDE) { accel = -accel; }
1148 Ogre::Vector3 latDir = bod0X.crossProduct(bod1X);
1149 Ogre::Real latMag = latDir.squaredLength();
1151 if (latMag > 1.0e-6f)
1154 latMag = Ogre::Math::Sqrt(latMag);
1156 Ogre::Radian angle = Ogre::Math::ASin(latMag);
1163 Ogre::Vector3 latDir2 = latDir.crossProduct(bod1X);
1175 Ogre::Real cos = bod0Y.dotProduct(bod1Y);
1176 Ogre::Real sin = (bod0Y.crossProduct(bod1Y)).dotProduct(bod0X);
1178 mAngle = Ogre::Math::ATan2(sin, cos);
1184 Ogre::Radian diff = mAngle - mMax;
1189 else if (mAngle < mMin)
1191 Ogre::Radian diff = mAngle - mMin;
1214 pinAndDirToLocal(pos, dir, mLocalOrient0, mLocalPos0, mLocalOrient1, mLocalPos1);
1224 Ogre::Vector3 globalPos0, globalPos1;
1225 Ogre::Quaternion globalOrient0, globalOrient1;
1227 localToGlobal(mLocalOrient0, mLocalPos0, globalOrient0, globalPos0, 0);
1228 localToGlobal(mLocalOrient1, mLocalPos1, globalOrient1, globalPos1, 1);
1231 addLinearRow(globalPos0, globalPos1, globalOrient0 * Ogre::Vector3::UNIT_X);
1232 addLinearRow(globalPos0, globalPos1, globalOrient0 * Ogre::Vector3::UNIT_Y);
1233 addLinearRow(globalPos0, globalPos1, globalOrient0 * Ogre::Vector3::UNIT_Z);
1236 globalPos0 = globalPos0 + (globalOrient0 * (Ogre::Vector3::UNIT_X * 10.0f));
1237 globalPos1 = globalPos1 + (globalOrient1 * (Ogre::Vector3::UNIT_X * 10.0f));
1240 addLinearRow(globalPos0, globalPos1, globalOrient0 * Ogre::Vector3::UNIT_Y);
1241 addLinearRow(globalPos0, globalPos1, globalOrient0 * Ogre::Vector3::UNIT_Z);
1243 Ogre::Vector3 xdir0 = globalOrient0 * Ogre::Vector3::UNIT_X;
1244 Ogre::Vector3 xdir1 = globalOrient1 * Ogre::Vector3::UNIT_X;
1246 Ogre::Radian angle = Ogre::Math::ACos(xdir0.dotProduct(xdir1));
1247 addAngularRow(angle, globalOrient0 * Ogre::Vector3::UNIT_X);
~BallAndSocket()
destructor.
Ogre::Vector3 getJointAngle()
retrieve the current joint angle
Ogre::Vector3 getJointForce()
retrieve the current joint force.
Ogre::Vector3 getJointOmega()
retrieve the current joint omega
BallAndSocket(const OgreNewt::Body *child, const OgreNewt::Body *parent, const Ogre::Vector3 &pos)
constructor
Ogre::Vector3 getJointForce()
retrieve the current joint force.
void setLimits(Ogre::Radian maxCone, Ogre::Radian minTwist, Ogre::Radian maxTwist)
set limits for the joints rotation
Ogre::Vector3 getJointAngle()
retrieve the current joint angle
~BallAndSocketLimits()
destructor.
BallAndSocketLimits(const OgreNewt::Body *child, const OgreNewt::Body *parent, const Ogre::Vector3 &pos)
constructor
Ogre::Vector3 getJointOmega()
retrieve the current joint omega
main class for all Rigid Bodies in the system.
void addTorque(const Ogre::Vector3 &torque)
add torque to the body.
NewtonBody * getNewtonBody() const
get a pointer to the NewtonBody object
void getPositionOrientation(Ogre::Vector3 &pos, Ogre::Quaternion &orient) const
get position and orientation in form of an Ogre::Vector(position) and Ogre::Quaternion(orientation)
~ControlledBallAndSocket()
destructor.
Ogre::Vector3 getJointOmega()
retrieve the current joint omega
void SetPitchAngle(Ogre::Real angle)
void SetAngularVelocity(Ogre::Real omegaMag)
void SetYawAngle(Ogre::Real angle)
Ogre::Real GetPitchAngle() const
Ogre::Real GetYawAngle() const
ControlledBallAndSocket(const OgreNewt::Body *child, const OgreNewt::Body *parent, const Ogre::Vector3 &pos)
constructor
Ogre::Vector3 getJointAngle()
retrieve the current joint angle
void SetRollAngle(Ogre::Real angle)
Ogre::Vector3 getJointForce()
retrieve the current joint force.
Ogre::Real GetAngularVelocity() const
Ogre::Real GetRollAngle() const
Ogre::Radian getJointAngularVelocity() const
get the relative joint angle around the hinge pin.
Ogre::Real m_motorMinFriction
Ogre::Real m_motorMaxFriction
void setLimits(Ogre::Radian minAngle, Ogre::Radian maxAngle)
set minimum and maximum hinge limits.
Ogre::Radian m_desiredAngle
ConstraintType m_constraintType
void setDesiredOmega(Ogre::Radian omega, Ogre::Real strength=0.5f)
sets desired rotational velocity of the joint
void setTorque(Ogre::Real torque)
sets hinge torque
Ogre::Real m_motorStrength
void setDesiredAngle(Ogre::Radian angle, Ogre::Real minFriction=0, Ogre::Real maxFriction=0)
set desired angle and optionally minimum and maximum friction
Hinge(const OgreNewt::Body *child, const OgreNewt::Body *parent, const Ogre::Vector3 &pos, const Ogre::Vector3 &pin)
constructor
Ogre::Radian m_desiredOmega
void setBrake(Ogre::Real maxForce=0)
apply hinge brake for one frame.
Ogre::Vector3 getJointPin() const
get the joint pin in global space
void enableLimits(bool state)
enable hinge limits.
Ogre::Real m_brakeMaxForce
virtual void submitConstraint(Ogre::Real timestep, int threadindex)
must be define for a functioning joint.
Ogre::Vector3 getJointForce()
retrieve the current joint force.
ConstraintType m_lastConstraintType
void enableMotor(bool state)
Ogre::Radian getJointAngle() const
get the relative joint angle around the hinge pin.
base class for all joints.
void setRowMaximumFriction(Ogre::Real friction) const
Body * getBody0() const
get the pointer to the first rigid body
void setRowAcceleration(Ogre::Real accel) const
CustomJoint * GetSupportJoint() const
GetSupportJoint.
void setRowMinimumFriction(Ogre::Real friction) const
void setRowStiffness(Ogre::Real stiffness) const
void addAngularRow(Ogre::Radian relativeAngleError, const Ogre::Vector3 &dir) const
void setRowSpringDamper(Ogre::Real springK, Ogre::Real springD) const
void addLinearRow(const Ogre::Vector3 &pt0, const Ogre::Vector3 &pt1, const Ogre::Vector3 &dir) const
void SetSupportJoint(CustomJoint *supportJoint)
SetSupportJoint.
Body * getBody1() const
get the pointer to the first rigid body
void setTargetPosit(const Ogre::Vector3 &position)
set the position part of the attachment matrix
void getTargetMatrix(Ogre::Vector3 &position, Ogre::Quaternion &rotation) const
set the position and orientation part of the attachment matrix
void setTargetMatrix(const Ogre::Vector3 &position, const Ogre::Quaternion &rotation)
set the position and orientation part of the attachment matrix
void setMaxLinearFriction(Ogre::Real accel)
set the linear acceleration the joint can take before the joint is violated .
void setMaxAngularFriction(Ogre::Real alpha)
set the angular acceleration the joint can take before the joint is violated .
void setTargetRotation(const Ogre::Quaternion &rotation)
set the orientation part of the attachment matrix
void setPickingMode(int mode)
enable limits.
KinematicController(const OgreNewt::Body *child, const Ogre::Vector3 &pos)
constructor
~KinematicController()
destructor.
void pinAndDirToLocal(const Ogre::Vector3 &pinpt, const Ogre::Vector3 &pindir, Ogre::Quaternion &localOrient0, Ogre::Vector3 &localPos0, Ogre::Quaternion &localOrient1, Ogre::Vector3 &localPos1) const
void localToGlobal(const Ogre::Quaternion &localOrient, const Ogre::Vector3 &localPos, Ogre::Quaternion &globalOrient, Ogre::Vector3 &globalPos, int bodyIndex) const
virtual void submitConstraint(Ogre::Real timeStep, int threadIndex)
overloaded function that applies the actual constraint.
Custom2DJoint(const OgreNewt::Body *body, const Ogre::Vector3 &pin)
constructor
CustomRigidJoint(OgreNewt::Body *child, OgreNewt::Body *parent, Ogre::Vector3 dir, Ogre::Vector3 pos)
virtual void submitConstraint(Ogre::Real timeStep, int threadIndex)
must be define for a functioning joint.
Ogre::Real getDistance() const
void enableMotor(bool state)
enable motor.
void setMotorVelocity(Ogre::Real velocity, Ogre::Real strength)
void setSpring(Ogre::Real springStrength, Ogre::Real springDamping)
set spring strenght and damping
Slider(const OgreNewt::Body *child, const OgreNewt::Body *parent, const Ogre::Vector3 &pos, const Ogre::Vector3 &pin)
constructor
virtual void submitConstraint(Ogre::Real timestep, int threadindex)
must be define for a functioning joint.
Ogre::Vector3 getJointForce()
retrieve the current joint force.
void setLimits(Ogre::Real minStopDist, Ogre::Real maxStopDist)
set minimum and maximum stops limits.
void enableSpring(bool state)
enable spring.
void setFriction(Ogre::Real friction)
Ogre::Real getJointVelocity() const
get the relative joint angle around the hinge pin.
void enableLimits(bool state)
enable limits.
this class represents a Universal joint.
Ogre::Real calculateStopAlpha0(Ogre::Real angle) const
calculate the acceleration neccesary to stop the joint at the specified angle on pin 0.
static unsigned _CDECL newtonCallback(const NewtonJoint *universal, NewtonHingeSliderUpdateDesc *desc)
newton callback. used internally.
Universal(const World *world, const OgreNewt::Body *child, const OgreNewt::Body *parent, const Ogre::Vector3 &pos, const Ogre::Vector3 &pin0, const Ogre::Vector3 &pin1)
constructor
void setCallbackAccel(Ogre::Real accel, unsigned axis)
set the acceleration around a particular pin.
void setCallbackFrictionMax(Ogre::Real max, unsigned axis)
set the maximum friction around a particular pin.
Ogre::Vector3 getJointForce() const
get the force on the joint.
NewtonHingeSliderUpdateDesc * m_desc
Ogre::Real calculateStopAlpha1(Ogre::Real angle) const
calculate the acceleration neccesary to stop the joint at the specified angle on pin 1.
void setCallbackFrictionMin(Ogre::Real min, unsigned axis)
set the minimum friction around a particular pin
UniversalCallback m_callback
Ogre::Real getCallbackTimestep() const
get the current phsics timestep.
const Ogre::Vector3 & getPin() const
get the current pin direction.
UpVector(const Body *body, const Ogre::Vector3 &pin)
constructor
void setPin(const Ogre::Vector3 &pin)
set the pin direction.
represents a physics world.
NewtonWorld * getNewtonWorld() const
retrieves a pointer to the NewtonWorld
_OgreNewtExport void MatrixToQuatPos(const dFloat *matrix, Ogre::Quaternion &quat, Ogre::Vector3 &pos)
Take a Newton matrix and create a Quaternion + Position_vector.
_OgreNewtExport void QuatPosToMatrix(const Ogre::Quaternion &quat, const Ogre::Vector3 &pos, dFloat *matrix)
Take a Quaternion and Position Matrix and create a Newton-happy float matrix!