Merge pull request #1287 from erwincoumans/master

implement pybullet.createUserConstraint for maximalCoordinates, bump up pybullet version to 1.3.0
This commit is contained in:
erwincoumans
2017-08-30 12:14:58 -07:00
committed by GitHub
4 changed files with 145 additions and 32 deletions

View File

@@ -1214,7 +1214,7 @@ void OpenGLGuiHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWor
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i]; btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
sortedObjects.push_back(colObj); sortedObjects.push_back(colObj);
} }
//sortedObjects.quickSort(shapePointerCompareFunc); sortedObjects.quickSort(shapePointerCompareFunc);
for (int i=0;i<sortedObjects.size();i++) for (int i=0;i<sortedObjects.size();i++)
{ {
btCollisionObject* colObj = sortedObjects[i]; btCollisionObject* colObj = sortedObjects[i];

View File

@@ -390,7 +390,7 @@ void ConvertURDF2BulletInternal(
{ {
//b3Printf("Fixed joint\n"); //b3Printf("Fixed joint\n");
btGeneric6DofSpring2Constraint* dof6 = creation.createFixedJoint(urdfLinkIndex,*linkRigidBody, *parentRigidBody, offsetInB, offsetInA); btGeneric6DofSpring2Constraint* dof6 = creation.createFixedJoint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB);
if (enableConstraints) if (enableConstraints)
world1->addConstraint(dof6,true); world1->addConstraint(dof6,true);
@@ -417,7 +417,7 @@ void ConvertURDF2BulletInternal(
} else } else
{ {
btGeneric6DofSpring2Constraint* dof6 = creation.createRevoluteJoint(urdfLinkIndex,*linkRigidBody, *parentRigidBody, offsetInB, offsetInA,jointAxisInJointSpace,jointLowerLimit, jointUpperLimit); btGeneric6DofSpring2Constraint* dof6 = creation.createRevoluteJoint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB,jointAxisInJointSpace,jointLowerLimit, jointUpperLimit);
if (enableConstraints) if (enableConstraints)
world1->addConstraint(dof6,true); world1->addConstraint(dof6,true);
@@ -449,10 +449,8 @@ void ConvertURDF2BulletInternal(
} else } else
{ {
//btGeneric6DofSpring2Constraint* dof6 = creation.createPrismaticJoint(urdfLinkIndex,*linkRigidBody, *parentRigidBody, offsetInB, offsetInA,jointAxisInJointSpace,jointLowerLimit,jointUpperLimit);
btGeneric6DofSpring2Constraint* dof6 = creation.createPrismaticJoint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB,jointAxisInJointSpace,jointLowerLimit,jointUpperLimit); btGeneric6DofSpring2Constraint* dof6 = creation.createPrismaticJoint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB,jointAxisInJointSpace,jointLowerLimit,jointUpperLimit);
if (enableConstraints) if (enableConstraints)
world1->addConstraint(dof6,true); world1->addConstraint(dof6,true);

View File

@@ -6716,24 +6716,124 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{ {
if (parentBody->m_rigidBody) if (parentBody->m_rigidBody)
{ {
if (clientCmd.m_userConstraintArguments.m_jointType == eGearType)
btRigidBody* parentRb = 0;
if (clientCmd.m_userConstraintArguments.m_parentJointIndex==-1)
{ {
btRigidBody* childRb = childBody->m_rigidBody; parentRb = parentBody->m_rigidBody;
if (childRb) } else
{
if ((clientCmd.m_userConstraintArguments.m_parentJointIndex>=0) &&
(clientCmd.m_userConstraintArguments.m_parentJointIndex<parentBody->m_rigidBodyJoints.size()))
{
parentRb = &parentBody->m_rigidBodyJoints[clientCmd.m_userConstraintArguments.m_parentJointIndex]->getRigidBodyB();
}
}
btRigidBody* childRb = 0;
if (childBody->m_rigidBody)
{
if (clientCmd.m_userConstraintArguments.m_childJointIndex==-1)
{
childRb = childBody->m_rigidBody;
}
else
{
if ((clientCmd.m_userConstraintArguments.m_childJointIndex>=0)
&& (clientCmd.m_userConstraintArguments.m_childJointIndex<childBody->m_rigidBodyJoints.size()))
{
childRb = &childBody->m_rigidBodyJoints[clientCmd.m_userConstraintArguments.m_childJointIndex]->getRigidBodyB();
}
}
}
switch (clientCmd.m_userConstraintArguments.m_jointType)
{
case eRevoluteType:
{
break;
}
case ePrismaticType:
{
break;
}
case eFixedType:
{
if (childRb && parentRb && (childRb!=parentRb))
{
btVector3 pivotInParent(clientCmd.m_userConstraintArguments.m_parentFrame[0], clientCmd.m_userConstraintArguments.m_parentFrame[1], clientCmd.m_userConstraintArguments.m_parentFrame[2]);
btVector3 pivotInChild(clientCmd.m_userConstraintArguments.m_childFrame[0], clientCmd.m_userConstraintArguments.m_childFrame[1], clientCmd.m_userConstraintArguments.m_childFrame[2]);
btTransform offsetTrA,offsetTrB;
offsetTrA.setIdentity();
offsetTrA.setOrigin(pivotInParent);
offsetTrB.setIdentity();
offsetTrB.setOrigin(pivotInChild);
btGeneric6DofSpring2Constraint* dof6 = new btGeneric6DofSpring2Constraint(*parentRb, *childRb, offsetTrA, offsetTrB);
dof6->setLinearLowerLimit(btVector3(0,0,0));
dof6->setLinearUpperLimit(btVector3(0,0,0));
dof6->setAngularLowerLimit(btVector3(0,0,0));
dof6->setAngularUpperLimit(btVector3(0,0,0));
m_data->m_dynamicsWorld->addConstraint(dof6);
InteralUserConstraintData userConstraintData;
userConstraintData.m_rbConstraint = dof6;
int uid = m_data->m_userConstraintUIDGenerator++;
serverCmd.m_userConstraintResultArgs = clientCmd.m_userConstraintArguments;
serverCmd.m_userConstraintResultArgs.m_userConstraintUniqueId = uid;
serverCmd.m_userConstraintResultArgs.m_maxAppliedForce = defaultMaxForce;
userConstraintData.m_userConstraintData = serverCmd.m_userConstraintResultArgs;
m_data->m_userConstraints.insert(uid,userConstraintData);
serverCmd.m_type = CMD_USER_CONSTRAINT_COMPLETED;
}
break;
}
case ePoint2PointType:
{
if (childRb && parentRb && (childRb!=parentRb))
{
btVector3 pivotInParent(clientCmd.m_userConstraintArguments.m_parentFrame[0], clientCmd.m_userConstraintArguments.m_parentFrame[1], clientCmd.m_userConstraintArguments.m_parentFrame[2]);
btVector3 pivotInChild(clientCmd.m_userConstraintArguments.m_childFrame[0], clientCmd.m_userConstraintArguments.m_childFrame[1], clientCmd.m_userConstraintArguments.m_childFrame[2]);
btPoint2PointConstraint* p2p = new btPoint2PointConstraint(*parentRb,*childRb,pivotInParent,pivotInChild);
p2p->m_setting.m_impulseClamp = defaultMaxForce;
m_data->m_dynamicsWorld->addConstraint(p2p);
InteralUserConstraintData userConstraintData;
userConstraintData.m_rbConstraint = p2p;
int uid = m_data->m_userConstraintUIDGenerator++;
serverCmd.m_userConstraintResultArgs = clientCmd.m_userConstraintArguments;
serverCmd.m_userConstraintResultArgs.m_userConstraintUniqueId = uid;
serverCmd.m_userConstraintResultArgs.m_maxAppliedForce = defaultMaxForce;
userConstraintData.m_userConstraintData = serverCmd.m_userConstraintResultArgs;
m_data->m_userConstraints.insert(uid,userConstraintData);
serverCmd.m_type = CMD_USER_CONSTRAINT_COMPLETED;
}
break;
}
case eGearType:
{
if (childRb && parentRb && (childRb!=parentRb))
{ {
btVector3 axisA(clientCmd.m_userConstraintArguments.m_jointAxis[0], btVector3 axisA(clientCmd.m_userConstraintArguments.m_jointAxis[0],
clientCmd.m_userConstraintArguments.m_jointAxis[1], clientCmd.m_userConstraintArguments.m_jointAxis[1],
clientCmd.m_userConstraintArguments.m_jointAxis[2]); clientCmd.m_userConstraintArguments.m_jointAxis[2]);
//for now we use the same local axis for both objects //for now we use the same local axis for both objects
btVector3 axisB(clientCmd.m_userConstraintArguments.m_jointAxis[0], btVector3 axisB(clientCmd.m_userConstraintArguments.m_jointAxis[0],
clientCmd.m_userConstraintArguments.m_jointAxis[1], clientCmd.m_userConstraintArguments.m_jointAxis[1],
clientCmd.m_userConstraintArguments.m_jointAxis[2]); clientCmd.m_userConstraintArguments.m_jointAxis[2]);
btScalar ratio=1; btScalar ratio=1;
btGearConstraint* gear = new btGearConstraint(*parentBody->m_rigidBody,*childRb, axisA,axisB,ratio); btGearConstraint* gear = new btGearConstraint(*parentRb,*childRb, axisA,axisB,ratio);
m_data->m_dynamicsWorld->addConstraint(gear,true); m_data->m_dynamicsWorld->addConstraint(gear,true);
InteralUserConstraintData userConstraintData; InteralUserConstraintData userConstraintData;
userConstraintData.m_rbConstraint = gear; userConstraintData.m_rbConstraint = gear;
int uid = m_data->m_userConstraintUIDGenerator++; int uid = m_data->m_userConstraintUIDGenerator++;
@@ -6742,10 +6842,25 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
serverCmd.m_userConstraintResultArgs.m_maxAppliedForce = defaultMaxForce; serverCmd.m_userConstraintResultArgs.m_maxAppliedForce = defaultMaxForce;
userConstraintData.m_userConstraintData = serverCmd.m_userConstraintResultArgs; userConstraintData.m_userConstraintData = serverCmd.m_userConstraintResultArgs;
m_data->m_userConstraints.insert(uid,userConstraintData); m_data->m_userConstraints.insert(uid,userConstraintData);
serverCmd.m_type = CMD_USER_CONSTRAINT_COMPLETED; serverCmd.m_type = CMD_USER_CONSTRAINT_COMPLETED;
} }
break;
} }
case eSphericalType:
{
b3Warning("constraint type not handled yet");
break;
}
case ePlanarType:
{
b3Warning("constraint type not handled yet");
break;
}
default:
{
b3Warning("unknown constraint type");
}
};
} }
} }
} }

View File

@@ -440,7 +440,7 @@ print("-----")
setup( setup(
name = 'pybullet', name = 'pybullet',
version='1.2.7', version='1.3.0',
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator', description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3', url='https://github.com/bulletphysics/bullet3',