Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
@@ -33,7 +33,7 @@ class btRigidBody* MyMultiBodyCreator::allocateRigidBody(int urdfLinkIndex, btSc
|
||||
btRigidBody::btRigidBodyConstructionInfo rbci(mass, 0, colShape, localInertiaDiagonal);
|
||||
rbci.m_startWorldTransform = initialWorldTrans;
|
||||
m_rigidBody = new btRigidBody(rbci);
|
||||
m_rigidBody->forceActivationState(DISABLE_DEACTIVATION);
|
||||
|
||||
|
||||
return m_rigidBody;
|
||||
}
|
||||
|
||||
@@ -337,6 +337,12 @@ void ConvertURDF2BulletInternal(
|
||||
if (!createMultiBody)
|
||||
{
|
||||
btRigidBody* body = creation.allocateRigidBody(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrameInWorldSpace, compoundShape);
|
||||
bool canSleep = (flags & CUF_ENABLE_SLEEPING)!=0;
|
||||
if (!canSleep)
|
||||
{
|
||||
body->forceActivationState(DISABLE_DEACTIVATION);
|
||||
}
|
||||
|
||||
linkRigidBody = body;
|
||||
|
||||
world1->addRigidBody(body);
|
||||
@@ -359,7 +365,7 @@ void ConvertURDF2BulletInternal(
|
||||
if (cache.m_bulletMultiBody==0)
|
||||
{
|
||||
|
||||
bool canSleep = false;
|
||||
bool canSleep = (flags & CUF_ENABLE_SLEEPING)!=0;
|
||||
bool isFixedBase = (mass==0);//todo: figure out when base is fixed
|
||||
int totalNumJoints = cache.m_totalNumJoints1;
|
||||
cache.m_bulletMultiBody = creation.allocateMultiBody(urdfLinkIndex, totalNumJoints,mass, localInertiaDiagonal, isFixedBase, canSleep);
|
||||
|
||||
@@ -29,6 +29,7 @@ enum ConvertURDFFlags {
|
||||
CUF_GLOBAL_VELOCITIES_MB=256,
|
||||
CUF_MJCF_COLORS_FROM_FILE=512,
|
||||
CUF_ENABLE_CACHED_GRAPHICS_SHAPES = 1024,
|
||||
CUF_ENABLE_SLEEPING=2048,
|
||||
};
|
||||
|
||||
struct UrdfVisualShapeCache
|
||||
|
||||
@@ -2301,7 +2301,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
|
||||
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP = 0.2;//need to check if there are artifacts with frictionERP
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0;
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7;
|
||||
// m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 2;
|
||||
|
||||
@@ -684,6 +684,7 @@ enum eURDF_Flags
|
||||
URDF_GLOBAL_VELOCITIES_MB =256,
|
||||
MJCF_COLORS_FROM_FILE=512,
|
||||
URDF_ENABLE_CACHED_GRAPHICS_SHAPES=1024,
|
||||
URDF_ENABLE_SLEEPING=2048,
|
||||
};
|
||||
|
||||
enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes
|
||||
|
||||
25
examples/pybullet/examples/sleeping.py
Normal file
25
examples/pybullet/examples/sleeping.py
Normal file
@@ -0,0 +1,25 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
useMaximalCoordinates=False
|
||||
|
||||
flags = p.URDF_ENABLE_SLEEPING
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
p.loadURDF("plane100.urdf",flags=flags, useMaximalCoordinates=useMaximalCoordinates)
|
||||
#p.loadURDF("cube_small.urdf", [0,0,0.5], flags=flags)
|
||||
for k in range (5):
|
||||
for i in range (5):
|
||||
r2d2=p.loadURDF("r2d2.urdf",[k*2,i*2,1], useMaximalCoordinates=useMaximalCoordinates, flags=p.URDF_ENABLE_CACHED_GRAPHICS_SHAPES+flags)
|
||||
for j in range (p.getNumJoints(r2d2)):
|
||||
p.setJointMotorControl2(r2d2,j,p.VELOCITY_CONTROL,targetVelocity=0)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
timestep = 1./240.
|
||||
p.setTimeStep(timestep)
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
while p.isConnected():
|
||||
p.stepSimulation()
|
||||
time.sleep(timestep)
|
||||
@@ -9313,6 +9313,7 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "URDF_GLOBAL_VELOCITIES_MB", URDF_GLOBAL_VELOCITIES_MB);
|
||||
PyModule_AddIntConstant(m, "MJCF_COLORS_FROM_FILE", MJCF_COLORS_FROM_FILE);
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_CACHED_GRAPHICS_SHAPES", URDF_ENABLE_CACHED_GRAPHICS_SHAPES);
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_SLEEPING", URDF_ENABLE_SLEEPING);
|
||||
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION);
|
||||
|
||||
Reference in New Issue
Block a user