trackObject -> parentObject
trackLinkIndex -> parentLinkIndex add example debugDrawItems.py
This commit is contained in:
@@ -1612,8 +1612,8 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle p
|
||||
|
||||
command->m_userDebugDrawArgs.m_lineWidth = lineWidth;
|
||||
command->m_userDebugDrawArgs.m_lifeTime = lifeTime;
|
||||
command->m_userDebugDrawArgs.m_trackingObjectUniqueId = -1;
|
||||
command->m_userDebugDrawArgs.m_trackingLinkIndex = -1;
|
||||
command->m_userDebugDrawArgs.m_parentObjectUniqueId = -1;
|
||||
command->m_userDebugDrawArgs.m_parentLinkIndex = -1;
|
||||
command->m_userDebugDrawArgs.m_optionFlags = 0;
|
||||
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
@@ -1649,8 +1649,8 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle p
|
||||
command->m_userDebugDrawArgs.m_textSize = textSize;
|
||||
|
||||
command->m_userDebugDrawArgs.m_lifeTime = lifeTime;
|
||||
command->m_userDebugDrawArgs.m_trackingObjectUniqueId = -1;
|
||||
command->m_userDebugDrawArgs.m_trackingLinkIndex = -1;
|
||||
command->m_userDebugDrawArgs.m_parentObjectUniqueId = -1;
|
||||
command->m_userDebugDrawArgs.m_parentLinkIndex = -1;
|
||||
|
||||
command->m_userDebugDrawArgs.m_optionFlags = 0;
|
||||
|
||||
@@ -1682,15 +1682,15 @@ void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, do
|
||||
}
|
||||
|
||||
|
||||
void b3UserDebugItemSetTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex)
|
||||
void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
|
||||
|
||||
command->m_updateFlags |= USER_DEBUG_HAS_TRACKING_OBJECT;
|
||||
command->m_userDebugDrawArgs.m_trackingObjectUniqueId = objectUniqueId;
|
||||
command->m_userDebugDrawArgs.m_trackingLinkIndex = linkIndex;
|
||||
command->m_updateFlags |= USER_DEBUG_HAS_PARENT_OBJECT;
|
||||
command->m_userDebugDrawArgs.m_parentObjectUniqueId = objectUniqueId;
|
||||
command->m_userDebugDrawArgs.m_parentLinkIndex = linkIndex;
|
||||
}
|
||||
|
||||
|
||||
@@ -1714,7 +1714,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle ph
|
||||
command->m_userDebugDrawArgs.m_rangeMin = rangeMin;
|
||||
command->m_userDebugDrawArgs.m_rangeMax = rangeMax;
|
||||
command->m_userDebugDrawArgs.m_startValue = startValue;
|
||||
command->m_userDebugDrawArgs.m_trackingObjectUniqueId = -1;
|
||||
command->m_userDebugDrawArgs.m_parentObjectUniqueId = -1;
|
||||
command->m_userDebugDrawArgs.m_optionFlags = 0;
|
||||
return (b3SharedMemoryCommandHandle)command;
|
||||
}
|
||||
|
||||
@@ -127,7 +127,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle p
|
||||
void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags);
|
||||
void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[4]);
|
||||
|
||||
void b3UserDebugItemSetTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);
|
||||
void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle physClient, const char* txt, double rangeMin, double rangeMax, double startValue);
|
||||
b3SharedMemoryCommandHandle b3InitUserDebugReadParameter(b3PhysicsClientHandle physClient, int debugItemUniqueId);
|
||||
|
||||
@@ -5820,12 +5820,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
int trackingVisualShapeIndex = -1;
|
||||
|
||||
if (clientCmd.m_userDebugDrawArgs.m_trackingObjectUniqueId>=0)
|
||||
if (clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId>=0)
|
||||
{
|
||||
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_userDebugDrawArgs.m_trackingObjectUniqueId);
|
||||
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId);
|
||||
if (bodyHandle && bodyHandle->m_multiBody)
|
||||
{
|
||||
int linkIndex = clientCmd.m_userDebugDrawArgs.m_trackingLinkIndex;
|
||||
int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex;
|
||||
if (linkIndex ==-1)
|
||||
{
|
||||
if (bodyHandle->m_multiBody->getBaseCollider())
|
||||
|
||||
@@ -627,7 +627,7 @@ enum EnumUserDebugDrawFlags
|
||||
USER_DEBUG_READ_PARAMETER=128,
|
||||
USER_DEBUG_HAS_OPTION_FLAGS=256,
|
||||
USER_DEBUG_HAS_TEXT_ORIENTATION = 512,
|
||||
USER_DEBUG_HAS_TRACKING_OBJECT=1024,
|
||||
USER_DEBUG_HAS_PARENT_OBJECT=1024,
|
||||
|
||||
};
|
||||
|
||||
@@ -644,8 +644,8 @@ struct UserDebugDrawArgs
|
||||
char m_text[MAX_FILENAME_LENGTH];
|
||||
double m_textPositionXYZ[3];
|
||||
double m_textOrientation[4];
|
||||
int m_trackingObjectUniqueId;
|
||||
int m_trackingLinkIndex;
|
||||
int m_parentObjectUniqueId;
|
||||
int m_parentLinkIndex;
|
||||
double m_textColorRGB[3];
|
||||
double m_textSize;
|
||||
int m_optionFlags;
|
||||
|
||||
Reference in New Issue
Block a user