Replaced upright constraint with simpler code that keeps the kart
in mid air aligned to the gravity. This will also enable jumps in section where the gravity is not in the default direction.
This commit is contained in:
parent
7ec2bae8e7
commit
a65959da42
@ -380,9 +380,6 @@
|
||||
downward-impulse-factor="0"
|
||||
track-connection-accel="2"/>
|
||||
|
||||
<!-- Parameters for the upright constraint, which keeps karts upright. -->
|
||||
<upright tolerance="0.2" max-force="30"/>
|
||||
|
||||
<!-- collision
|
||||
impulse-type: STK can apply an additional impulse in case of
|
||||
kart-track collision:
|
||||
|
@ -28,7 +28,6 @@ class AbstractKartAnimation;
|
||||
class Attachment;
|
||||
class btKart;
|
||||
class btQuaternion;
|
||||
class btUprightConstraint;
|
||||
class Controller;
|
||||
class Item;
|
||||
class KartModel;
|
||||
@ -342,9 +341,6 @@ public:
|
||||
/** Returns the bullet vehicle which represents this kart. */
|
||||
virtual btKart* getVehicle() const = 0;
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns the upright constraint for this kart. */
|
||||
virtual btUprightConstraint* getUprightConstraint() const = 0;
|
||||
// ------------------------------------------------------------------------
|
||||
virtual btQuaternion getVisualRotation() const = 0;
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns true if the kart is 'resting', i.e. (nearly) not moving. */
|
||||
|
@ -58,7 +58,6 @@
|
||||
#include "network/network_manager.hpp"
|
||||
#include "physics/btKart.hpp"
|
||||
#include "physics/btKartRaycast.hpp"
|
||||
#include "physics/btUprightConstraint.hpp"
|
||||
#include "physics/physics.hpp"
|
||||
#include "race/history.hpp"
|
||||
#include "tracks/track.hpp"
|
||||
@ -269,7 +268,6 @@ Kart::~Kart()
|
||||
World::getWorld()->getPhysics()->removeKart(this);
|
||||
delete m_vehicle;
|
||||
delete m_vehicle_raycaster;
|
||||
delete m_uprightConstraint;
|
||||
}
|
||||
|
||||
for(int i=0; i<m_kart_chassis.getNumChildShapes(); i++)
|
||||
@ -682,13 +680,6 @@ void Kart::createPhysics()
|
||||
// Obviously these allocs have to be properly managed/freed
|
||||
btTransform t;
|
||||
t.setIdentity();
|
||||
m_uprightConstraint=new btUprightConstraint(this, t);
|
||||
m_uprightConstraint->setLimit(m_kart_properties->getUprightTolerance());
|
||||
m_uprightConstraint->setBounce(0.0f);
|
||||
m_uprightConstraint->setMaxLimitForce(m_kart_properties->getUprightMaxForce());
|
||||
m_uprightConstraint->setErp(1.0f);
|
||||
m_uprightConstraint->setLimitSoftness(1.0f);
|
||||
m_uprightConstraint->setDamping(0.0f);
|
||||
World::getWorld()->getPhysics()->addKart(this);
|
||||
|
||||
} // createPhysics
|
||||
@ -699,8 +690,9 @@ void Kart::flyUp()
|
||||
{
|
||||
m_flying = true;
|
||||
Moveable::flyUp();
|
||||
}
|
||||
} // flyUp
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
void Kart::flyDown()
|
||||
{
|
||||
if (isNearGround())
|
||||
@ -712,7 +704,7 @@ void Kart::flyDown()
|
||||
{
|
||||
Moveable::flyDown();
|
||||
}
|
||||
} // flyUp
|
||||
} // flyDown
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
/** Starts the engine sound effect. Called once the track intro phase is over.
|
||||
@ -957,8 +949,7 @@ bool Kart::isOnGround() const
|
||||
|
||||
//-----------------------------------------------------------------------------
|
||||
/** The kart is near the ground, but not necessarily on it (small jumps). This
|
||||
* is used to determine when to switch off the upright constraint, so that
|
||||
* explosions can be more violent, while still
|
||||
* is used to determine when to stop flying.
|
||||
*/
|
||||
bool Kart::isNearGround() const
|
||||
{
|
||||
@ -1102,21 +1093,6 @@ void Kart::update(float dt)
|
||||
|
||||
m_slipstream->update(dt);
|
||||
|
||||
if (!m_flying)
|
||||
{
|
||||
// When really on air, free fly, when near ground, try to glide /
|
||||
// adjust for landing. If zipped, be stable, so ramp+zipper can
|
||||
// allow nice jumps without scripting the fly
|
||||
// Also disable he upright constraint when gravity is changed by
|
||||
// the terrain
|
||||
if( (!isNearGround() &&
|
||||
m_max_speed->getSpeedIncreaseTimeLeft(MaxSpeed::MS_INCREASE_ZIPPER)<=0.0f ) ||
|
||||
(getMaterial() && getMaterial()->hasGravity()) )
|
||||
m_uprightConstraint->setLimit(M_PI);
|
||||
else
|
||||
m_uprightConstraint->setLimit(m_kart_properties->getUprightTolerance());
|
||||
}
|
||||
|
||||
// TODO: hiker said this probably will be moved to btKart or so when updating bullet engine.
|
||||
// Neutralize any yaw change if the kart leaves the ground, so the kart falls more or less
|
||||
// straight after jumping, but still allowing some "boat shake" (roll and pitch).
|
||||
@ -2041,6 +2017,30 @@ void Kart::updatePhysics(float dt)
|
||||
m_max_speed->setMinSpeed(min_speed);
|
||||
m_max_speed->update(dt);
|
||||
|
||||
// If the kart is flying, keep its up-axis aligned to gravity (which in
|
||||
// turn typically means the kart is parallel to the ground). This avoids
|
||||
// that the kart rotates in mid-air and lands on its side.
|
||||
if(m_vehicle->getNumWheelsOnGround()==0)
|
||||
{
|
||||
btVector3 kart_up = getTrans().getBasis().getColumn(1); // up vector
|
||||
btVector3 terrain_up = m_body->getGravity();
|
||||
float g = World::getWorld()->getTrack()->getGravity();
|
||||
// Normalize the gravity, g is the length of the vector
|
||||
btVector3 new_up = 0.9f * kart_up + 0.1f * terrain_up/-g;
|
||||
// Get the rotation (hpr) based on current heading.
|
||||
Vec3 rotation(getHeading(), new_up);
|
||||
btMatrix3x3 m;
|
||||
m.setEulerZYX(rotation.getX(), rotation.getY(), rotation.getZ());
|
||||
// We can't use getXYZ() for the position here, since the position is
|
||||
// based on interpolation, while the actual center-of-mass-transform
|
||||
// is based on the actual value every 1/60 of a second (using getXYZ()
|
||||
// would result in the kart being pushed ahead a bit, making it jump
|
||||
// much further, depending on fps)
|
||||
btTransform new_trans(m, m_body->getCenterOfMassTransform().getOrigin());
|
||||
//setTrans(new_trans);
|
||||
m_body->setCenterOfMassTransform(new_trans);
|
||||
}
|
||||
|
||||
// To avoid tunneling (which can happen on long falls), clamp the
|
||||
// velocity in Y direction. Tunneling can happen if the Y velocity
|
||||
// is larger than the maximum suspension travel (per frame), since then
|
||||
@ -2048,6 +2048,7 @@ void Kart::updatePhysics(float dt)
|
||||
// not sure if this is enough in all cases!). So the speed is limited
|
||||
// to suspensionTravel / dt with dt = 1/60 (since this is the dt
|
||||
// bullet is using).
|
||||
|
||||
// Only apply if near ground instead of purely based on speed avoiding
|
||||
// the "parachute on top" look.
|
||||
const Vec3 &v = m_body->getLinearVelocity();
|
||||
@ -2056,7 +2057,7 @@ void Kart::updatePhysics(float dt)
|
||||
Vec3 v_clamped = v;
|
||||
// clamp the speed to 99% of the maxium falling speed.
|
||||
v_clamped.setY(-m_kart_properties->getSuspensionTravelCM()*0.01f*60 * 0.99f);
|
||||
m_body->setLinearVelocity(v_clamped);
|
||||
//m_body->setLinearVelocity(v_clamped);
|
||||
}
|
||||
|
||||
//at low velocity, forces on kart push it back and forth so we ignore this
|
||||
|
@ -35,7 +35,6 @@
|
||||
#include "utils/no_copy.hpp"
|
||||
|
||||
class btKart;
|
||||
class btUprightConstraint;
|
||||
|
||||
class Attachment;
|
||||
class Controller;
|
||||
@ -146,7 +145,6 @@ private:
|
||||
btCompoundShape m_kart_chassis;
|
||||
btVehicleRaycaster *m_vehicle_raycaster;
|
||||
btKart *m_vehicle;
|
||||
btUprightConstraint *m_uprightConstraint;
|
||||
|
||||
/** The amount of energy collected by hitting coins. Note that it
|
||||
* must be float, since dt is subtraced in each timestep. */
|
||||
@ -344,10 +342,6 @@ public:
|
||||
/** Returns the bullet vehicle which represents this kart. */
|
||||
virtual btKart *getVehicle() const {return m_vehicle; }
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns the upright constraint for this kart. */
|
||||
virtual btUprightConstraint *getUprightConstraint() const
|
||||
{return m_uprightConstraint;}
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns the speed of the kart in meters/second. */
|
||||
virtual float getSpeed() const {return m_speed; }
|
||||
// ------------------------------------------------------------------------
|
||||
|
@ -72,9 +72,8 @@ KartProperties::KartProperties(const std::string &filename)
|
||||
m_wheel_radius = m_chassis_linear_damping = m_max_suspension_force =
|
||||
m_chassis_angular_damping = m_suspension_rest =
|
||||
m_max_speed_reverse_ratio = m_rescue_vert_offset =
|
||||
m_upright_tolerance = m_collision_terrain_impulse =
|
||||
m_collision_impulse = m_restitution = m_collision_impulse_time =
|
||||
m_upright_max_force = m_suspension_travel_cm =
|
||||
m_collision_terrain_impulse = m_collision_impulse = m_restitution =
|
||||
m_collision_impulse_time = m_suspension_travel_cm =
|
||||
m_track_connection_accel = m_rubber_band_max_length =
|
||||
m_rubber_band_force = m_rubber_band_duration =
|
||||
m_rubber_band_speed_increase = m_rubber_band_fade_out_time =
|
||||
@ -367,12 +366,6 @@ void KartProperties::getAllData(const XMLNode * root)
|
||||
&m_track_connection_accel );
|
||||
}
|
||||
|
||||
if(const XMLNode *upright_node = root->getNode("upright"))
|
||||
{
|
||||
upright_node->get("tolerance", &m_upright_tolerance);
|
||||
upright_node->get("max-force", &m_upright_max_force);
|
||||
}
|
||||
|
||||
if(const XMLNode *collision_node = root->getNode("collision"))
|
||||
{
|
||||
collision_node->get("impulse", &m_collision_impulse );
|
||||
@ -673,8 +666,6 @@ void KartProperties::checkAllSet(const std::string &filename)
|
||||
CHECK_NEG(m_bevel_factor.getX(), "collision bevel-factor" );
|
||||
CHECK_NEG(m_bevel_factor.getY(), "collision bevel-factor" );
|
||||
CHECK_NEG(m_bevel_factor.getZ(), "collision bevel-factor" );
|
||||
CHECK_NEG(m_upright_tolerance, "upright tolerance" );
|
||||
CHECK_NEG(m_upright_max_force, "upright max-force" );
|
||||
CHECK_NEG(m_rubber_band_max_length, "plunger band-max-length" );
|
||||
CHECK_NEG(m_rubber_band_force, "plunger band-force" );
|
||||
CHECK_NEG(m_rubber_band_duration, "plunger band-duration" );
|
||||
|
@ -328,9 +328,6 @@ private:
|
||||
/** The restitution factor to be used in collsions for this kart. */
|
||||
float m_restitution;
|
||||
|
||||
float m_upright_tolerance;
|
||||
float m_upright_max_force;
|
||||
|
||||
/** How far behind a kart slipstreaming is effective. */
|
||||
float m_slipstream_length;
|
||||
/** How wide the slipstream area is at the end. */
|
||||
@ -699,15 +696,6 @@ public:
|
||||
float getExplosionInvulnerabilityTime() const
|
||||
{ return m_explosion_invulnerability_time; }
|
||||
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns how much a kart can roll/pitch before the upright constraint
|
||||
* counteracts. */
|
||||
float getUprightTolerance () const {return m_upright_tolerance; }
|
||||
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns the maximum value of the upright counteracting force. */
|
||||
float getUprightMaxForce () const {return m_upright_max_force; }
|
||||
|
||||
// ------------------------------------------------------------------------
|
||||
/** Returns the maximum length of a rubber band before it breaks. */
|
||||
float getRubberBandMaxLength () const {return m_rubber_band_max_length;}
|
||||
|
@ -1,176 +0,0 @@
|
||||
/*
|
||||
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (C) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the
|
||||
use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim
|
||||
that you wrote the original software. If you use this software in a
|
||||
product, an acknowledgment in the product documentation would be
|
||||
appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be
|
||||
misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
|
||||
*/
|
||||
|
||||
#include "physics/btUprightConstraint.hpp"
|
||||
|
||||
#include <new>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
|
||||
#include "karts/kart.hpp"
|
||||
|
||||
//!
|
||||
//!
|
||||
//!
|
||||
|
||||
void btUprightConstraint::solveAngularLimit(
|
||||
btUprightConstraintLimit *limit,
|
||||
btScalar timeStep, btScalar jacDiagABInv,
|
||||
btRigidBody * body0 )
|
||||
{
|
||||
|
||||
// Work out if limit is violated
|
||||
if(limit->m_angle>=m_loLimit && limit->m_angle<=m_hiLimit) return;
|
||||
|
||||
limit->m_currentLimitError = (limit->m_angle<m_loLimit)
|
||||
? limit->m_angle - m_loLimit
|
||||
: limit->m_angle - m_hiLimit;
|
||||
|
||||
btScalar targetVelocity = -m_ERP*limit->m_currentLimitError
|
||||
/ (3.1415f/8.0f*timeStep);
|
||||
btScalar maxMotorForce = m_maxLimitForce;
|
||||
|
||||
maxMotorForce *= timeStep;
|
||||
|
||||
// current velocity difference
|
||||
btVector3 angularVelocity = body0->getAngularVelocity();
|
||||
btScalar axisAngularVelocity = limit->m_axis.dot( angularVelocity );
|
||||
|
||||
// correction velocity
|
||||
btScalar motorVelocity = m_limitSoftness*(targetVelocity
|
||||
- m_damping*axisAngularVelocity);
|
||||
|
||||
// correction impulse
|
||||
btScalar unclippedMotorImpulse = (1+m_bounce)*motorVelocity*jacDiagABInv;
|
||||
|
||||
// clip correction impulse
|
||||
btScalar clippedMotorImpulse = unclippedMotorImpulse;
|
||||
|
||||
//todo: should clip against accumulated impulse
|
||||
|
||||
if (unclippedMotorImpulse>0.0f)
|
||||
{
|
||||
clippedMotorImpulse = unclippedMotorImpulse > maxMotorForce
|
||||
? maxMotorForce : unclippedMotorImpulse;
|
||||
}
|
||||
else
|
||||
{
|
||||
clippedMotorImpulse = unclippedMotorImpulse < -maxMotorForce
|
||||
? -maxMotorForce : unclippedMotorImpulse;
|
||||
}
|
||||
|
||||
// sort with accumulated impulses
|
||||
btScalar lo = btScalar(-1e30);
|
||||
btScalar hi = btScalar(1e30);
|
||||
|
||||
btScalar oldaccumImpulse = limit->m_accumulatedImpulse;
|
||||
|
||||
btScalar sum = oldaccumImpulse + clippedMotorImpulse;
|
||||
|
||||
limit->m_accumulatedImpulse = sum > hi ? btScalar(0.)
|
||||
: sum < lo ? btScalar(0.) : sum;
|
||||
|
||||
clippedMotorImpulse = limit->m_accumulatedImpulse - oldaccumImpulse;
|
||||
|
||||
btVector3 motorImp = clippedMotorImpulse * limit->m_axis;
|
||||
body0->applyTorqueImpulse(motorImp);
|
||||
} // solveAngularLimit
|
||||
|
||||
//!
|
||||
//!
|
||||
//!
|
||||
|
||||
btUprightConstraint::btUprightConstraint(const Kart* kart,
|
||||
const btTransform& frameInA)
|
||||
: btTypedConstraint(D6_CONSTRAINT_TYPE, *(kart->getBody()))
|
||||
, m_frameInA(frameInA)
|
||||
|
||||
{
|
||||
m_kart = kart;
|
||||
m_ERP = 1.0f;
|
||||
m_bounce = 0.0f;
|
||||
m_damping = 1.0f;
|
||||
m_limitSoftness = 1.0f;
|
||||
m_maxLimitForce = 3000.0f;
|
||||
m_disable_time = 0.0f;
|
||||
m_limit[0].m_accumulatedImpulse = 0.0f;
|
||||
m_limit[1].m_accumulatedImpulse = 0.0f;
|
||||
m_limit[ 0 ].m_axis = btVector3( 1, 0, 0 );
|
||||
m_limit[ 1 ].m_axis = btVector3( 0, 0, 1 );
|
||||
setLimit( SIMD_PI * 0.4f );
|
||||
} // btUprightConstraint
|
||||
|
||||
//!
|
||||
//!
|
||||
//!
|
||||
|
||||
void btUprightConstraint::buildJacobian()
|
||||
{
|
||||
m_limit[ 0 ].m_angle = m_kart->getPitch();
|
||||
m_limit[ 1 ].m_angle = -m_kart->getRoll();
|
||||
for ( int i = 0; i < 2; i++ )
|
||||
{
|
||||
new (&m_jacAng[ i ]) btJacobianEntry( m_limit[ i ].m_axis,
|
||||
m_rbA.getCenterOfMassTransform().getBasis().transpose(),
|
||||
m_rbB.getCenterOfMassTransform().getBasis().transpose(),
|
||||
m_rbA.getInvInertiaDiagLocal(),
|
||||
m_rbB.getInvInertiaDiagLocal());
|
||||
}
|
||||
} // buildJacobian
|
||||
|
||||
//!
|
||||
//!
|
||||
//!
|
||||
|
||||
void btUprightConstraint::solveConstraintObsolete(btRigidBody& /*bodyA*/,btRigidBody& /*bodyB*/,btScalar timeStep)
|
||||
{
|
||||
m_timeStep = timeStep;
|
||||
|
||||
// Update disable time and return if constraint is still disabled
|
||||
if(m_disable_time>0.0f)
|
||||
{
|
||||
m_disable_time -= timeStep;
|
||||
if(m_disable_time>0.0f) return;
|
||||
}
|
||||
|
||||
solveAngularLimit( &m_limit[ 0 ], m_timeStep, btScalar(1.) / m_jacAng[ 0 ].getDiagonal(), &m_rbA );
|
||||
solveAngularLimit( &m_limit[ 1 ], m_timeStep, btScalar(1.) / m_jacAng[ 1 ].getDiagonal(), &m_rbA );
|
||||
} // solveConstraint
|
||||
|
||||
void btUprightConstraint::getInfo1(btConstraintInfo1* info) {
|
||||
info->m_numConstraintRows = 0;
|
||||
info->nub = 0;
|
||||
}
|
||||
|
||||
void btUprightConstraint::getInfo2(btConstraintInfo2* info) {
|
||||
}
|
||||
|
||||
btScalar btUprightConstraint::getParam(int num, int axis) const
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
void btUprightConstraint::setParam(int num, btScalar value, int axis)
|
||||
{
|
||||
}
|
@ -1,122 +0,0 @@
|
||||
/*
|
||||
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (C) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the
|
||||
use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim
|
||||
that you wrote the original software. If you use this software in a
|
||||
product, an acknowledgment in the product documentation would be
|
||||
appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be
|
||||
misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef HEADER_UPRIGHT_CONSTRAINT_HPP
|
||||
#define HEADER_UPRIGHT_CONSTRAINT_HPP
|
||||
|
||||
#include "LinearMath/btVector3.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btJacobianEntry.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
|
||||
class btRigidBody;
|
||||
class Kart;
|
||||
|
||||
/**
|
||||
* \ingroup physics
|
||||
*/
|
||||
class btUprightConstraint : public btTypedConstraint
|
||||
{
|
||||
private:
|
||||
class btUprightConstraintLimit
|
||||
{
|
||||
public:
|
||||
btVector3 m_axis;
|
||||
btScalar m_angle;
|
||||
btScalar m_accumulatedImpulse;
|
||||
btScalar m_currentLimitError;
|
||||
};
|
||||
|
||||
//! relative_frames
|
||||
|
||||
//!@{
|
||||
btTransform m_frameInA;//!< the constraint space w.r.t body A
|
||||
//!@}
|
||||
|
||||
//! Jacobians
|
||||
//!@{
|
||||
btJacobianEntry m_jacAng[ 2 ];//!< angular constraint
|
||||
//!@}
|
||||
|
||||
const Kart *m_kart;
|
||||
protected:
|
||||
|
||||
//! temporal variables
|
||||
//!@{
|
||||
btScalar m_timeStep;
|
||||
btScalar m_ERP;
|
||||
btScalar m_bounce;
|
||||
btScalar m_damping;
|
||||
btScalar m_maxLimitForce;
|
||||
btScalar m_limitSoftness;
|
||||
btScalar m_hiLimit;
|
||||
btScalar m_loLimit;
|
||||
btScalar m_disable_time;
|
||||
|
||||
btUprightConstraintLimit m_limit[ 2 ];
|
||||
|
||||
//!@}
|
||||
|
||||
btUprightConstraint& operator=(btUprightConstraint& other)
|
||||
{
|
||||
btAssert(0);
|
||||
(void) other;
|
||||
return *this;
|
||||
}
|
||||
|
||||
void buildAngularJacobian(btJacobianEntry & jacAngular,
|
||||
const btVector3 & jointAxisW);
|
||||
|
||||
void solveAngularLimit(btUprightConstraintLimit *limit,
|
||||
btScalar timeStep, btScalar jacDiagABInv,
|
||||
btRigidBody * body0 );
|
||||
|
||||
public:
|
||||
|
||||
btUprightConstraint(const Kart* kart, const btTransform& frameInA);
|
||||
|
||||
// -PI,+PI is the full range
|
||||
// 0,0 is no rotation around x or z
|
||||
// -PI*0.2,+PI*0.2 is a nice bit of tilt
|
||||
void setLimit( btScalar range ) { m_loLimit = -range;
|
||||
m_hiLimit = +range; }
|
||||
// Error correction scaling
|
||||
// 0 - 1
|
||||
void setErp( btScalar erp ) { m_ERP = erp; }
|
||||
void setBounce( btScalar bounce ) { m_bounce = bounce; }
|
||||
void setMaxLimitForce( btScalar force ) { m_maxLimitForce = force; }
|
||||
void setLimitSoftness( btScalar softness ) { m_limitSoftness = softness; }
|
||||
void setDamping( btScalar damping ) { m_damping = damping; }
|
||||
void setDisableTime( btScalar t ) { m_disable_time = t; }
|
||||
virtual void buildJacobian();
|
||||
virtual void solveConstraintObsolete(btRigidBody& /*bodyA*/,
|
||||
btRigidBody& /*bodyB*/, btScalar
|
||||
timeStep);
|
||||
virtual void getInfo1 (btConstraintInfo1* info);
|
||||
virtual void getInfo2 (btConstraintInfo2* info);
|
||||
virtual void setParam(int num, btScalar value, int axis = -1);
|
||||
virtual btScalar getParam(int num, int axis) const;
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif //UPRIGHT_CONSTRAINT_H
|
||||
|
@ -33,7 +33,6 @@
|
||||
#include "modes/world.hpp"
|
||||
#include "karts/explosion_animation.hpp"
|
||||
#include "physics/btKart.hpp"
|
||||
#include "physics/btUprightConstraint.hpp"
|
||||
#include "physics/irr_debug_drawer.hpp"
|
||||
#include "physics/physical_object.hpp"
|
||||
#include "physics/stk_dynamics_world.hpp"
|
||||
@ -85,8 +84,8 @@ Physics::~Physics()
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
/** Adds a kart to the physics engine.
|
||||
* This adds the rigid body, the vehicle, and the upright constraint, but only
|
||||
* if the kart is not already in the physics world.
|
||||
* This adds the rigid body and the vehicle but only if the kart is not
|
||||
* already in the physics world.
|
||||
* \param kart The kart to add.
|
||||
* \param vehicle The raycast vehicle object.
|
||||
*/
|
||||
@ -101,7 +100,6 @@ void Physics::addKart(const AbstractKart *kart)
|
||||
}
|
||||
m_dynamics_world->addRigidBody(kart->getBody());
|
||||
m_dynamics_world->addVehicle(kart->getVehicle());
|
||||
m_dynamics_world->addConstraint(kart->getUprightConstraint());
|
||||
} // addKart
|
||||
|
||||
//-----------------------------------------------------------------------------
|
||||
@ -129,7 +127,6 @@ void Physics::removeKart(const AbstractKart *kart)
|
||||
{
|
||||
m_dynamics_world->removeRigidBody(kart->getBody());
|
||||
m_dynamics_world->removeVehicle(kart->getVehicle());
|
||||
m_dynamics_world->removeConstraint(kart->getUprightConstraint());
|
||||
}
|
||||
} // removeKart
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user