work on pybullet/C-API createMultiBody (still preliminary, only sphere/box collision shapes, no links/hierarchies yet, soon)
pybullet/C-API, expose linear/angular damping fix some warnings (param name needs to be same in .h and .cpp) fix potential startup threading issue (args were deleted in main thread while still possibly use in child thread) fix for spinning/rolling friction in case of mixing maximal and reduced coordinate btMultiBody+btRigidBody
This commit is contained in:
@@ -877,6 +877,17 @@ int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass
|
||||
return -2;
|
||||
}
|
||||
|
||||
//useMaximalCoordinates are disabled by default, enabling them is experimental and not fully supported yet
|
||||
void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_CREATE_MULTI_BODY);
|
||||
if (command->m_type==CMD_CREATE_MULTI_BODY)
|
||||
{
|
||||
command->m_updateFlags |= MULT_BODY_USE_MAXIMAL_COORDINATES;
|
||||
}
|
||||
}
|
||||
|
||||
int b3GetStatusMultiBodyUniqueId(b3SharedMemoryStatusHandle statusHandle)
|
||||
{
|
||||
@@ -1269,6 +1280,11 @@ int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle)
|
||||
bodyId = status->m_rigidBodyCreateArgs.m_bodyUniqueId;
|
||||
break;
|
||||
}
|
||||
case CMD_CREATE_MULTI_BODY_COMPLETED:
|
||||
{
|
||||
bodyId = status->m_dataStreamArguments.m_bodyUniqueId;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
b3Assert(0);
|
||||
@@ -1541,9 +1557,29 @@ int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle
|
||||
command->m_changeDynamicsInfoArgs.m_restitution = restitution;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_RESTITUTION;
|
||||
return 0;
|
||||
}
|
||||
int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double linearDamping)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO);
|
||||
command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
command->m_changeDynamicsInfoArgs.m_linearDamping = linearDamping;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING;
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double angularDamping)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO);
|
||||
command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
command->m_changeDynamicsInfoArgs.m_linearDamping = angularDamping;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_ANGULAR_DAMPING;
|
||||
return 0;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
||||
@@ -87,7 +87,8 @@ int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHa
|
||||
int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction);
|
||||
int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction);
|
||||
int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution);
|
||||
|
||||
int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double linearDamping);
|
||||
int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double angularDamping);
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info);
|
||||
@@ -329,9 +330,10 @@ int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||
b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle physClient);
|
||||
int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, double basePosition[3], double baseOrientation[4]);
|
||||
|
||||
//int b3CreateMultiBodyAddLink(b3SharedMemoryCommandHandle commandHandle, int jointType, int parentLinkIndex, double linkMass, int linkCollisionShapeUnique, int linkVisualShapeUniqueId);
|
||||
//useMaximalCoordinates are disabled by default, enabling them is experimental and not fully supported yet
|
||||
void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle);
|
||||
|
||||
int b3GetStatusMultiBodyUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||
//int b3CreateMultiBodyAddLink(b3SharedMemoryCommandHandle commandHandle, int jointType, int parentLinkIndex, double linkMass, int linkCollisionShapeUnique, int linkVisualShapeUniqueId);
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -3530,9 +3530,16 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverStatusOut.m_type = CMD_CREATE_MULTI_BODY_FAILED;
|
||||
if (clientCmd.m_createMultiBodyArgs.m_baseLinkIndex>=0)
|
||||
{
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
ProgrammaticUrdfInterface u2b(clientCmd.m_createMultiBodyArgs, m_data);
|
||||
|
||||
bool useMultiBody = false;
|
||||
bool useMultiBody = true;
|
||||
if (clientCmd.m_updateFlags & MULT_BODY_USE_MAXIMAL_COORDINATES)
|
||||
{
|
||||
useMultiBody = false;
|
||||
}
|
||||
|
||||
int flags = 0;
|
||||
bool ok = processImportedObjects("memory", bufferServerToClient, bufferSizeInBytes, useMultiBody, flags, u2b);
|
||||
|
||||
@@ -4329,6 +4336,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
mb->getBaseCollider()->setRestitution(restitution);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING)
|
||||
{
|
||||
mb->setLinearDamping(clientCmd.m_changeDynamicsInfoArgs.m_linearDamping);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ANGULAR_DAMPING)
|
||||
{
|
||||
mb->setLinearDamping(clientCmd.m_changeDynamicsInfoArgs.m_angularDamping);
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
mb->getBaseCollider()->setFriction(lateralFriction);
|
||||
@@ -4395,6 +4411,17 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
if (body && body->m_rigidBody)
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING)
|
||||
{
|
||||
btScalar angDamping = body->m_rigidBody->getAngularDamping();
|
||||
body->m_rigidBody->setDamping(clientCmd.m_changeDynamicsInfoArgs.m_linearDamping,angDamping);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ANGULAR_DAMPING)
|
||||
{
|
||||
btScalar linDamping = body->m_rigidBody->getLinearDamping();
|
||||
body->m_rigidBody->setDamping(linDamping, clientCmd.m_changeDynamicsInfoArgs.m_angularDamping);
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_RESTITUTION)
|
||||
{
|
||||
body->m_rigidBody->setRestitution(restitution);
|
||||
|
||||
@@ -117,6 +117,8 @@ enum EnumChangeDynamicsInfoFlags
|
||||
CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION=8,
|
||||
CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION=16,
|
||||
CHANGE_DYNAMICS_INFO_SET_RESTITUTION=32,
|
||||
CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING=64,
|
||||
CHANGE_DYNAMICS_INFO_SET_ANGULAR_DAMPING=128,
|
||||
};
|
||||
|
||||
struct ChangeDynamicsInfoArgs
|
||||
@@ -129,6 +131,8 @@ struct ChangeDynamicsInfoArgs
|
||||
double m_spinningFriction;
|
||||
double m_rollingFriction;
|
||||
double m_restitution;
|
||||
double m_linearDamping;
|
||||
double m_angularDamping;
|
||||
};
|
||||
|
||||
struct GetDynamicsInfoArgs
|
||||
@@ -806,6 +810,7 @@ struct b3CreateVisualShapeArgs
|
||||
enum eCreateMultiBodyEnum
|
||||
{
|
||||
MULTI_BODY_HAS_BASE=1,
|
||||
MULT_BODY_USE_MAXIMAL_COORDINATES=2,
|
||||
};
|
||||
struct b3CreateMultiBodyArgs
|
||||
{
|
||||
|
||||
@@ -93,22 +93,23 @@ b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int arg
|
||||
class InProcessPhysicsClientSharedMemory : public PhysicsClientSharedMemory
|
||||
{
|
||||
btInProcessExampleBrowserInternalData* m_data;
|
||||
public:
|
||||
char** m_newargv;
|
||||
|
||||
public:
|
||||
|
||||
InProcessPhysicsClientSharedMemory(int argc, char* argv[])
|
||||
{
|
||||
int newargc = argc+2;
|
||||
char** newargv = (char**)malloc(sizeof(void*)*newargc);
|
||||
m_newargv = (char**)malloc(sizeof(void*)*newargc);
|
||||
for (int i=0;i<argc;i++)
|
||||
newargv[i] = argv[i];
|
||||
m_newargv[i] = argv[i];
|
||||
|
||||
char* t0 = (char*)"--logtostderr";
|
||||
char* t1 = (char*)"--start_demo_name=Physics Server";
|
||||
newargv[argc] = t0;
|
||||
newargv[argc+1] = t1;
|
||||
m_data = btCreateInProcessExampleBrowser(newargc,newargv);
|
||||
m_newargv[argc] = t0;
|
||||
m_newargv[argc+1] = t1;
|
||||
m_data = btCreateInProcessExampleBrowser(newargc,m_newargv);
|
||||
SharedMemoryInterface* shMem = btGetSharedMemoryInterface(m_data);
|
||||
free(newargv);
|
||||
setSharedMemoryInterface(shMem);
|
||||
}
|
||||
|
||||
@@ -116,6 +117,7 @@ public:
|
||||
{
|
||||
setSharedMemoryInterface(0);
|
||||
btShutDownExampleBrowser(m_data);
|
||||
free(m_newargv);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
@@ -22,7 +22,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
|
||||
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
|
||||
|
||||
virtual void changeRGBAColor(int bodyUniqueId, int shapeIndex, const double rgbaColor[4]);
|
||||
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, const double rgbaColor[4]);
|
||||
|
||||
virtual void removeVisualShape(class btCollisionObject* colObj);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user