#include <btBulletDynamicsCommon.h>
Go to the source code of this file.
Functions | |
void | deleteConstraint (btTypedConstraint *constraint) |
void | enableAngularMotor (btHingeConstraint *hinge, bool enableMotor, double targetVelocity, double maxMotorImpulse) |
void | enableMotor (btHingeConstraint *hinge, bool enableMotor) |
bool | getAngularOnly (btHingeConstraint *hinge) |
double | getDampingDirAng (btSliderConstraint *slider) |
double | getDampingDirLin (btSliderConstraint *slider) |
double | getDampingLimAng (btSliderConstraint *slider) |
double | getDampingLimLin (btSliderConstraint *slider) |
double | getDampingOrthoAng (btSliderConstraint *slider) |
double | getDampingOrthoLin (btSliderConstraint *slider) |
bool | getEnableMotor (btHingeConstraint *hinge) |
double | getHingeAngle (btHingeConstraint *hinge) |
double | getLinearPos (btSliderConstraint *slider) |
double | getLowerAngLimit (btSliderConstraint *slider) |
double | getLowerLimit (btHingeConstraint *hinge) |
double | getLowerLinLimit (btSliderConstraint *slider) |
double | getMaxAngMotorForce (btSliderConstraint *slider) |
double | getMaxLinMotorForce (btSliderConstraint *slider) |
double | getMaxMotorImpulse (btHingeConstraint *hinge) |
double | getMotorTargetVelocity (btHingeConstraint *hinge) |
bool | getPoweredAngMotor (btSliderConstraint *slider) |
bool | getPoweredLinMotor (btSliderConstraint *slider) |
double | getRestitutionDirAng (btSliderConstraint *slider) |
double | getRestitutionDirLin (btSliderConstraint *slider) |
double | getRestitutionLimAng (btSliderConstraint *slider) |
double | getRestitutionLimLin (btSliderConstraint *slider) |
double | getRestitutionOrthoAng (btSliderConstraint *slider) |
double | getRestitutionOrthoLin (btSliderConstraint *slider) |
double | getSoftnessDirAng (btSliderConstraint *slider) |
double | getSoftnessDirLin (btSliderConstraint *slider) |
double | getSoftnessLimAng (btSliderConstraint *slider) |
double | getSoftnessLimLin (btSliderConstraint *slider) |
double | getSoftnessOrthoAng (btSliderConstraint *slider) |
double | getSoftnessOrthoLin (btSliderConstraint *slider) |
double | getTargetAngMotorVelocity (btSliderConstraint *slider) |
double | getTargetLinMotorVelocity (btSliderConstraint *slider) |
double | getUpperAngLimit (btSliderConstraint *slider) |
double | getUpperLimit (btHingeConstraint *hinge) |
double | getUpperLinLimit (btSliderConstraint *slider) |
bool | isHingeConstraint (const btTypedConstraint *ptr) |
bool | isPoint2PointConstraint (const btTypedConstraint *ptr) |
bool | isSliderConstraint (const btTypedConstraint *ptr) |
btTypedConstraint * | newHingeConstraint (btRigidBody *rbA, btRigidBody *rbB, const double *frameInA, const double *frameInB) |
btTypedConstraint * | newPoint2PointConstraint (btRigidBody *rbA, btRigidBody *rbB, const double *pivotInA, const double *pivotInB) |
btTypedConstraint * | newSliderConstraint (btRigidBody *rbA, btRigidBody *rbB, const double *frameInA, const double *frameInB) |
void | setAngularOnly (btHingeConstraint *hinge, bool angularOnly) |
void | setDampingDirAng (btSliderConstraint *slider, double dampingDirAng) |
void | setDampingDirLin (btSliderConstraint *slider, double dampingDirLin) |
void | setDampingLimAng (btSliderConstraint *slider, double dampingLimAng) |
void | setDampingLimLin (btSliderConstraint *slider, double dampingLimLin) |
void | setDampingOrthoAng (btSliderConstraint *slider, double dampingOrthoAng) |
void | setDampingOrthoLin (btSliderConstraint *slider, double dampingOrthoLin) |
void | setLimit (btHingeConstraint *hinge, double low, double high) |
void | setLimitComplex (btHingeConstraint *hinge, double low, double high, double softness, double biasFactor, double relaxationFactor) |
void | setLowerAngLimit (btSliderConstraint *slider, double lowerLimit) |
void | setLowerLinLimit (btSliderConstraint *slider, double lowerLimit) |
void | setMaxAngMotorForce (btSliderConstraint *slider, double maxAngMotorForce) |
void | setMaxLinMotorForce (btSliderConstraint *slider, double maxLinMotorForce) |
void | setMaxMotorImpulse (btHingeConstraint *hinge, double maxMotorImpulse) |
void | setMotorTarget (btHingeConstraint *hinge, double targetAngle, double dt) |
void | setPoweredAngMotor (btSliderConstraint *slider, bool onOff) |
void | setPoweredLinMotor (btSliderConstraint *slider, bool onOff) |
void | setRestitutionDirAng (btSliderConstraint *slider, double restitutionDirAng) |
void | setRestitutionDirLin (btSliderConstraint *slider, double restitutionDirLin) |
void | setRestitutionLimAng (btSliderConstraint *slider, double restitutionLimAng) |
void | setRestitutionLimLin (btSliderConstraint *slider, double restitutionLimLin) |
void | setRestitutionOrthoAng (btSliderConstraint *slider, double restitutionOrthoAng) |
void | setRestitutionOrthoLin (btSliderConstraint *slider, double restitutionOrthoLin) |
void | setSoftnessDirAng (btSliderConstraint *slider, double softnessDirAng) |
void | setSoftnessDirLin (btSliderConstraint *slider, double softnessDirLin) |
void | setSoftnessLimAng (btSliderConstraint *slider, double softnessLimAng) |
void | setSoftnessLimLin (btSliderConstraint *slider, double softnessLimLin) |
void | setSoftnessOrthoAng (btSliderConstraint *slider, double softnessOrthoAng) |
void | setSoftnessOrthoLin (btSliderConstraint *slider, double softnessOrthoLin) |
void | setTargetAngMotorVelocity (btSliderConstraint *slider, double targetAngMotorVelocity) |
void | setTargetLinMotorVelocity (btSliderConstraint *slider, double targetLinMotorVelocity) |
void | setUpperAngLimit (btSliderConstraint *slider, double lowerLimit) |
void | setUpperLinLimit (btSliderConstraint *slider, double lowerLimit) |
Variables | |
double | bulletWorldScalingFactor |
void deleteConstraint | ( | btTypedConstraint * | constraint | ) |
Definition at line 38 of file constraints.cpp.
void enableAngularMotor | ( | btHingeConstraint * | hinge, |
bool | enableMotor, | ||
double | targetVelocity, | ||
double | maxMotorImpulse | ||
) |
Definition at line 100 of file constraints.cpp.
void enableMotor | ( | btHingeConstraint * | hinge, |
bool | enableMotor | ||
) |
Definition at line 106 of file constraints.cpp.
bool getAngularOnly | ( | btHingeConstraint * | hinge | ) |
Definition at line 95 of file constraints.cpp.
double getDampingDirAng | ( | btSliderConstraint * | slider | ) |
Definition at line 252 of file constraints.cpp.
double getDampingDirLin | ( | btSliderConstraint * | slider | ) |
Definition at line 237 of file constraints.cpp.
double getDampingLimAng | ( | btSliderConstraint * | slider | ) |
Definition at line 282 of file constraints.cpp.
double getDampingLimLin | ( | btSliderConstraint * | slider | ) |
Definition at line 267 of file constraints.cpp.
double getDampingOrthoAng | ( | btSliderConstraint * | slider | ) |
Definition at line 312 of file constraints.cpp.
double getDampingOrthoLin | ( | btSliderConstraint * | slider | ) |
Definition at line 297 of file constraints.cpp.
bool getEnableMotor | ( | btHingeConstraint * | hinge | ) |
Definition at line 111 of file constraints.cpp.
double getHingeAngle | ( | btHingeConstraint * | hinge | ) |
Definition at line 148 of file constraints.cpp.
double getLinearPos | ( | btSliderConstraint * | slider | ) |
Definition at line 467 of file constraints.cpp.
double getLowerAngLimit | ( | btSliderConstraint * | slider | ) |
Definition at line 207 of file constraints.cpp.
double getLowerLimit | ( | btHingeConstraint * | hinge | ) |
Definition at line 153 of file constraints.cpp.
double getLowerLinLimit | ( | btSliderConstraint * | slider | ) |
Definition at line 187 of file constraints.cpp.
double getMaxAngMotorForce | ( | btSliderConstraint * | slider | ) |
Definition at line 462 of file constraints.cpp.
double getMaxLinMotorForce | ( | btSliderConstraint * | slider | ) |
Definition at line 432 of file constraints.cpp.
double getMaxMotorImpulse | ( | btHingeConstraint * | hinge | ) |
Definition at line 121 of file constraints.cpp.
double getMotorTargetVelocity | ( | btHingeConstraint * | hinge | ) |
Definition at line 126 of file constraints.cpp.
bool getPoweredAngMotor | ( | btSliderConstraint * | slider | ) |
Definition at line 442 of file constraints.cpp.
bool getPoweredLinMotor | ( | btSliderConstraint * | slider | ) |
Definition at line 412 of file constraints.cpp.
double getRestitutionDirAng | ( | btSliderConstraint * | slider | ) |
Definition at line 247 of file constraints.cpp.
double getRestitutionDirLin | ( | btSliderConstraint * | slider | ) |
Definition at line 232 of file constraints.cpp.
double getRestitutionLimAng | ( | btSliderConstraint * | slider | ) |
Definition at line 277 of file constraints.cpp.
double getRestitutionLimLin | ( | btSliderConstraint * | slider | ) |
Definition at line 262 of file constraints.cpp.
double getRestitutionOrthoAng | ( | btSliderConstraint * | slider | ) |
Definition at line 307 of file constraints.cpp.
double getRestitutionOrthoLin | ( | btSliderConstraint * | slider | ) |
Definition at line 292 of file constraints.cpp.
double getSoftnessDirAng | ( | btSliderConstraint * | slider | ) |
Definition at line 242 of file constraints.cpp.
double getSoftnessDirLin | ( | btSliderConstraint * | slider | ) |
Definition at line 227 of file constraints.cpp.
double getSoftnessLimAng | ( | btSliderConstraint * | slider | ) |
Definition at line 272 of file constraints.cpp.
double getSoftnessLimLin | ( | btSliderConstraint * | slider | ) |
Definition at line 257 of file constraints.cpp.
double getSoftnessOrthoAng | ( | btSliderConstraint * | slider | ) |
Definition at line 302 of file constraints.cpp.
double getSoftnessOrthoLin | ( | btSliderConstraint * | slider | ) |
Definition at line 287 of file constraints.cpp.
double getTargetAngMotorVelocity | ( | btSliderConstraint * | slider | ) |
Definition at line 452 of file constraints.cpp.
double getTargetLinMotorVelocity | ( | btSliderConstraint * | slider | ) |
Definition at line 422 of file constraints.cpp.
double getUpperAngLimit | ( | btSliderConstraint * | slider | ) |
Definition at line 217 of file constraints.cpp.
double getUpperLimit | ( | btHingeConstraint * | hinge | ) |
Definition at line 158 of file constraints.cpp.
double getUpperLinLimit | ( | btSliderConstraint * | slider | ) |
Definition at line 197 of file constraints.cpp.
bool isHingeConstraint | ( | const btTypedConstraint * | ptr | ) |
Definition at line 85 of file constraints.cpp.
bool isPoint2PointConstraint | ( | const btTypedConstraint * | ptr | ) |
Definition at line 59 of file constraints.cpp.
bool isSliderConstraint | ( | const btTypedConstraint * | ptr | ) |
Definition at line 182 of file constraints.cpp.
btTypedConstraint* newHingeConstraint | ( | btRigidBody * | rbA, |
btRigidBody * | rbB, | ||
const double * | frameInA, | ||
const double * | frameInB | ||
) |
HingeConstraint
Definition at line 67 of file constraints.cpp.
btTypedConstraint* newPoint2PointConstraint | ( | btRigidBody * | rbA, |
btRigidBody * | rbB, | ||
const double * | pivotInA, | ||
const double * | pivotInB | ||
) |
Point2PointConstraint
Definition at line 46 of file constraints.cpp.
btTypedConstraint* newSliderConstraint | ( | btRigidBody * | rbA, |
btRigidBody * | rbB, | ||
const double * | frameInA, | ||
const double * | frameInB | ||
) |
SliderConstraint
Definition at line 166 of file constraints.cpp.
void setAngularOnly | ( | btHingeConstraint * | hinge, |
bool | angularOnly | ||
) |
Definition at line 90 of file constraints.cpp.
void setDampingDirAng | ( | btSliderConstraint * | slider, |
double | dampingDirAng | ||
) |
Definition at line 342 of file constraints.cpp.
void setDampingDirLin | ( | btSliderConstraint * | slider, |
double | dampingDirLin | ||
) |
Definition at line 327 of file constraints.cpp.
void setDampingLimAng | ( | btSliderConstraint * | slider, |
double | dampingLimAng | ||
) |
Definition at line 372 of file constraints.cpp.
void setDampingLimLin | ( | btSliderConstraint * | slider, |
double | dampingLimLin | ||
) |
Definition at line 357 of file constraints.cpp.
void setDampingOrthoAng | ( | btSliderConstraint * | slider, |
double | dampingOrthoAng | ||
) |
Definition at line 402 of file constraints.cpp.
void setDampingOrthoLin | ( | btSliderConstraint * | slider, |
double | dampingOrthoLin | ||
) |
Definition at line 387 of file constraints.cpp.
void setLimit | ( | btHingeConstraint * | hinge, |
double | low, | ||
double | high | ||
) |
Definition at line 136 of file constraints.cpp.
void setLimitComplex | ( | btHingeConstraint * | hinge, |
double | low, | ||
double | high, | ||
double | softness, | ||
double | biasFactor, | ||
double | relaxationFactor | ||
) |
Definition at line 141 of file constraints.cpp.
void setLowerAngLimit | ( | btSliderConstraint * | slider, |
double | lowerLimit | ||
) |
Definition at line 212 of file constraints.cpp.
void setLowerLinLimit | ( | btSliderConstraint * | slider, |
double | lowerLimit | ||
) |
Definition at line 192 of file constraints.cpp.
void setMaxAngMotorForce | ( | btSliderConstraint * | slider, |
double | maxAngMotorForce | ||
) |
Definition at line 457 of file constraints.cpp.
void setMaxLinMotorForce | ( | btSliderConstraint * | slider, |
double | maxLinMotorForce | ||
) |
Definition at line 427 of file constraints.cpp.
void setMaxMotorImpulse | ( | btHingeConstraint * | hinge, |
double | maxMotorImpulse | ||
) |
Definition at line 116 of file constraints.cpp.
void setMotorTarget | ( | btHingeConstraint * | hinge, |
double | targetAngle, | ||
double | dt | ||
) |
Definition at line 131 of file constraints.cpp.
void setPoweredAngMotor | ( | btSliderConstraint * | slider, |
bool | onOff | ||
) |
Definition at line 437 of file constraints.cpp.
void setPoweredLinMotor | ( | btSliderConstraint * | slider, |
bool | onOff | ||
) |
Definition at line 407 of file constraints.cpp.
void setRestitutionDirAng | ( | btSliderConstraint * | slider, |
double | restitutionDirAng | ||
) |
Definition at line 337 of file constraints.cpp.
void setRestitutionDirLin | ( | btSliderConstraint * | slider, |
double | restitutionDirLin | ||
) |
Definition at line 322 of file constraints.cpp.
void setRestitutionLimAng | ( | btSliderConstraint * | slider, |
double | restitutionLimAng | ||
) |
Definition at line 367 of file constraints.cpp.
void setRestitutionLimLin | ( | btSliderConstraint * | slider, |
double | restitutionLimLin | ||
) |
Definition at line 352 of file constraints.cpp.
void setRestitutionOrthoAng | ( | btSliderConstraint * | slider, |
double | restitutionOrthoAng | ||
) |
Definition at line 397 of file constraints.cpp.
void setRestitutionOrthoLin | ( | btSliderConstraint * | slider, |
double | restitutionOrthoLin | ||
) |
Definition at line 382 of file constraints.cpp.
void setSoftnessDirAng | ( | btSliderConstraint * | slider, |
double | softnessDirAng | ||
) |
Definition at line 332 of file constraints.cpp.
void setSoftnessDirLin | ( | btSliderConstraint * | slider, |
double | softnessDirLin | ||
) |
Definition at line 317 of file constraints.cpp.
void setSoftnessLimAng | ( | btSliderConstraint * | slider, |
double | softnessLimAng | ||
) |
Definition at line 362 of file constraints.cpp.
void setSoftnessLimLin | ( | btSliderConstraint * | slider, |
double | softnessLimLin | ||
) |
Definition at line 347 of file constraints.cpp.
void setSoftnessOrthoAng | ( | btSliderConstraint * | slider, |
double | softnessOrthoAng | ||
) |
Definition at line 392 of file constraints.cpp.
void setSoftnessOrthoLin | ( | btSliderConstraint * | slider, |
double | softnessOrthoLin | ||
) |
Definition at line 377 of file constraints.cpp.
void setTargetAngMotorVelocity | ( | btSliderConstraint * | slider, |
double | targetAngMotorVelocity | ||
) |
Definition at line 447 of file constraints.cpp.
void setTargetLinMotorVelocity | ( | btSliderConstraint * | slider, |
double | targetLinMotorVelocity | ||
) |
Definition at line 417 of file constraints.cpp.
void setUpperAngLimit | ( | btSliderConstraint * | slider, |
double | lowerLimit | ||
) |
Definition at line 222 of file constraints.cpp.
void setUpperLinLimit | ( | btSliderConstraint * | slider, |
double | lowerLimit | ||
) |
Definition at line 202 of file constraints.cpp.
double bulletWorldScalingFactor |
Copyright (c) 2010, Lorenz Moesenlechner <moesenle@in.tum.de> All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the Intelligent Autonomous Systems Group/ Technische Universitaet Muenchen nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Definition at line 42 of file dynamics_world.cpp.