pybullet: allow to replace existing text, to avoid flickering (remove/add)

allow texture caching (disable using the disable file caching)
This commit is contained in:
erwincoumans
2017-10-25 08:15:01 -07:00
parent e9415f5912
commit ed8de36ffa
17 changed files with 256 additions and 88 deletions

View File

@@ -2594,6 +2594,18 @@ B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle com
}
B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHandle commandHandle, int replaceItemUniqueId)
{
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_replaceItemUniqueId = replaceItemUniqueId;
command->m_updateFlags |= USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID;
}
B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex)
{

View File

@@ -170,6 +170,8 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3Physics
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[/*3*/], double colorRGB[/*3*/], double textSize, double lifeTime);
B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags);
B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[/*4*/]);
B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHandle commandHandle, int replaceItem);
B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);

View File

@@ -78,7 +78,7 @@ struct PhysicsClientSharedMemoryInternalData {
m_hasLastServerStatus(false),
m_sharedMemoryKey(SHARED_MEMORY_KEY),
m_verboseOutput(false),
m_timeOutInSeconds(30)
m_timeOutInSeconds(1e30)
{}
void processServerStatus();

View File

@@ -1,5 +1,4 @@
#include "PhysicsServerCommandProcessor.h"
#include "../CommonInterfaces/CommonRenderInterface.h"
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
@@ -4483,7 +4482,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
if (textures.size())
{
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height);
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData1,textures[0].m_width,textures[0].m_height);
}
int graphicsIndex = -1;
{
@@ -8146,27 +8145,35 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
if (clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId>=0)
{
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
if (bodyHandle)
{
int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex;
if (linkIndex ==-1)
int linkIndex = -1;
if (bodyHandle->m_multiBody)
{
if (bodyHandle->m_multiBody->getBaseCollider())
int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex;
if (linkIndex ==-1)
{
trackingVisualShapeIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
}
} else
{
if (linkIndex >=0 && linkIndex < bodyHandle->m_multiBody->getNumLinks())
{
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
if (bodyHandle->m_multiBody->getBaseCollider())
{
trackingVisualShapeIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
trackingVisualShapeIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
}
} else
{
if (linkIndex >=0 && linkIndex < bodyHandle->m_multiBody->getNumLinks())
{
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
{
trackingVisualShapeIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
}
}
}
}
if (bodyHandle->m_rigidBody)
{
trackingVisualShapeIndex = bodyHandle->m_rigidBody->getUserIndex();
}
}
}
@@ -8252,7 +8259,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
int replaceItemUniqueId = -1;
if ((clientCmd.m_updateFlags & USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID)!=0)
{
replaceItemUniqueId = clientCmd.m_userDebugDrawArgs.m_replaceItemUniqueId;
}
int uid = m_data->m_guiHelper->addUserDebugText3D(clientCmd.m_userDebugDrawArgs.m_text,
@@ -8262,7 +8273,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
clientCmd.m_userDebugDrawArgs.m_textSize,
clientCmd.m_userDebugDrawArgs.m_lifeTime,
trackingVisualShapeIndex,
optionFlags);
optionFlags,
replaceItemUniqueId);
if (uid>=0)
{

View File

@@ -13,13 +13,14 @@
#include "../Utils/b3Clock.h"
#include "../MultiThreading/b3ThreadSupportInterface.h"
#include "SharedMemoryPublic.h"
//#define BT_ENABLE_VR
#ifdef BT_ENABLE_VR
#include "../RenderingExamples/TinyVRGui.h"
#endif//BT_ENABLE_VR
#include "../CommonInterfaces/CommonParameterInterface.h"
#include "../Importers/ImportURDFDemo/urdfStringSplit.h"
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
bool gEnablePicking=true;
@@ -36,9 +37,7 @@ static bool gEnableDefaultKeyboardShortcuts = true;
static bool gEnableDefaultMousePicking = true;
//extern btVector3 gLastPickPos;
btVector3 gVRTeleportPosLocal(0,0,0);
btQuaternion gVRTeleportOrnLocal(0,0,0,1);
btScalar gVRTeleportRotZ = 0;
@@ -1132,10 +1131,17 @@ public:
UserDebugText m_tmpText;
int m_resultUserDebugTextUid;
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags)
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid)
{
m_tmpText.m_itemUniqueId = m_uidGenerator++;
if (replaceItemUid>=0)
{
m_tmpText.m_itemUniqueId = replaceItemUid;
} else
{
m_tmpText.m_itemUniqueId = m_uidGenerator++;
}
m_tmpText.m_lifeTime = lifeTime;
m_tmpText.textSize = size;
//int len = strlen(txt);
@@ -2171,10 +2177,26 @@ void PhysicsServerExample::updateGraphics()
case eGUIUserDebugAddText:
{
B3_PROFILE("eGUIUserDebugAddText");
bool replaced = false;
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size()-1].m_itemUniqueId;
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpText.m_itemUniqueId)
{
m_multiThreadedHelper->m_userDebugText[i] = m_multiThreadedHelper->m_tmpText;
m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_tmpText.m_itemUniqueId;
replaced = true;
}
}
if (!replaced)
{
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size()-1].m_itemUniqueId;
}
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIUserDebugAddParameter:
@@ -2503,10 +2525,35 @@ void PhysicsServerExample::drawUserDebugLines()
}
{
btAlignedObjectArray<std::string> pieces;
btAlignedObjectArray<std::string> separators;
separators.push_back("\n");
urdfStringSplit(pieces,m_multiThreadedHelper->m_userDebugText[i].m_text,separators);
double sz = m_multiThreadedHelper->m_userDebugText[i].textSize;
btTransform tr;
tr.setIdentity();
tr.setOrigin(btVector3(pos[0],pos[1],pos[2]));
tr.setRotation(btQuaternion(orientation[0],orientation[1],orientation[2],orientation[3]));
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
pos,orientation,colorRGBA,
m_multiThreadedHelper->m_userDebugText[i].textSize,optionFlag);
//float newpos[3]={pos[0]-float(t)*sz,pos[1],pos[2]};
for (int t=0;t<pieces.size();t++)
{
btTransform offset;
offset.setIdentity();
offset.setOrigin(btVector3(0,-float(t)*sz,0));
btTransform result = tr*offset;
float newpos[3] = {result.getOrigin()[0],result.getOrigin()[1],result.getOrigin()[2]};
m_guiHelper->getAppInterface()->drawText3D(pieces[t].c_str(),
newpos,orientation,colorRGBA,
sz,optionFlag);
}
}
/*m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,

View File

@@ -700,7 +700,7 @@ enum EnumUserDebugDrawFlags
USER_DEBUG_HAS_OPTION_FLAGS=256,
USER_DEBUG_HAS_TEXT_ORIENTATION = 512,
USER_DEBUG_HAS_PARENT_OBJECT=1024,
USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID=2048,
};
struct UserDebugDrawArgs
@@ -721,7 +721,7 @@ struct UserDebugDrawArgs
double m_textColorRGB[3];
double m_textSize;
int m_optionFlags;
int m_replaceItemUniqueId;
double m_rangeMin;
double m_rangeMax;

View File

@@ -38,9 +38,10 @@ subject to the following restrictions:
struct MyTexture2
{
unsigned char* textureData;
unsigned char* textureData1;
int m_width;
int m_height;
bool m_isCached;
};
struct TinyRendererObjectArray
@@ -308,12 +309,13 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData))
{
if (meshData.m_textureImage)
if (meshData.m_textureImage1)
{
MyTexture2 texData;
texData.m_width = meshData.m_textureWidth;
texData.m_height = meshData.m_textureHeight;
texData.textureData = meshData.m_textureImage;
texData.textureData1 = meshData.m_textureImage1;
texData.m_isCached = meshData.m_isCached;
texturesOut.push_back(texData);
}
glmesh = meshData.m_gfxShape;
@@ -628,27 +630,32 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
if (vertices.size() && indices.size())
{
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId);
unsigned char* textureImage=0;
unsigned char* textureImage1=0;
int textureWidth=0;
int textureHeight=0;
bool isCached = false;
if (textures.size())
{
textureImage = textures[0].textureData;
textureImage1 = textures[0].textureData1;
textureWidth = textures[0].m_width;
textureHeight = textures[0].m_height;
isCached = textures[0].m_isCached;
}
{
B3_PROFILE("registerMeshShape");
tinyObj->registerMeshShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), rgbaColor,
textureImage, textureWidth, textureHeight);
textureImage1, textureWidth, textureHeight);
}
visuals->m_renderObjects.push_back(tinyObj);
}
for (int i=0;i<textures.size();i++)
{
free(textures[i].textureData);
if (!textures[i].m_isCached)
{
free(textures[i].textureData1);
}
}
}
}
@@ -1090,7 +1097,10 @@ void TinyRendererVisualShapeConverter::resetAll()
for (int i=0;i<m_data->m_textures.size();i++)
{
free(m_data->m_textures[i].textureData);
if (!m_data->m_textures[i].m_isCached)
{
free(m_data->m_textures[i].textureData1);
}
}
m_data->m_textures.clear();
m_data->m_swRenderInstances.clear();
@@ -1117,7 +1127,7 @@ void TinyRendererVisualShapeConverter::activateShapeTexture(int objectUniqueId,
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
if ((shapeIndex < 0) || (shapeIndex == v))
{
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData1, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
}
}
}
@@ -1131,7 +1141,7 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
MyTexture2 texData;
texData.m_width = width;
texData.m_height = height;
texData.textureData = texels;
texData.textureData1 = texels;
m_data->m_textures.push_back(texData);
return m_data->m_textures.size()-1;
}