Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
This commit is contained in:
@@ -1612,6 +1612,9 @@ 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_optionFlags = 0;
|
||||
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
@@ -1646,10 +1649,51 @@ 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_optionFlags = 0;
|
||||
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
|
||||
b3Assert(command->m_updateFlags & USER_DEBUG_HAS_TEXT);
|
||||
command->m_userDebugDrawArgs.m_optionFlags = optionFlags;
|
||||
command->m_updateFlags |= USER_DEBUG_HAS_OPTION_FLAGS;
|
||||
}
|
||||
|
||||
void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[4])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
|
||||
b3Assert(command->m_updateFlags & USER_DEBUG_HAS_TEXT);
|
||||
command->m_userDebugDrawArgs.m_textOrientation[0] = orientation[0];
|
||||
command->m_userDebugDrawArgs.m_textOrientation[1] = orientation[1];
|
||||
command->m_userDebugDrawArgs.m_textOrientation[2] = orientation[2];
|
||||
command->m_userDebugDrawArgs.m_textOrientation[3] = orientation[3];
|
||||
command->m_updateFlags |= USER_DEBUG_HAS_TEXT_ORIENTATION;
|
||||
|
||||
}
|
||||
|
||||
|
||||
void b3UserDebugItemSetTrackingObject(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;
|
||||
}
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle physClient, const char* txt, double rangeMin, double rangeMax, double startValue)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
@@ -1670,6 +1714,8 @@ 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_optionFlags = 0;
|
||||
return (b3SharedMemoryCommandHandle)command;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user