Merge remote-tracking branch 'bp/master'
This commit is contained in:
@@ -10,6 +10,7 @@
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
|
||||
|
||||
#include "../OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "BulletCollision/CollisionShapes/btShapeHull.h"
|
||||
@@ -134,7 +135,8 @@ void MultiDofDemo::initPhysics()
|
||||
bool spherical = true; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
|
||||
bool multibodyOnly = false;
|
||||
bool canSleep = true;
|
||||
bool selfCollide = false;
|
||||
bool selfCollide = false;
|
||||
bool multibodyConstraint = true;
|
||||
btVector3 linkHalfExtents(0.05, 0.37, 0.1);
|
||||
btVector3 baseHalfExtents(0.05, 0.37, 0.1);
|
||||
|
||||
@@ -236,7 +238,18 @@ void MultiDofDemo::initPhysics()
|
||||
|
||||
m_dynamicsWorld->addRigidBody(body);//,1,1+2);
|
||||
|
||||
|
||||
if (multibodyConstraint) {
|
||||
btVector3 pointInA = -linkHalfExtents;
|
||||
btVector3 pointInB = halfExtents;
|
||||
btMatrix3x3 frameInA;
|
||||
btMatrix3x3 frameInB;
|
||||
frameInA.setIdentity();
|
||||
frameInB.setIdentity();
|
||||
btMultiBodyFixedConstraint* p2p = new btMultiBodyFixedConstraint(mbC,numLinks-1,body,pointInA,pointInB,frameInA,frameInB);
|
||||
//btMultiBodyFixedConstraint* p2p = new btMultiBodyFixedConstraint(mbC,numLinks-1,mbC,numLinks-4,pointInA,pointInA,frameInA,frameInB);
|
||||
p2p->setMaxAppliedImpulse(2.0);
|
||||
m_dynamicsWorld->addMultiBodyConstraint(p2p);
|
||||
}
|
||||
}
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
|
||||
@@ -82,11 +82,11 @@ public:
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
|
||||
args.m_fileType = B3_SDF_FILE;
|
||||
args.m_useMultiBody = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
|
||||
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
|
||||
@@ -135,6 +135,7 @@ public:
|
||||
args.m_fileName = "cube_small.urdf";
|
||||
args.m_startPosition.setValue(0,0,.107);
|
||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||
args.m_useMultiBody = false;
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
if (1)
|
||||
@@ -144,6 +145,7 @@ public:
|
||||
args.m_startPosition.setValue(0,0,0);
|
||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||
args.m_forceOverrideFixedBase = true;
|
||||
args.m_useMultiBody = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
|
||||
|
||||
@@ -211,7 +211,10 @@ public:
|
||||
return m_cs;
|
||||
}
|
||||
|
||||
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color){}
|
||||
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color)
|
||||
{
|
||||
createCollisionObjectGraphicsObject((btCollisionObject*)body, color);
|
||||
}
|
||||
|
||||
btCollisionObject* m_obj;
|
||||
btVector3 m_color2;
|
||||
@@ -685,6 +688,7 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
|
||||
{
|
||||
b3LoadUrdfCommandSetUseFixedBase(command,true);
|
||||
}
|
||||
b3LoadUrdfCommandSetUseMultiBody(command, args.m_useMultiBody);
|
||||
statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
||||
@@ -699,6 +703,7 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(m_data->m_physicsClient, args.m_fileName.c_str());
|
||||
b3LoadSdfCommandSetUseMultiBody(command, args.m_useMultiBody);
|
||||
statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
b3Assert(statusType == CMD_SDF_LOADING_COMPLETED);
|
||||
|
||||
@@ -23,6 +23,7 @@ struct b3RobotSimLoadFileArgs
|
||||
b3Vector3 m_startPosition;
|
||||
b3Quaternion m_startOrientation;
|
||||
bool m_forceOverrideFixedBase;
|
||||
bool m_useMultiBody;
|
||||
int m_fileType;
|
||||
|
||||
|
||||
|
||||
@@ -55,6 +55,27 @@ b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClie
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_LOAD_URDF);
|
||||
command->m_updateFlags |=URDF_ARGS_USE_MULTIBODY;
|
||||
command->m_urdfArguments.m_useMultiBody = useMultiBody;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_LOAD_SDF);
|
||||
command->m_updateFlags |=URDF_ARGS_USE_MULTIBODY;
|
||||
command->m_sdfArguments.m_useMultiBody = useMultiBody;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase)
|
||||
{
|
||||
@@ -67,8 +88,6 @@ int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle,
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
|
||||
@@ -96,6 +96,7 @@ int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle,
|
||||
int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW);
|
||||
int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody);
|
||||
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase);
|
||||
int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody);
|
||||
|
||||
///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics
|
||||
b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex,
|
||||
|
||||
@@ -711,7 +711,7 @@ void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb)
|
||||
}
|
||||
|
||||
|
||||
bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes)
|
||||
bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody)
|
||||
{
|
||||
btAssert(m_data->m_dynamicsWorld);
|
||||
if (!m_data->m_dynamicsWorld)
|
||||
@@ -768,7 +768,6 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
MyMultiBodyCreator creation(m_data->m_guiHelper);
|
||||
|
||||
u2b.getRootTransformInWorld(rootTrans);
|
||||
bool useMultiBody = true;
|
||||
ConvertURDF2Bullet(u2b,creation, rootTrans,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),true);
|
||||
|
||||
|
||||
@@ -877,6 +876,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
}
|
||||
|
||||
btMultiBody* mb = creation.getBulletMultiBody();
|
||||
|
||||
if (useMultiBody)
|
||||
{
|
||||
|
||||
@@ -944,7 +944,6 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
|
||||
} else
|
||||
{
|
||||
btAssert(0);
|
||||
|
||||
return true;
|
||||
}
|
||||
@@ -1244,8 +1243,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
b3Printf("Processed CMD_LOAD_SDF:%s", sdfArgs.m_sdfFileName);
|
||||
}
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? sdfArgs.m_useMultiBody : true;
|
||||
|
||||
bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes);
|
||||
bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody);
|
||||
if (completedOk)
|
||||
{
|
||||
//serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
|
||||
|
||||
@@ -21,7 +21,7 @@ protected:
|
||||
|
||||
|
||||
|
||||
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes);
|
||||
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody);
|
||||
|
||||
bool loadUrdf(const char* fileName, const class btVector3& pos, const class btQuaternion& orn,
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes);
|
||||
|
||||
@@ -64,6 +64,7 @@ enum EnumSdfArgsUpdateFlags
|
||||
struct SdfArgs
|
||||
{
|
||||
char m_sdfFileName[MAX_URDF_FILENAME_LENGTH];
|
||||
int m_useMultiBody;
|
||||
};
|
||||
|
||||
enum EnumUrdfArgsUpdateFlags
|
||||
|
||||
Reference in New Issue
Block a user