Change dynamic to dynamics in dynamics info.
This commit is contained in:
@@ -1214,65 +1214,65 @@ int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointInd
|
||||
return cl->getJointInfo(bodyIndex, jointIndex, *info);
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3GetDynamicInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
|
||||
b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
b3Assert(cl);
|
||||
b3Assert(cl->canSubmitCommand());
|
||||
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||
b3Assert(command);
|
||||
command->m_type = CMD_GET_DYNAMIC_INFO;
|
||||
command->m_getDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
command->m_getDynamicInfoArgs.m_linkIndex = linkIndex;
|
||||
command->m_type = CMD_GET_DYNAMICS_INFO;
|
||||
command->m_getDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
command->m_getDynamicsInfoArgs.m_linkIndex = linkIndex;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
int b3GetDynamicInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicInfo* info)
|
||||
int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info)
|
||||
{
|
||||
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
|
||||
const b3DynamicInfo &dynamicInfo = status->m_dynamicInfo;
|
||||
btAssert(status->m_type == CMD_GET_DYNAMIC_INFO);
|
||||
if (status->m_type != CMD_GET_DYNAMIC_INFO_COMPLETED)
|
||||
const b3DynamicsInfo &dynamicsInfo = status->m_dynamicsInfo;
|
||||
btAssert(status->m_type == CMD_GET_DYNAMICS_INFO);
|
||||
if (status->m_type != CMD_GET_DYNAMICS_INFO_COMPLETED)
|
||||
return false;
|
||||
|
||||
info->m_mass = dynamicInfo.m_mass;
|
||||
info->m_lateralFrictionCoeff = dynamicInfo.m_lateralFrictionCoeff;
|
||||
info->m_mass = dynamicsInfo.m_mass;
|
||||
info->m_lateralFrictionCoeff = dynamicsInfo.m_lateralFrictionCoeff;
|
||||
return true;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitResetDynamicInfo(b3PhysicsClientHandle physClient)
|
||||
b3SharedMemoryCommandHandle b3InitResetDynamicsInfo(b3PhysicsClientHandle physClient)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
b3Assert(cl);
|
||||
b3Assert(cl->canSubmitCommand());
|
||||
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||
b3Assert(command);
|
||||
command->m_type = CMD_RESET_DYNAMIC_INFO;
|
||||
command->m_type = CMD_RESET_DYNAMICS_INFO;
|
||||
command->m_updateFlags = 0;
|
||||
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
int b3ResetDynamicInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass)
|
||||
int b3ResetDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_RESET_DYNAMIC_INFO);
|
||||
b3Assert(command->m_type == CMD_RESET_DYNAMICS_INFO);
|
||||
b3Assert(mass > 0);
|
||||
command->m_resetDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
command->m_resetDynamicInfoArgs.m_linkIndex = linkIndex;
|
||||
command->m_resetDynamicInfoArgs.m_mass = mass;
|
||||
command->m_updateFlags |= RESET_DYNAMIC_INFO_SET_MASS;
|
||||
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;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3ResetDynamicInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
|
||||
int b3ResetDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_RESET_DYNAMIC_INFO);
|
||||
command->m_resetDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
command->m_resetDynamicInfoArgs.m_linkIndex = linkIndex;
|
||||
command->m_resetDynamicInfoArgs.m_lateralFriction = lateralFriction;
|
||||
command->m_updateFlags |= RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION;
|
||||
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;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user