Change the API names for loading softbody.

This commit is contained in:
yunfeibai
2018-01-07 19:24:37 -08:00
parent e3e9546960
commit d077bdec07
9 changed files with 47 additions and 65 deletions

View File

@@ -1143,7 +1143,7 @@ void b3RobotSimulatorClientAPI::submitProfileTiming(const std::string& profileN
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
} }
void b3RobotSimulatorClientAPI::loadBunny(double scale, double mass, double collisionMargin) void b3RobotSimulatorClientAPI::loadSoftBody(double scale, double mass, double collisionMargin)
{ {
if (!isConnected()) if (!isConnected())
{ {
@@ -1151,9 +1151,9 @@ void b3RobotSimulatorClientAPI::loadBunny(double scale, double mass, double coll
return; return;
} }
b3SharedMemoryCommandHandle command = b3LoadBunnyCommandInit(m_data->m_physicsClientHandle); b3SharedMemoryCommandHandle command = b3LoadSoftBodyCommandInit(m_data->m_physicsClientHandle);
b3LoadBunnySetScale(command, scale); b3LoadSoftBodySetScale(command, scale);
b3LoadBunnySetMass(command, mass); b3LoadSoftBodySetMass(command, mass);
b3LoadBunnySetCollisionMargin(command, collisionMargin); b3LoadSoftBodySetCollisionMargin(command, collisionMargin);
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
} }

View File

@@ -229,7 +229,7 @@ public:
//////////////// INTERNAL //////////////// INTERNAL
void loadBunny(double scale, double mass, double collisionMargin); void loadSoftBody(double scale, double mass, double collisionMargin);
//setGuiHelper is only used when embedded in existing example browser //setGuiHelper is only used when embedded in existing example browser
void setGuiHelper(struct GUIHelperInterface* guiHelper); void setGuiHelper(struct GUIHelperInterface* guiHelper);

View File

@@ -336,7 +336,7 @@ public:
} }
m_robotSim.setGravity(b3MakeVector3(0,0,-10)); m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.loadBunny(0.1,0.1,0.02); m_robotSim.loadSoftBody(0.1,0.1,0.02);
b3JointInfo revoluteJoint1; b3JointInfo revoluteJoint1;
revoluteJoint1.m_parentFrame[0] = -0.055; revoluteJoint1.m_parentFrame[0] = -0.055;
@@ -412,7 +412,7 @@ public:
m_robotSim.loadURDF("plane.urdf", args); m_robotSim.loadURDF("plane.urdf", args);
} }
m_robotSim.setGravity(b3MakeVector3(0,0,-10)); m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.loadBunny(0.3,10.0,0.1); m_robotSim.loadSoftBody(0.3,10.0,0.1);
} }
} }
virtual void exitPhysics() virtual void exitPhysics()

View File

@@ -256,7 +256,7 @@ B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle command
} }
} }
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient) B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSoftBodyCommandInit(b3PhysicsClientHandle physClient)
{ {
PhysicsClient* cl = (PhysicsClient* ) physClient; PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl); b3Assert(cl);
@@ -264,36 +264,36 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClient
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command); b3Assert(command);
command->m_type = CMD_LOAD_BUNNY; command->m_type = CMD_LOAD_SOFT_BODY;
command->m_updateFlags = 0; command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command; return (b3SharedMemoryCommandHandle) command;
} }
B3_SHARED_API int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale) B3_SHARED_API int b3LoadSoftBodySetScale(b3SharedMemoryCommandHandle commandHandle, double scale)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_LOAD_BUNNY); b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
command->m_loadBunnyArguments.m_scale = scale; command->m_loadSoftBodyArguments.m_scale = scale;
command->m_updateFlags |= LOAD_BUNNY_UPDATE_SCALE; command->m_updateFlags |= LOAD_SOFT_BODY_UPDATE_SCALE;
return 0; return 0;
} }
B3_SHARED_API int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass) B3_SHARED_API int b3LoadSoftBodySetMass(b3SharedMemoryCommandHandle commandHandle, double mass)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_LOAD_BUNNY); b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
command->m_loadBunnyArguments.m_mass = mass; command->m_loadSoftBodyArguments.m_mass = mass;
command->m_updateFlags |= LOAD_BUNNY_UPDATE_MASS; command->m_updateFlags |= LOAD_SOFT_BODY_UPDATE_MASS;
return 0; return 0;
} }
B3_SHARED_API int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin) B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_LOAD_BUNNY); b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
command->m_loadBunnyArguments.m_collisionMargin = collisionMargin; command->m_loadSoftBodyArguments.m_collisionMargin = collisionMargin;
command->m_updateFlags |= LOAD_BUNNY_UPDATE_COLLISION_MARGIN; command->m_updateFlags |= LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN;
return 0; return 0;
} }

View File

@@ -512,10 +512,10 @@ B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandl
B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[/*3*/], int flag); B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[/*3*/], int flag);
///experiments of robots interacting with non-rigid objects (such as btSoftBody) ///experiments of robots interacting with non-rigid objects (such as btSoftBody)
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSoftBodyCommandInit(b3PhysicsClientHandle physClient);
B3_SHARED_API int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale); B3_SHARED_API int b3LoadSoftBodySetScale(b3SharedMemoryCommandHandle commandHandle, double scale);
B3_SHARED_API int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass); B3_SHARED_API int b3LoadSoftBodySetMass(b3SharedMemoryCommandHandle commandHandle, double mass);
B3_SHARED_API int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin); B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin);
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient);

View File

@@ -5660,7 +5660,7 @@ bool PhysicsServerCommandProcessor::processLoadURDFCommand(const struct SharedMe
return hasStatus; return hasStatus;
} }
bool PhysicsServerCommandProcessor::processLoadBunnyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{ {
serverStatusOut.m_type = CMD_UNKNOWN_COMMAND_FLUSHED; serverStatusOut.m_type = CMD_UNKNOWN_COMMAND_FLUSHED;
bool hasStatus = true; bool hasStatus = true;
@@ -5668,17 +5668,17 @@ bool PhysicsServerCommandProcessor::processLoadBunnyCommand(const struct SharedM
double scale = 0.1; double scale = 0.1;
double mass = 0.1; double mass = 0.1;
double collisionMargin = 0.02; double collisionMargin = 0.02;
if (clientCmd.m_updateFlags & LOAD_BUNNY_UPDATE_SCALE) if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_UPDATE_SCALE)
{ {
scale = clientCmd.m_loadBunnyArguments.m_scale; scale = clientCmd.m_loadSoftBodyArguments.m_scale;
} }
if (clientCmd.m_updateFlags & LOAD_BUNNY_UPDATE_MASS) if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_UPDATE_MASS)
{ {
mass = clientCmd.m_loadBunnyArguments.m_mass; mass = clientCmd.m_loadSoftBodyArguments.m_mass;
} }
if (clientCmd.m_updateFlags & LOAD_BUNNY_UPDATE_COLLISION_MARGIN) if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN)
{ {
collisionMargin = clientCmd.m_loadBunnyArguments.m_collisionMargin; collisionMargin = clientCmd.m_loadSoftBodyArguments.m_collisionMargin;
} }
m_data->m_softBodyWorldInfo.air_density = (btScalar)1.2; m_data->m_softBodyWorldInfo.air_density = (btScalar)1.2;
@@ -5688,24 +5688,6 @@ bool PhysicsServerCommandProcessor::processLoadBunnyCommand(const struct SharedM
m_data->m_softBodyWorldInfo.m_gravity.setValue(0,0,-10); m_data->m_softBodyWorldInfo.m_gravity.setValue(0,0,-10);
m_data->m_softBodyWorldInfo.m_broadphase = m_data->m_broadphase; m_data->m_softBodyWorldInfo.m_broadphase = m_data->m_broadphase;
m_data->m_softBodyWorldInfo.m_sparsesdf.Initialize(); m_data->m_softBodyWorldInfo.m_sparsesdf.Initialize();
/*
btSoftBody* psb=btSoftBodyHelpers::CreateFromTriMesh(m_data->m_softBodyWorldInfo,gVerticesBunny, &gIndicesBunny[0][0], BUNNY_NUM_TRIANGLES);
btSoftBody::Material* pm=psb->appendMaterial();
pm->m_kLST = 1.0;
pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
psb->generateBendingConstraints(2,pm);
psb->m_cfg.piterations = 50;
psb->m_cfg.kDF = 0.5;
psb->randomizeConstraints();
psb->rotate(btQuaternion(0.70711,0,0,0.70711));
psb->translate(btVector3(0,0,1.0));
psb->scale(btVector3(scale,scale,scale));
psb->setTotalMass(mass,true);
psb->getCollisionShape()->setMargin(collisionMargin);
m_data->m_dynamicsWorld->addSoftBody(psb);
*/
{ {
char relativeFileName[1024]; char relativeFileName[1024];
@@ -5754,7 +5736,7 @@ bool PhysicsServerCommandProcessor::processLoadBunnyCommand(const struct SharedM
int bodyUniqueId = m_data->m_bodyHandles.allocHandle(); int bodyUniqueId = m_data->m_bodyHandles.allocHandle();
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId); InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId);
bodyHandle->m_softBody = psb; bodyHandle->m_softBody = psb;
serverStatusOut.m_loadBunnyResultArguments.m_objectUniqueId = bodyUniqueId; serverStatusOut.m_loadSoftBodyResultArguments.m_objectUniqueId = bodyUniqueId;
} }
} }
} }
@@ -8584,9 +8566,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
hasStatus = processLoadURDFCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes); hasStatus = processLoadURDFCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
break; break;
} }
case CMD_LOAD_BUNNY: case CMD_LOAD_SOFT_BODY:
{ {
hasStatus = processLoadBunnyCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes); hasStatus = processLoadSoftBodyCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
break; break;
} }
case CMD_CREATE_SENSOR: case CMD_CREATE_SENSOR:

View File

@@ -46,7 +46,7 @@ protected:
bool processLoadSDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processLoadSDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCreateMultiBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processCreateMultiBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processLoadURDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processLoadURDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processLoadBunnyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processLoadSoftBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCreateSensorCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processCreateSensorCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestCollisionInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); bool processRequestCollisionInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);

View File

@@ -428,11 +428,11 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP = 32768, SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP = 32768,
}; };
enum EnumLoadBunnyUpdateFlags enum EnumLoadSoftBodyUpdateFlags
{ {
LOAD_BUNNY_UPDATE_SCALE=1, LOAD_SOFT_BODY_UPDATE_SCALE=1,
LOAD_BUNNY_UPDATE_MASS=2, LOAD_SOFT_BODY_UPDATE_MASS=2,
LOAD_BUNNY_UPDATE_COLLISION_MARGIN=4 LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN=4
}; };
enum EnumSimParamInternalSimFlags enum EnumSimParamInternalSimFlags
@@ -444,14 +444,14 @@ enum EnumSimParamInternalSimFlags
///Controlling a robot involves sending the desired state to its joint motor controllers. ///Controlling a robot involves sending the desired state to its joint motor controllers.
///The control mode determines the state variables used for motor control. ///The control mode determines the state variables used for motor control.
struct LoadBunnyArgs struct LoadSoftBodyArgs
{ {
double m_scale; double m_scale;
double m_mass; double m_mass;
double m_collisionMargin; double m_collisionMargin;
}; };
struct b3LoadBunnyResultArgs struct b3LoadSoftBodyResultArgs
{ {
int m_objectUniqueId; int m_objectUniqueId;
}; };
@@ -985,7 +985,7 @@ struct SharedMemoryCommand
struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments; struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments;
struct UserDebugDrawArgs m_userDebugDrawArgs; struct UserDebugDrawArgs m_userDebugDrawArgs;
struct RequestRaycastIntersections m_requestRaycastIntersections; struct RequestRaycastIntersections m_requestRaycastIntersections;
struct LoadBunnyArgs m_loadBunnyArguments; struct LoadSoftBodyArgs m_loadSoftBodyArguments;
struct VRCameraState m_vrCameraStateArguments; struct VRCameraState m_vrCameraStateArguments;
struct StateLoggingRequest m_stateLoggingArguments; struct StateLoggingRequest m_stateLoggingArguments;
struct ConfigureOpenGLVisualizerRequest m_configureOpenGLVisualizerArguments; struct ConfigureOpenGLVisualizerRequest m_configureOpenGLVisualizerArguments;
@@ -1073,7 +1073,7 @@ struct SharedMemoryStatus
struct b3CustomCommandResultArgs m_customCommandResultArgs; struct b3CustomCommandResultArgs m_customCommandResultArgs;
struct b3PhysicsSimulationParameters m_simulationParameterResultArgs; struct b3PhysicsSimulationParameters m_simulationParameterResultArgs;
struct b3StateSerializationArguments m_saveStateResultArgs; struct b3StateSerializationArguments m_saveStateResultArgs;
struct b3LoadBunnyResultArgs m_loadBunnyResultArguments; struct b3LoadSoftBodyResultArgs m_loadSoftBodyResultArguments;
}; };
}; };

View File

@@ -22,7 +22,7 @@ enum EnumSharedMemoryClientCommand
CMD_LOAD_BULLET, CMD_LOAD_BULLET,
CMD_SAVE_BULLET, CMD_SAVE_BULLET,
CMD_LOAD_MJCF, CMD_LOAD_MJCF,
CMD_LOAD_BUNNY, CMD_LOAD_SOFT_BODY,
CMD_SEND_BULLET_DATA_STREAM, CMD_SEND_BULLET_DATA_STREAM,
CMD_CREATE_BOX_COLLISION_SHAPE, CMD_CREATE_BOX_COLLISION_SHAPE,
CMD_CREATE_RIGID_BODY, CMD_CREATE_RIGID_BODY,