Use "change" instead of "reset" for changing dynamics info.

This commit is contained in:
yunfeibai
2017-05-09 10:44:33 -07:00
parent 98654a0cb4
commit a587d4fec4
8 changed files with 45 additions and 45 deletions

View File

@@ -1240,39 +1240,39 @@ int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3Dynamics
return true;
}
b3SharedMemoryCommandHandle b3InitResetDynamicsInfo(b3PhysicsClientHandle physClient)
b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_RESET_DYNAMICS_INFO;
command->m_type = CMD_CHANGE_DYNAMICS_INFO;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command;
}
int b3ResetDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass)
int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_RESET_DYNAMICS_INFO);
b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO);
b3Assert(mass > 0);
command->m_resetDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicsInfoArgs.m_mass = mass;
command->m_updateFlags |= RESET_DYNAMICS_INFO_SET_MASS;
command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_changeDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_changeDynamicsInfoArgs.m_mass = mass;
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_MASS;
return 0;
}
int b3ResetDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_RESET_DYNAMICS_INFO);
command->m_resetDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicsInfoArgs.m_lateralFriction = lateralFriction;
command->m_updateFlags |= RESET_DYNAMICS_INFO_SET_LATERAL_FRICTION;
b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO);
command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_changeDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_changeDynamicsInfoArgs.m_lateralFriction = lateralFriction;
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION;
return 0;
}

View File

@@ -78,12 +78,12 @@ int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex);
int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info);
b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex);
///given a body unique id and link index, return the dynamic information. See b3DynamicInfo in SharedMemoryPublic.h
///given a body unique id and link index, return the dynamics information. See b3DynamicsInfo in SharedMemoryPublic.h
int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info);
b3SharedMemoryCommandHandle b3InitResetDynamicsInfo(b3PhysicsClientHandle physClient);
int b3ResetDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass);
int b3ResetDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction);
b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient);
int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass);
int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction);
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info);

View File

@@ -1045,7 +1045,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
}
case CMD_GET_DYNAMICS_INFO_FAILED:
{
b3Warning("Request dynamic info failed");
b3Warning("Request dynamics info failed");
break;
}
default: {

View File

@@ -3898,15 +3898,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
};
case CMD_RESET_DYNAMICS_INFO:
case CMD_CHANGE_DYNAMICS_INFO:
{
BT_PROFILE("CMD_RESET_DYNAMICS_INFO");
BT_PROFILE("CMD_CHANGE_DYNAMICS_INFO");
if (clientCmd.m_updateFlags & RESET_DYNAMICS_INFO_SET_MASS)
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
{
int bodyUniqueId = clientCmd.m_resetDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicsInfoArgs.m_linkIndex;
double mass = clientCmd.m_resetDynamicsInfoArgs.m_mass;
int bodyUniqueId = clientCmd.m_changeDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_changeDynamicsInfoArgs.m_linkIndex;
double mass = clientCmd.m_changeDynamicsInfoArgs.m_mass;
btAssert(bodyUniqueId >= 0);
btAssert(linkIndex >= -1);
@@ -3925,11 +3925,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
}
if (clientCmd.m_updateFlags & RESET_DYNAMICS_INFO_SET_LATERAL_FRICTION)
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
{
int bodyUniqueId = clientCmd.m_resetDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicsInfoArgs.m_linkIndex;
double lateralFriction = clientCmd.m_resetDynamicsInfoArgs.m_lateralFriction;
int bodyUniqueId = clientCmd.m_changeDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_changeDynamicsInfoArgs.m_linkIndex;
double lateralFriction = clientCmd.m_changeDynamicsInfoArgs.m_lateralFriction;
btAssert(bodyUniqueId >= 0);
btAssert(linkIndex >= -1);

View File

@@ -106,14 +106,14 @@ struct BulletDataStreamArgs
char m_bodyName[MAX_FILENAME_LENGTH];
};
enum EnumResetDynamicsInfoFlags
enum EnumChangeDynamicsInfoFlags
{
RESET_DYNAMICS_INFO_SET_MASS=1,
RESET_DYNAMICS_INFO_SET_COM=2,
RESET_DYNAMICS_INFO_SET_LATERAL_FRICTION=4,
CHANGE_DYNAMICS_INFO_SET_MASS=1,
CHANGE_DYNAMICS_INFO_SET_COM=2,
CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION=4,
};
struct ResetDynamicsInfoArgs
struct ChangeDynamicsInfoArgs
{
int m_bodyUniqueId;
int m_linkIndex;
@@ -744,7 +744,7 @@ struct SharedMemoryCommand
struct MjcfArgs m_mjcfArguments;
struct FileArgs m_fileArguments;
struct SdfRequestInfoArgs m_sdfRequestInfoArgs;
struct ResetDynamicsInfoArgs m_resetDynamicsInfoArgs;
struct ChangeDynamicsInfoArgs m_changeDynamicsInfoArgs;
struct GetDynamicsInfoArgs m_getDynamicsInfoArgs;
struct InitPoseArgs m_initPoseArgs;
struct SendPhysicsSimulationParameters m_physSimParamArgs;

View File

@@ -56,7 +56,7 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_KEYBOARD_EVENTS_DATA,
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA,
CMD_REMOVE_BODY,
CMD_RESET_DYNAMICS_INFO,
CMD_CHANGE_DYNAMICS_INFO,
CMD_GET_DYNAMICS_INFO,
CMD_PROFILE_TIMING,
//don't go beyond this command!

View File

@@ -6,15 +6,15 @@ p.connect(p.GUI)
planeId = p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593])
p.loadURDF(fileName="cube.urdf",baseOrientation=[0.25882,0,0,0.96593],basePosition=[0,0,2])
cubeId = p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4])
p.resetDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
#p.resetDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
p.changeDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
#p.changeDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
p.setGravity(0,0,-10)
p.setRealTimeSimulation(0)
t=0
while 1:
t=t+1
if t > 400:
p.resetDynamicsInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
p.changeDynamicsInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
mass1,frictionCoeff1=p.getDynamicsInfo(bodyUniqueId=planeId,linkIndex=-1)
mass2,frictionCoeff2=p.getDynamicsInfo(bodyUniqueId=cubeId,linkIndex=-1)
print mass1,frictionCoeff1

View File

@@ -604,7 +604,7 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key
return pylist;
}
static PyObject* pybullet_resetDynamicsInfo(PyObject* self, PyObject* args, PyObject* keywds)
static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyObject* keywds)
{
int bodyUniqueId = -1;
int linkIndex = -2;
@@ -627,17 +627,17 @@ static PyObject* pybullet_resetDynamicsInfo(PyObject* self, PyObject* args, PyOb
}
{
b3SharedMemoryCommandHandle command = b3InitResetDynamicsInfo(sm);
b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(sm);
b3SharedMemoryStatusHandle statusHandle;
if (mass >= 0)
{
b3ResetDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass);
b3ChangeDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass);
}
if (lateralFriction >= 0)
{
b3ResetDynamicsInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
b3ChangeDynamicsInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
@@ -5639,8 +5639,8 @@ static PyMethodDef SpamMethods[] = {
"Reset the state (position, velocity etc) for a joint on a body "
"instantaneously, not through physics simulation."},
{"resetDynamicsInfo", (PyCFunction)pybullet_resetDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
"Reset dynamics information such as mass, lateral friction coefficient."},
{"changeDynamicsInfo", (PyCFunction)pybullet_changeDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
"change dynamics information such as mass, lateral friction coefficient."},
{"getDynamicsInfo", (PyCFunction)pybullet_getDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
"Get dynamics information such as mass, lateral friction coefficient."},