fix an issue with btMultiBodyConstraint, automatically 'finalizeMultiDof' to pre-allocate jacobian data
enable joint limit for slider/prismatic joint in btMultiBody version of URDF loader
This commit is contained in:
@@ -29,17 +29,17 @@
|
||||
class ImportUrdfSetup : public CommonMultiBodyBase
|
||||
{
|
||||
char m_fileName[1024];
|
||||
|
||||
|
||||
struct ImportUrdfInternalData* m_data;
|
||||
bool m_useMultiBody;
|
||||
|
||||
|
||||
public:
|
||||
ImportUrdfSetup(struct GUIHelperInterface* helper, int option, const char* fileName);
|
||||
virtual ~ImportUrdfSetup();
|
||||
|
||||
virtual void initPhysics();
|
||||
virtual void stepSimulation(float deltaTime);
|
||||
|
||||
|
||||
void setFileName(const char* urdfFileName);
|
||||
|
||||
virtual void resetCamera()
|
||||
@@ -64,7 +64,7 @@ struct ImportUrdfInternalData
|
||||
:m_numMotors(0)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
btScalar m_motorTargetVelocities[MAX_NUM_MOTORS];
|
||||
btMultiBodyJointMotor* m_jointMotors [MAX_NUM_MOTORS];
|
||||
int m_numMotors;
|
||||
@@ -93,10 +93,10 @@ ImportUrdfSetup::ImportUrdfSetup(struct GUIHelperInterface* helper, int option,
|
||||
gFileNameArray.clear();
|
||||
gFileNameArray.push_back("r2d2.urdf");
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//load additional urdf file names from file
|
||||
|
||||
|
||||
FILE* f = fopen("urdf_files.txt","r");
|
||||
if (f)
|
||||
{
|
||||
@@ -112,10 +112,10 @@ ImportUrdfSetup::ImportUrdfSetup(struct GUIHelperInterface* helper, int option,
|
||||
gFileNameArray.push_back(fileName);
|
||||
}
|
||||
} while (result==1);
|
||||
|
||||
|
||||
fclose(f);
|
||||
}
|
||||
|
||||
|
||||
int numFileNames = gFileNameArray.size();
|
||||
|
||||
if (count>=numFileNames)
|
||||
@@ -173,14 +173,14 @@ void ImportUrdfSetup::initPhysics()
|
||||
+btIDebugDraw::DBG_DrawAabb
|
||||
);//+btIDebugDraw::DBG_DrawConstraintLimits);
|
||||
|
||||
|
||||
|
||||
btVector3 gravity(0,0,0);
|
||||
gravity[upAxis]=-9.8;
|
||||
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//now print the tree using the new interface
|
||||
MyURDFImporter u2b(m_guiHelper);
|
||||
bool loadOk = u2b.loadURDF(m_fileName);
|
||||
@@ -188,17 +188,17 @@ void ImportUrdfSetup::initPhysics()
|
||||
if (loadOk)
|
||||
{
|
||||
u2b.printTree();
|
||||
|
||||
|
||||
btTransform identityTrans;
|
||||
identityTrans.setIdentity();
|
||||
|
||||
|
||||
|
||||
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
btMultiBody* mb = 0;
|
||||
|
||||
|
||||
|
||||
|
||||
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||
printf("urdf root link index = %d\n",rootLinkIndex);
|
||||
@@ -209,22 +209,22 @@ void ImportUrdfSetup::initPhysics()
|
||||
|
||||
if (m_useMultiBody)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//create motors for each joint
|
||||
|
||||
|
||||
for (int i=0;i<mb->getNumLinks();i++)
|
||||
{
|
||||
int mbLinkIndex = i;
|
||||
if (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute
|
||||
if (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute
|
||||
||mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::ePrismatic
|
||||
)
|
||||
{
|
||||
if (m_data->m_numMotors<MAX_NUM_MOTORS)
|
||||
{
|
||||
int urdfLinkIndex = creation.m_mb2urdfLink[mbLinkIndex];
|
||||
|
||||
|
||||
std::string jointName = u2b.getJointName(urdfLinkIndex);
|
||||
char motorName[1024];
|
||||
sprintf(motorName,"%s q'", jointName.c_str());
|
||||
@@ -241,15 +241,19 @@ void ImportUrdfSetup::initPhysics()
|
||||
m_data->m_numMotors++;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//the btMultiBody support is work-in-progress :-)
|
||||
|
||||
|
||||
|
||||
for (int i=0;i<m_dynamicsWorld->getNumMultiBodyConstraints();i++)
|
||||
{
|
||||
m_dynamicsWorld->getMultiBodyConstraint(i)->finalizeMultiDof();
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool createGround=true;
|
||||
if (createGround)
|
||||
@@ -284,7 +288,7 @@ void ImportUrdfSetup::stepSimulation(float deltaTime)
|
||||
{
|
||||
m_data->m_jointMotors[i]->setVelocityTarget(m_data->m_motorTargetVelocities[i]);
|
||||
}
|
||||
|
||||
|
||||
//the maximal coordinates/iterative MLCP solver requires a smallish timestep to converge
|
||||
m_dynamicsWorld->stepSimulation(deltaTime,10,1./240.);
|
||||
}
|
||||
|
||||
@@ -25,7 +25,7 @@ static btVector4 colors[4] =
|
||||
|
||||
static btVector3 selectColor2()
|
||||
{
|
||||
|
||||
|
||||
static int curColor = 0;
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
@@ -37,9 +37,9 @@ void printTree(const URDFImporterInterface& u2b, int linkIndex, int indentationL
|
||||
{
|
||||
btAlignedObjectArray<int> childIndices;
|
||||
u2b.getLinkChildIndices(linkIndex,childIndices);
|
||||
|
||||
|
||||
int numChildren = childIndices.size();
|
||||
|
||||
|
||||
indentationLevel+=2;
|
||||
int count = 0;
|
||||
for (int i=0;i<numChildren;i++)
|
||||
@@ -61,19 +61,19 @@ struct URDF2BulletCachedData
|
||||
m_currentMultiBodyLinkIndex(-1),
|
||||
m_bulletMultiBody(0)
|
||||
{
|
||||
|
||||
|
||||
}
|
||||
//these arrays will be initialized in the 'InitURDF2BulletCache'
|
||||
|
||||
|
||||
btAlignedObjectArray<int> m_urdfLinkParentIndices;
|
||||
btAlignedObjectArray<int> m_urdfLinkIndices2BulletLinkIndices;
|
||||
btAlignedObjectArray<class btRigidBody*> m_urdfLink2rigidBodies;
|
||||
btAlignedObjectArray<btTransform> m_urdfLinkLocalInertialFrames;
|
||||
|
||||
|
||||
int m_currentMultiBodyLinkIndex;
|
||||
|
||||
|
||||
class btMultiBody* m_bulletMultiBody;
|
||||
|
||||
|
||||
//this will be initialized in the constructor
|
||||
int m_totalNumJoints1;
|
||||
int getParentUrdfIndex(int linkIndex) const
|
||||
@@ -86,26 +86,26 @@ struct URDF2BulletCachedData
|
||||
return -2;
|
||||
return m_urdfLinkIndices2BulletLinkIndices[urdfIndex];
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void registerMultiBody( int urdfLinkIndex, class btMultiBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCompoundShape* compound, const btTransform& localInertialFrame)
|
||||
{
|
||||
m_urdfLinkLocalInertialFrames[urdfLinkIndex] = localInertialFrame;
|
||||
}
|
||||
|
||||
|
||||
class btRigidBody* getRigidBodyFromLink(int urdfLinkIndex)
|
||||
{
|
||||
return m_urdfLink2rigidBodies[urdfLinkIndex];
|
||||
}
|
||||
|
||||
|
||||
void registerRigidBody( int urdfLinkIndex, class btRigidBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCompoundShape* compound, const btTransform& localInertialFrame)
|
||||
{
|
||||
btAssert(m_urdfLink2rigidBodies[urdfLinkIndex]==0);
|
||||
|
||||
|
||||
m_urdfLink2rigidBodies[urdfLinkIndex] = body;
|
||||
m_urdfLinkLocalInertialFrames[urdfLinkIndex] = localInertialFrame;
|
||||
}
|
||||
|
||||
|
||||
};
|
||||
|
||||
void ComputeTotalNumberOfJoints(const URDFImporterInterface& u2b, URDF2BulletCachedData& cache, int linkIndex)
|
||||
@@ -129,7 +129,7 @@ void ComputeParentIndices(const URDFImporterInterface& u2b, URDF2BulletCachedDat
|
||||
{
|
||||
cache.m_urdfLinkParentIndices[urdfLinkIndex]=urdfParentIndex;
|
||||
cache.m_urdfLinkIndices2BulletLinkIndices[urdfLinkIndex]=cache.m_currentMultiBodyLinkIndex++;
|
||||
|
||||
|
||||
btAlignedObjectArray<int> childIndices;
|
||||
u2b.getLinkChildIndices(urdfLinkIndex,childIndices);
|
||||
for (int i=0;i<childIndices.size();i++)
|
||||
@@ -148,32 +148,32 @@ void InitURDF2BulletCache(const URDFImporterInterface& u2b, URDF2BulletCachedDat
|
||||
{
|
||||
ComputeTotalNumberOfJoints(u2b,cache,rootLinkIndex);
|
||||
int numTotalLinksIncludingBase = 1+cache.m_totalNumJoints1;
|
||||
|
||||
|
||||
cache.m_urdfLinkParentIndices.resize(numTotalLinksIncludingBase);
|
||||
cache.m_urdfLinkIndices2BulletLinkIndices.resize(numTotalLinksIncludingBase);
|
||||
cache.m_urdfLink2rigidBodies.resize(numTotalLinksIncludingBase);
|
||||
cache.m_urdfLinkLocalInertialFrames.resize(numTotalLinksIncludingBase);
|
||||
|
||||
|
||||
cache.m_currentMultiBodyLinkIndex = -1;//multi body base has 'link' index -1
|
||||
ComputeParentIndices(u2b,cache,rootLinkIndex,-2);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation, URDF2BulletCachedData& cache, int urdfLinkIndex, const btTransform& parentTransformInWorldSpace, btMultiBodyDynamicsWorld* world1,bool createMultiBody, const char* pathPrefix)
|
||||
{
|
||||
printf("start converting/extracting data from URDF interface\n");
|
||||
|
||||
|
||||
btTransform linkTransformInWorldSpace;
|
||||
linkTransformInWorldSpace.setIdentity();
|
||||
|
||||
|
||||
|
||||
int mbLinkIndex =cache.getMbIndexFromUrdfIndex(urdfLinkIndex);
|
||||
|
||||
int urdfParentIndex = cache.getParentUrdfIndex(urdfLinkIndex);
|
||||
int mbParentIndex = cache.getMbIndexFromUrdfIndex(urdfParentIndex);
|
||||
btRigidBody* parentRigidBody = 0;
|
||||
|
||||
|
||||
std::string name = u2b.getLinkName(urdfLinkIndex);
|
||||
printf("link name=%s urdf link index=%d\n",name.c_str(),urdfLinkIndex);
|
||||
printf("mb link index = %d\n",mbLinkIndex);
|
||||
@@ -192,19 +192,19 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
printf("mb parent index = %d\n",mbParentIndex);
|
||||
parentRigidBody = cache.getRigidBodyFromLink(urdfParentIndex);
|
||||
u2b.getMassAndInertia(urdfParentIndex, parentMass,parentLocalInertiaDiagonal,parentLocalInertialFrame);
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
btScalar mass = 0;
|
||||
btTransform localInertialFrame;
|
||||
localInertialFrame.setIdentity();
|
||||
btVector3 localInertiaDiagonal(0,0,0);
|
||||
u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
btTransform parent2joint;
|
||||
parent2joint.setIdentity();
|
||||
|
||||
@@ -212,23 +212,23 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
btVector3 jointAxisInJointSpace;
|
||||
btScalar jointLowerLimit;
|
||||
btScalar jointUpperLimit;
|
||||
|
||||
|
||||
|
||||
bool hasParentJoint = u2b.getJointInfo(urdfLinkIndex, parent2joint, jointAxisInJointSpace, jointType,jointLowerLimit,jointUpperLimit);
|
||||
|
||||
|
||||
|
||||
|
||||
linkTransformInWorldSpace =parentTransformInWorldSpace*parent2joint;
|
||||
|
||||
int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
|
||||
|
||||
|
||||
btCompoundShape* compoundShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
|
||||
|
||||
|
||||
if (compoundShape)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
btVector3 color = selectColor2();
|
||||
/*
|
||||
/*
|
||||
if (visual->material.get())
|
||||
{
|
||||
color.setValue(visual->material->color.r,visual->material->color.g,visual->material->color.b);//,visual->material->color.a);
|
||||
@@ -239,19 +239,19 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
//{
|
||||
// shape->calculateLocalInertia(mass, localInertiaDiagonal);
|
||||
//}
|
||||
|
||||
|
||||
btRigidBody* linkRigidBody = 0;
|
||||
btTransform inertialFrameInWorldSpace = linkTransformInWorldSpace*localInertialFrame;
|
||||
|
||||
|
||||
if (!createMultiBody)
|
||||
{
|
||||
btRigidBody* body = creation.allocateRigidBody(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrameInWorldSpace, compoundShape);
|
||||
linkRigidBody = body;
|
||||
|
||||
|
||||
world1->addRigidBody(body, bodyCollisionFilterGroup, bodyCollisionFilterMask);
|
||||
|
||||
|
||||
compoundShape->setUserIndex(graphicsIndex);
|
||||
|
||||
|
||||
creation.createRigidBodyGraphicsInstance(urdfLinkIndex, body, color, graphicsIndex);
|
||||
cache.registerRigidBody(urdfLinkIndex, body, inertialFrameInWorldSpace, mass, localInertiaDiagonal, compoundShape, localInertialFrame);
|
||||
} else
|
||||
@@ -263,19 +263,19 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
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, multiDof);
|
||||
|
||||
|
||||
cache.registerMultiBody(urdfLinkIndex, cache.m_bulletMultiBody, inertialFrameInWorldSpace, mass, localInertiaDiagonal, compoundShape, localInertialFrame);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
//create a joint if necessary
|
||||
if (hasParentJoint) {
|
||||
|
||||
|
||||
btTransform offsetInA,offsetInB;
|
||||
offsetInA = parentLocalInertialFrame.inverse()*parent2joint;
|
||||
offsetInB = localInertialFrame.inverse();
|
||||
|
||||
|
||||
bool disableParentCollision = true;
|
||||
switch (jointType)
|
||||
{
|
||||
@@ -284,32 +284,32 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
if (createMultiBody)
|
||||
{
|
||||
//todo: adjust the center of mass transform and pivot axis properly
|
||||
|
||||
|
||||
printf("Fixed joint (btMultiBody)\n");
|
||||
btQuaternion rot = offsetInA.inverse().getRotation();//parent2joint.inverse().getRotation();
|
||||
cache.m_bulletMultiBody->setupFixed(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex,
|
||||
rot*offsetInB.getRotation(), offsetInA.getOrigin(),-offsetInB.getOrigin(),disableParentCollision);
|
||||
creation.addLinkMapping(urdfLinkIndex,mbLinkIndex);
|
||||
|
||||
|
||||
|
||||
|
||||
} else
|
||||
{
|
||||
printf("Fixed joint\n");
|
||||
|
||||
|
||||
btMatrix3x3 rm(offsetInA.getBasis());
|
||||
btScalar y,p,r;
|
||||
rm.getEulerZYX(y,p,r);
|
||||
printf("y=%f,p=%f,r=%f\n", y,p,r);
|
||||
|
||||
|
||||
//we could also use btFixedConstraint but it has some issues
|
||||
btGeneric6DofSpring2Constraint* dof6 = creation.allocateGeneric6DofSpring2Constraint(urdfLinkIndex, *parentRigidBody, *linkRigidBody, offsetInA, offsetInB);
|
||||
|
||||
dof6->setLinearLowerLimit(btVector3(0,0,0));
|
||||
dof6->setLinearUpperLimit(btVector3(0,0,0));
|
||||
|
||||
|
||||
dof6->setAngularLowerLimit(btVector3(0,0,0));
|
||||
dof6->setAngularUpperLimit(btVector3(0,0,0));
|
||||
|
||||
|
||||
if (enableConstraints)
|
||||
world1->addConstraint(dof6,true);
|
||||
}
|
||||
@@ -320,14 +320,14 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
{
|
||||
if (createMultiBody)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
cache.m_bulletMultiBody->setupRevolute(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex,
|
||||
offsetInA.inverse().getRotation()*offsetInB.getRotation(), quatRotate(offsetInB.inverse().getRotation(),jointAxisInJointSpace), offsetInA.getOrigin(),//parent2joint.getOrigin(),
|
||||
-offsetInB.getOrigin(),
|
||||
disableParentCollision);
|
||||
creation.addLinkMapping(urdfLinkIndex,mbLinkIndex);
|
||||
|
||||
|
||||
} else
|
||||
{
|
||||
//only handle principle axis at the moment,
|
||||
@@ -340,10 +340,10 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
btGeneric6DofSpring2Constraint* dof6 = creation.allocateGeneric6DofSpring2Constraint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB,RO_ZYX);
|
||||
dof6->setLinearLowerLimit(btVector3(0,0,0));
|
||||
dof6->setLinearUpperLimit(btVector3(0,0,0));
|
||||
|
||||
|
||||
dof6->setAngularUpperLimit(btVector3(-1,0,0));
|
||||
dof6->setAngularLowerLimit(btVector3(1,0,0));
|
||||
|
||||
|
||||
if (enableConstraints)
|
||||
world1->addConstraint(dof6,true);
|
||||
break;
|
||||
@@ -353,10 +353,10 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
btGeneric6DofSpring2Constraint* dof6 = creation.allocateGeneric6DofSpring2Constraint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB,RO_XZY);
|
||||
dof6->setLinearLowerLimit(btVector3(0,0,0));
|
||||
dof6->setLinearUpperLimit(btVector3(0,0,0));
|
||||
|
||||
|
||||
dof6->setAngularUpperLimit(btVector3(0,-1,0));
|
||||
dof6->setAngularLowerLimit(btVector3(0,1,0));
|
||||
|
||||
|
||||
if (enableConstraints)
|
||||
world1->addConstraint(dof6,true);
|
||||
break;
|
||||
@@ -367,10 +367,10 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
btGeneric6DofSpring2Constraint* dof6 = creation.allocateGeneric6DofSpring2Constraint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB,RO_XYZ);
|
||||
dof6->setLinearLowerLimit(btVector3(0,0,0));
|
||||
dof6->setLinearUpperLimit(btVector3(0,0,0));
|
||||
|
||||
|
||||
dof6->setAngularUpperLimit(btVector3(0,0,-1));
|
||||
dof6->setAngularLowerLimit(btVector3(0,0,0));
|
||||
|
||||
|
||||
if (enableConstraints)
|
||||
world1->addConstraint(dof6,true);
|
||||
}
|
||||
@@ -383,17 +383,17 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
{
|
||||
if (createMultiBody)
|
||||
{
|
||||
|
||||
|
||||
cache.m_bulletMultiBody->setupPrismatic(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex,
|
||||
offsetInA.inverse().getRotation()*offsetInB.getRotation(), quatRotate(offsetInB.inverse().getRotation(),jointAxisInJointSpace), offsetInA.getOrigin(),//parent2joint.getOrigin(),
|
||||
-offsetInB.getOrigin(),
|
||||
disableParentCollision);
|
||||
|
||||
|
||||
creation.addLinkMapping(urdfLinkIndex,mbLinkIndex);
|
||||
btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(cache.m_bulletMultiBody,mbLinkIndex,jointLowerLimit, jointUpperLimit);
|
||||
//world1->addMultiBodyConstraint(con);
|
||||
printf("joint lower limit=%d, upper limit = %f\n", jointLowerLimit, jointUpperLimit);
|
||||
|
||||
btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(cache.m_bulletMultiBody,mbLinkIndex,jointLowerLimit, jointUpperLimit);
|
||||
world1->addMultiBodyConstraint(con);
|
||||
//printf("joint lower limit=%d, upper limit = %f\n", jointLowerLimit, jointUpperLimit);
|
||||
|
||||
} else
|
||||
{
|
||||
btGeneric6DofSpring2Constraint* dof6 = creation.allocateGeneric6DofSpring2Constraint(urdfLinkIndex,*parentRigidBody, *linkRigidBody, offsetInA, offsetInB);
|
||||
@@ -420,12 +420,12 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
dof6->setLinearUpperLimit(btVector3(0,0,jointUpperLimit));
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
dof6->setAngularLowerLimit(btVector3(0,0,0));
|
||||
dof6->setAngularUpperLimit(btVector3(0,0,0));
|
||||
if (enableConstraints)
|
||||
world1->addConstraint(dof6,true);
|
||||
|
||||
|
||||
printf("Prismatic\n");
|
||||
}
|
||||
break;
|
||||
@@ -436,41 +436,41 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
btAssert(0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
if (createMultiBody)
|
||||
{
|
||||
if (compoundShape->getNumChildShapes()>0)
|
||||
{
|
||||
btMultiBodyLinkCollider* col= creation.allocateMultiBodyLinkCollider(urdfLinkIndex, mbLinkIndex, cache.m_bulletMultiBody);
|
||||
|
||||
|
||||
compoundShape->setUserIndex(graphicsIndex);
|
||||
|
||||
|
||||
col->setCollisionShape(compoundShape);
|
||||
|
||||
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr = linkTransformInWorldSpace;
|
||||
//if we don't set the initial pose of the btCollisionObject, the simulator will do this
|
||||
//if we don't set the initial pose of the btCollisionObject, the simulator will do this
|
||||
//when syncing the btMultiBody link transforms to the btMultiBodyLinkCollider
|
||||
|
||||
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
|
||||
bool isDynamic = true;
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
|
||||
world1->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
|
||||
|
||||
|
||||
btVector3 color = selectColor2();//(0.0,0.0,0.5);
|
||||
|
||||
|
||||
creation.createCollisionObjectGraphicsInstance(urdfLinkIndex,col,color);
|
||||
|
||||
|
||||
btScalar friction = 0.5f;
|
||||
|
||||
|
||||
col->setFriction(friction);
|
||||
|
||||
|
||||
if (mbLinkIndex>=0) //???? double-check +/- 1
|
||||
{
|
||||
cache.m_bulletMultiBody->getLink(mbLinkIndex).m_collider=col;
|
||||
@@ -481,20 +481,20 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
btAlignedObjectArray<int> urdfChildIndices;
|
||||
u2b.getLinkChildIndices(urdfLinkIndex,urdfChildIndices);
|
||||
|
||||
|
||||
int numChildren = urdfChildIndices.size();
|
||||
|
||||
|
||||
for (int i=0;i<numChildren;i++)
|
||||
{
|
||||
int urdfChildLinkIndex = urdfChildIndices[i];
|
||||
|
||||
|
||||
ConvertURDF2BulletInternal(u2b,creation, cache,urdfChildLinkIndex,linkTransformInWorldSpace,world1,createMultiBody,pathPrefix);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void ConvertURDF2Bullet(const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation, const btTransform& rootTransformInWorldSpace, btMultiBodyDynamicsWorld* world1,bool createMultiBody, const char* pathPrefix)
|
||||
@@ -504,7 +504,7 @@ void ConvertURDF2Bullet(const URDFImporterInterface& u2b, MultiBodyCreationInter
|
||||
InitURDF2BulletCache(u2b,cache);
|
||||
int urdfLinkIndex = u2b.getRootLinkIndex();
|
||||
ConvertURDF2BulletInternal(u2b, creation, cache, urdfLinkIndex,rootTransformInWorldSpace,world1,createMultiBody,pathPrefix);
|
||||
|
||||
|
||||
if (world1 && cache.m_bulletMultiBody)
|
||||
{
|
||||
btMultiBody* mb = cache.m_bulletMultiBody;
|
||||
|
||||
@@ -48,7 +48,7 @@ typedef struct
|
||||
float m_frictionCoeff;
|
||||
} Body;
|
||||
|
||||
__kernel void
|
||||
__kernel void
|
||||
copyTransformsToVBOKernel( __global Body* gBodies, __global float4* posOrnColor, const int numNodes)
|
||||
{
|
||||
int nodeID = get_global_id(0);
|
||||
@@ -76,14 +76,14 @@ m_window(0)
|
||||
{
|
||||
m_instancingRenderer = 0;
|
||||
}
|
||||
|
||||
|
||||
m_window = helper->getAppInterface()->m_window;
|
||||
|
||||
m_data = new GpuRigidBodyDemoInternalData;
|
||||
}
|
||||
GpuRigidBodyDemo::~GpuRigidBodyDemo()
|
||||
{
|
||||
|
||||
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
@@ -97,9 +97,9 @@ static void PairKeyboardCallback(int key, int state)
|
||||
{
|
||||
if (key=='R' && state)
|
||||
{
|
||||
gReset = true;
|
||||
//gReset = true;
|
||||
}
|
||||
|
||||
|
||||
//b3DefaultKeyboardCallback(key,state);
|
||||
oldCallback(key,state);
|
||||
}
|
||||
@@ -122,13 +122,13 @@ void GpuRigidBodyDemo::initPhysics()
|
||||
|
||||
cl_program rbProg=0;
|
||||
m_data->m_copyTransformsToVBOKernel = b3OpenCLUtils::compileCLKernelFromString(m_clData->m_clContext,m_clData->m_clDevice,s_rigidBodyKernelString,"copyTransformsToVBOKernel",&errNum,rbProg);
|
||||
|
||||
|
||||
m_data->m_config.m_maxConvexBodies = b3Max(m_data->m_config.m_maxConvexBodies,gGpuArraySizeX*gGpuArraySizeY*gGpuArraySizeZ+10);
|
||||
m_data->m_config.m_maxConvexShapes = m_data->m_config.m_maxConvexBodies;
|
||||
int maxPairsPerBody = 16;
|
||||
m_data->m_config.m_maxBroadphasePairs = maxPairsPerBody*m_data->m_config.m_maxConvexBodies;
|
||||
m_data->m_config.m_maxContactCapacity = m_data->m_config.m_maxBroadphasePairs;
|
||||
|
||||
|
||||
|
||||
b3GpuNarrowPhase* np = new b3GpuNarrowPhase(m_clData->m_clContext,m_clData->m_clDevice,m_clData->m_clQueue,m_data->m_config);
|
||||
b3GpuBroadphaseInterface* bp =0;
|
||||
@@ -155,11 +155,11 @@ void GpuRigidBodyDemo::initPhysics()
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
m_guiHelper->getRenderInterface()->writeTransforms();
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -171,8 +171,8 @@ void GpuRigidBodyDemo::exitPhysics()
|
||||
delete m_data->m_rigidBodyPipeline;
|
||||
delete m_data->m_broadphaseDbvt;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
delete m_data->m_np;
|
||||
m_data->m_np = 0;
|
||||
delete m_data->m_bp;
|
||||
@@ -185,7 +185,7 @@ void GpuRigidBodyDemo::exitPhysics()
|
||||
void GpuRigidBodyDemo::renderScene()
|
||||
{
|
||||
m_guiHelper->getRenderInterface()->renderScene();
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -216,7 +216,7 @@ void GpuRigidBodyDemo::stepSimulation(float deltaTime)
|
||||
if (animate && numObjects)
|
||||
{
|
||||
B3_PROFILE("gl2cl");
|
||||
|
||||
|
||||
if (!m_data->m_instancePosOrnColor)
|
||||
{
|
||||
GLuint vbo = m_instancingRenderer->getInternalData()->m_vbo;
|
||||
@@ -234,11 +234,11 @@ void GpuRigidBodyDemo::stepSimulation(float deltaTime)
|
||||
assert(err==GL_NO_ERROR);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
{
|
||||
B3_PROFILE("stepSimulation");
|
||||
m_data->m_rigidBodyPipeline->stepSimulation(1./60.f);
|
||||
|
||||
|
||||
}
|
||||
|
||||
if (numObjects)
|
||||
@@ -247,7 +247,7 @@ void GpuRigidBodyDemo::stepSimulation(float deltaTime)
|
||||
{
|
||||
b3GpuNarrowPhaseInternalData* npData = m_data->m_np->getInternalData();
|
||||
npData->m_bodyBufferGPU->copyToHost(*npData->m_bodyBufferCPU);
|
||||
|
||||
|
||||
b3AlignedObjectArray<b3Vector4> vboCPU;
|
||||
m_data->m_instancePosOrnColor->copyToHost(vboCPU);
|
||||
|
||||
@@ -301,7 +301,7 @@ b3Vector3 GpuRigidBodyDemo::getRayTo(int x,int y)
|
||||
{
|
||||
if (!m_instancingRenderer)
|
||||
return b3MakeVector3(0,0,0);
|
||||
|
||||
|
||||
float top = 1.f;
|
||||
float bottom = -1.f;
|
||||
float nearPlane = 1.f;
|
||||
@@ -339,7 +339,7 @@ b3Vector3 GpuRigidBodyDemo::getRayTo(int x,int y)
|
||||
float height = m_instancingRenderer->getScreenHeight();
|
||||
|
||||
aspect = width / height;
|
||||
|
||||
|
||||
hor*=aspect;
|
||||
|
||||
|
||||
@@ -362,7 +362,7 @@ unsigned char* GpuRigidBodyDemo::loadImage(const char* fileName, int& width, int
|
||||
|
||||
bool GpuRigidBodyDemo::keyboardCallback(int key, int state)
|
||||
{
|
||||
|
||||
|
||||
if (m_data)
|
||||
{
|
||||
if (key==B3G_ALT )
|
||||
@@ -429,17 +429,17 @@ bool GpuRigidBodyDemo::mouseButtonCallback(int button, int state, float x, float
|
||||
m_data->m_rigidBodyPipeline->castRays(rays,hitResults);
|
||||
if (hitResults[0].m_hitFraction<1.f)
|
||||
{
|
||||
|
||||
|
||||
int hitBodyA = hitResults[0].m_hitBody;
|
||||
if (m_data->m_np->getBodiesCpu()[hitBodyA].m_invMass)
|
||||
{
|
||||
//printf("hit!\n");
|
||||
m_data->m_np->readbackAllBodiesToCpu();
|
||||
m_data->m_pickBody = hitBodyA;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//pivotInA
|
||||
b3Vector3 pivotInB;
|
||||
pivotInB.setInterpolate3(ray.m_from,ray.m_to,hitResults[0].m_hitFraction);
|
||||
@@ -458,14 +458,14 @@ bool GpuRigidBodyDemo::mouseButtonCallback(int button, int state, float x, float
|
||||
m_data->m_pickFixedBody = m_data->m_rigidBodyPipeline->registerPhysicsInstance(0,pos,orn,fixedSphere,0,false);
|
||||
m_data->m_rigidBodyPipeline->writeAllInstancesToGpu();
|
||||
m_data->m_bp->writeAabbsToGpu();
|
||||
|
||||
|
||||
if (m_data->m_pickGraphicsShapeIndex<0)
|
||||
{
|
||||
int strideInBytes = 9*sizeof(float);
|
||||
int numVertices = sizeof(point_sphere_vertices)/strideInBytes;
|
||||
int numIndices = sizeof(point_sphere_indices)/sizeof(int);
|
||||
m_data->m_pickGraphicsShapeIndex = m_guiHelper->getRenderInterface()->registerShape(&point_sphere_vertices[0],numVertices,point_sphere_indices,numIndices,B3_GL_POINTS);
|
||||
|
||||
|
||||
float color[4] ={1,0,0,1};
|
||||
float scaling[4]={1,1,1,1};
|
||||
|
||||
@@ -480,7 +480,7 @@ bool GpuRigidBodyDemo::mouseButtonCallback(int button, int state, float x, float
|
||||
m_instancingRenderer->writeSingleInstanceTransformToGPU(pivotInB,orn,m_data->m_pickGraphicsShapeInstance);
|
||||
m_data->m_np->setObjectTransformCpu(pos,orn,m_data->m_pickFixedBody);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
pivotInB.w = 0.f;
|
||||
m_data->m_pickPivotInA = pivotInA;
|
||||
|
||||
Reference in New Issue
Block a user