implement pybullet.changeTexture. For now, the width/height has to match the target texture unique id, otherwise crashes may happen (a check for width/height match will be added)
See also examples\pybullet\examples\changeTexture.py
This commit is contained in:
BIN
data/tex256.png
Normal file
BIN
data/tex256.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 12 KiB |
@@ -40,6 +40,7 @@ struct GUIHelperInterface
|
|||||||
virtual void removeGraphicsInstance(int graphicsUid) {}
|
virtual void removeGraphicsInstance(int graphicsUid) {}
|
||||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
|
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
|
||||||
virtual void changeSpecularColor(int instanceUid, const double specularColor[3]) {}
|
virtual void changeSpecularColor(int instanceUid, const double specularColor[3]) {}
|
||||||
|
virtual void changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int width, int height){}
|
||||||
|
|
||||||
virtual int getShapeIndexFromInstance(int instanceUid){return -1;}
|
virtual int getShapeIndexFromInstance(int instanceUid){return -1;}
|
||||||
virtual void replaceTexture(int shapeIndex, int textureUid){}
|
virtual void replaceTexture(int shapeIndex, int textureUid){}
|
||||||
|
|||||||
@@ -292,6 +292,12 @@ int OpenGLGuiHelper::registerTexture(const unsigned char* texels, int width, int
|
|||||||
return textureId;
|
return textureId;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void OpenGLGuiHelper::changeTexture(int textureUniqueId, const unsigned char* texels, int width, int height)
|
||||||
|
{
|
||||||
|
bool flipPixelsY = true;
|
||||||
|
m_data->m_glApp->m_renderer->updateTexture(textureUniqueId, texels,flipPixelsY);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
int OpenGLGuiHelper::registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
|
int OpenGLGuiHelper::registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -28,6 +28,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
|||||||
virtual void removeGraphicsInstance(int graphicsUid);
|
virtual void removeGraphicsInstance(int graphicsUid);
|
||||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]);
|
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]);
|
||||||
virtual void changeSpecularColor(int instanceUid, const double specularColor[3]);
|
virtual void changeSpecularColor(int instanceUid, const double specularColor[3]);
|
||||||
|
virtual void changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int width, int height);
|
||||||
|
|
||||||
virtual int getShapeIndexFromInstance(int instanceUid);
|
virtual int getShapeIndexFromInstance(int instanceUid);
|
||||||
virtual void replaceTexture(int shapeIndex, int textureUid);
|
virtual void replaceTexture(int shapeIndex, int textureUid);
|
||||||
|
|||||||
@@ -117,13 +117,14 @@ GLint lineWidthRange[2]={1,1};
|
|||||||
|
|
||||||
enum
|
enum
|
||||||
{
|
{
|
||||||
eGfxTransparency=1
|
eGfxTransparency=1,
|
||||||
};
|
};
|
||||||
|
|
||||||
struct b3GraphicsInstance
|
struct b3GraphicsInstance
|
||||||
{
|
{
|
||||||
GLuint m_cube_vao;
|
GLuint m_cube_vao;
|
||||||
GLuint m_index_vbo;
|
GLuint m_index_vbo;
|
||||||
GLuint m_texturehandle;
|
GLuint m_textureIndex;
|
||||||
|
|
||||||
int m_numIndices;
|
int m_numIndices;
|
||||||
int m_numVertices;
|
int m_numVertices;
|
||||||
@@ -141,7 +142,7 @@ struct b3GraphicsInstance
|
|||||||
b3GraphicsInstance()
|
b3GraphicsInstance()
|
||||||
:m_cube_vao(-1),
|
:m_cube_vao(-1),
|
||||||
m_index_vbo(-1),
|
m_index_vbo(-1),
|
||||||
m_texturehandle(0),
|
m_textureIndex(-1),
|
||||||
m_numIndices(-1),
|
m_numIndices(-1),
|
||||||
m_numVertices(-1),
|
m_numVertices(-1),
|
||||||
m_numGraphicsInstances(0),
|
m_numGraphicsInstances(0),
|
||||||
@@ -188,6 +189,7 @@ struct InternalTextureHandle
|
|||||||
GLuint m_glTexture;
|
GLuint m_glTexture;
|
||||||
int m_width;
|
int m_width;
|
||||||
int m_height;
|
int m_height;
|
||||||
|
int m_enableFiltering;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct b3PublicGraphicsInstanceData
|
struct b3PublicGraphicsInstanceData
|
||||||
@@ -954,7 +956,7 @@ int GLInstancingRenderer::registerTexture(const unsigned char* texels, int width
|
|||||||
h.m_glTexture = textureHandle;
|
h.m_glTexture = textureHandle;
|
||||||
h.m_width = width;
|
h.m_width = width;
|
||||||
h.m_height = height;
|
h.m_height = height;
|
||||||
|
h.m_enableFiltering = true;
|
||||||
m_data->m_textureHandles.push_back(h);
|
m_data->m_textureHandles.push_back(h);
|
||||||
if (texels)
|
if (texels)
|
||||||
{
|
{
|
||||||
@@ -971,7 +973,8 @@ void GLInstancingRenderer::replaceTexture(int shapeIndex, int textureId)
|
|||||||
b3GraphicsInstance* gfxObj = m_graphicsInstances[shapeIndex];
|
b3GraphicsInstance* gfxObj = m_graphicsInstances[shapeIndex];
|
||||||
if (textureId>=0)
|
if (textureId>=0)
|
||||||
{
|
{
|
||||||
gfxObj->m_texturehandle = m_data->m_textureHandles[textureId].m_glTexture;
|
gfxObj->m_textureIndex = textureId;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -980,9 +983,6 @@ void GLInstancingRenderer::updateTexture(int textureIndex, const unsigned cha
|
|||||||
{
|
{
|
||||||
if (textureIndex>=0)
|
if (textureIndex>=0)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
glActiveTexture(GL_TEXTURE0);
|
glActiveTexture(GL_TEXTURE0);
|
||||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||||
InternalTextureHandle& h = m_data->m_textureHandles[textureIndex];
|
InternalTextureHandle& h = m_data->m_textureHandles[textureIndex];
|
||||||
@@ -1011,7 +1011,10 @@ void GLInstancingRenderer::updateTexture(int textureIndex, const unsigned cha
|
|||||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, h.m_width,h.m_height,0,GL_RGB,GL_UNSIGNED_BYTE,&texels[0]);
|
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, h.m_width,h.m_height,0,GL_RGB,GL_UNSIGNED_BYTE,&texels[0]);
|
||||||
}
|
}
|
||||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||||
glGenerateMipmap(GL_TEXTURE_2D);
|
if (h.m_enableFiltering)
|
||||||
|
{
|
||||||
|
glGenerateMipmap(GL_TEXTURE_2D);
|
||||||
|
}
|
||||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -1048,7 +1051,7 @@ int GLInstancingRenderer::registerShape(const float* vertices, int numvertices,
|
|||||||
|
|
||||||
if (textureId>=0)
|
if (textureId>=0)
|
||||||
{
|
{
|
||||||
gfxObj->m_texturehandle = m_data->m_textureHandles[textureId].m_glTexture;
|
gfxObj->m_textureIndex = textureId;
|
||||||
}
|
}
|
||||||
|
|
||||||
gfxObj->m_primitiveType = primitiveType;
|
gfxObj->m_primitiveType = primitiveType;
|
||||||
@@ -2201,10 +2204,26 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
|||||||
{
|
{
|
||||||
glActiveTexture(GL_TEXTURE0);
|
glActiveTexture(GL_TEXTURE0);
|
||||||
GLuint curBindTexture = 0;
|
GLuint curBindTexture = 0;
|
||||||
if (gfxObj->m_texturehandle)
|
if (gfxObj->m_textureIndex>=0)
|
||||||
curBindTexture = gfxObj->m_texturehandle;
|
{
|
||||||
|
curBindTexture = m_data->m_textureHandles[gfxObj->m_textureIndex].m_glTexture;
|
||||||
|
|
||||||
|
glTexParameteri(GL_TEXTURE_2D,GL_TEXTURE_BASE_LEVEL,0);
|
||||||
|
|
||||||
|
if (m_data->m_textureHandles[gfxObj->m_textureIndex].m_enableFiltering)
|
||||||
|
{
|
||||||
|
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
|
||||||
|
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
|
||||||
|
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
|
||||||
|
}
|
||||||
|
}
|
||||||
else
|
else
|
||||||
|
{
|
||||||
curBindTexture = m_data->m_defaultTexturehandle;
|
curBindTexture = m_data->m_defaultTexturehandle;
|
||||||
|
}
|
||||||
|
|
||||||
//disable lazy evaluation, it just leads to bugs
|
//disable lazy evaluation, it just leads to bugs
|
||||||
//if (lastBindTexture != curBindTexture)
|
//if (lastBindTexture != curBindTexture)
|
||||||
|
|||||||
@@ -2918,6 +2918,25 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels)
|
||||||
|
{
|
||||||
|
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||||
|
b3Assert(cl);
|
||||||
|
b3Assert(cl->canSubmitCommand());
|
||||||
|
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||||
|
b3Assert(command);
|
||||||
|
command->m_type = CMD_CHANGE_TEXTURE;
|
||||||
|
|
||||||
|
command->m_changeTextureArgs.m_textureUniqueId = textureUniqueId;
|
||||||
|
command->m_changeTextureArgs.m_width = width;
|
||||||
|
command->m_changeTextureArgs.m_height = height;
|
||||||
|
int numPixels = width*height;
|
||||||
|
cl->uploadBulletFileToSharedMemory(rgbPixels,numPixels*3);
|
||||||
|
command->m_updateFlags = 0;
|
||||||
|
return (b3SharedMemoryCommandHandle) command;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename)
|
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename)
|
||||||
{
|
{
|
||||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||||
|
|||||||
@@ -219,6 +219,7 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
|
|||||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
|
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
|
||||||
int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels);
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||||
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]);
|
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]);
|
||||||
|
|||||||
@@ -1368,7 +1368,9 @@ void PhysicsClientSharedMemory::uploadBulletFileToSharedMemory(const char* data,
|
|||||||
SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
||||||
} else {
|
} else {
|
||||||
for (int i = 0; i < len; i++) {
|
for (int i = 0; i < len; i++) {
|
||||||
m_data->m_testBlock1->m_bulletStreamDataClientToServer[i] = data[i];
|
//m_data->m_testBlock1->m_bulletStreamDataClientToServer[i] = data[i];
|
||||||
|
m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[i] = data[i];
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1095,6 +1095,14 @@ void PhysicsDirect::setSharedMemoryKey(int key)
|
|||||||
|
|
||||||
void PhysicsDirect::uploadBulletFileToSharedMemory(const char* data, int len)
|
void PhysicsDirect::uploadBulletFileToSharedMemory(const char* data, int len)
|
||||||
{
|
{
|
||||||
|
if (len>SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE)
|
||||||
|
{
|
||||||
|
len = SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE;
|
||||||
|
}
|
||||||
|
for (int i=0;i<len;i++)
|
||||||
|
{
|
||||||
|
m_data->m_bulletStreamDataServerToClient[i] = data[i];
|
||||||
|
}
|
||||||
//m_data->m_physicsClient->uploadBulletFileToSharedMemory(data,len);
|
//m_data->m_physicsClient->uploadBulletFileToSharedMemory(data,len);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -6863,6 +6863,24 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case CMD_CHANGE_TEXTURE:
|
||||||
|
{
|
||||||
|
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||||
|
serverCmd.m_type = CMD_CHANGE_TEXTURE_COMMAND_FAILED;
|
||||||
|
|
||||||
|
InternalTextureHandle* texH = m_data->m_textureHandles.getHandle(clientCmd.m_changeTextureArgs.m_textureUniqueId);
|
||||||
|
if(texH)
|
||||||
|
{
|
||||||
|
int gltex = texH->m_openglTextureId;
|
||||||
|
m_data->m_guiHelper->changeTexture(gltex,
|
||||||
|
(const unsigned char*)bufferServerToClient, clientCmd.m_changeTextureArgs.m_width,clientCmd.m_changeTextureArgs.m_height);
|
||||||
|
|
||||||
|
serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
|
||||||
|
}
|
||||||
|
hasStatus = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
case CMD_LOAD_TEXTURE:
|
case CMD_LOAD_TEXTURE:
|
||||||
{
|
{
|
||||||
BT_PROFILE("CMD_LOAD_TEXTURE");
|
BT_PROFILE("CMD_LOAD_TEXTURE");
|
||||||
|
|||||||
@@ -133,6 +133,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
|
|||||||
eGUIHelperSetVisualizerFlag,
|
eGUIHelperSetVisualizerFlag,
|
||||||
eGUIHelperChangeGraphicsInstanceTextureId,
|
eGUIHelperChangeGraphicsInstanceTextureId,
|
||||||
eGUIHelperGetShapeIndexFromInstance,
|
eGUIHelperGetShapeIndexFromInstance,
|
||||||
|
eGUIHelperChangeTexture,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
@@ -958,6 +959,23 @@ public:
|
|||||||
workerThreadWait();
|
workerThreadWait();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int m_changeTextureUniqueId;
|
||||||
|
const unsigned char* m_changeTextureRgbTexels;
|
||||||
|
int m_changeTextureWidth;
|
||||||
|
int m_changeTextureHeight;
|
||||||
|
|
||||||
|
virtual void changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int width, int height)
|
||||||
|
{
|
||||||
|
m_changeTextureUniqueId = textureUniqueId;
|
||||||
|
m_changeTextureRgbTexels = rgbTexels;
|
||||||
|
m_changeTextureWidth = width;
|
||||||
|
m_changeTextureHeight = height;
|
||||||
|
m_cs->lock();
|
||||||
|
m_cs->setSharedParam(1,eGUIHelperChangeTexture);
|
||||||
|
workerThreadWait();
|
||||||
|
}
|
||||||
|
|
||||||
double m_rgbaColor[4];
|
double m_rgbaColor[4];
|
||||||
int m_graphicsInstanceChangeColor;
|
int m_graphicsInstanceChangeColor;
|
||||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4])
|
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4])
|
||||||
@@ -1955,6 +1973,16 @@ void PhysicsServerExample::updateGraphics()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
case eGUIHelperChangeTexture:
|
||||||
|
{
|
||||||
|
m_multiThreadedHelper->m_childGuiHelper->changeTexture(
|
||||||
|
m_multiThreadedHelper->m_changeTextureUniqueId,
|
||||||
|
m_multiThreadedHelper->m_changeTextureRgbTexels,
|
||||||
|
m_multiThreadedHelper->m_changeTextureWidth,
|
||||||
|
m_multiThreadedHelper->m_changeTextureHeight);
|
||||||
|
m_multiThreadedHelper->mainThreadRelease();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
case eGUIHelperChangeGraphicsInstanceRGBAColor:
|
case eGUIHelperChangeGraphicsInstanceRGBAColor:
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -898,6 +898,12 @@ struct b3CreateMultiBodyResultArgs
|
|||||||
int m_bodyUniqueId;
|
int m_bodyUniqueId;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
struct b3ChangeTextureArgs
|
||||||
|
{
|
||||||
|
int m_textureUniqueId;
|
||||||
|
int m_width;
|
||||||
|
int m_height;
|
||||||
|
};
|
||||||
|
|
||||||
struct SharedMemoryCommand
|
struct SharedMemoryCommand
|
||||||
{
|
{
|
||||||
@@ -950,6 +956,7 @@ struct SharedMemoryCommand
|
|||||||
struct b3CreateVisualShapeArgs m_createVisualShapeArgs;
|
struct b3CreateVisualShapeArgs m_createVisualShapeArgs;
|
||||||
struct b3CreateMultiBodyArgs m_createMultiBodyArgs;
|
struct b3CreateMultiBodyArgs m_createMultiBodyArgs;
|
||||||
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs;
|
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs;
|
||||||
|
struct b3ChangeTextureArgs m_changeTextureArgs;
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -67,6 +67,7 @@ enum EnumSharedMemoryClientCommand
|
|||||||
CMD_CREATE_MULTI_BODY,
|
CMD_CREATE_MULTI_BODY,
|
||||||
CMD_REQUEST_COLLISION_INFO,
|
CMD_REQUEST_COLLISION_INFO,
|
||||||
CMD_REQUEST_MOUSE_EVENTS_DATA,
|
CMD_REQUEST_MOUSE_EVENTS_DATA,
|
||||||
|
CMD_CHANGE_TEXTURE,
|
||||||
//don't go beyond this command!
|
//don't go beyond this command!
|
||||||
CMD_MAX_CLIENT_COMMANDS,
|
CMD_MAX_CLIENT_COMMANDS,
|
||||||
|
|
||||||
@@ -161,6 +162,7 @@ enum EnumSharedMemoryServerStatus
|
|||||||
CMD_REQUEST_COLLISION_INFO_COMPLETED,
|
CMD_REQUEST_COLLISION_INFO_COMPLETED,
|
||||||
CMD_REQUEST_COLLISION_INFO_FAILED,
|
CMD_REQUEST_COLLISION_INFO_FAILED,
|
||||||
CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
|
CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
|
||||||
|
CMD_CHANGE_TEXTURE_COMMAND_FAILED,
|
||||||
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
||||||
CMD_MAX_SERVER_COMMANDS
|
CMD_MAX_SERVER_COMMANDS
|
||||||
};
|
};
|
||||||
|
|||||||
43
examples/pybullet/examples/changeTexture.py
Normal file
43
examples/pybullet/examples/changeTexture.py
Normal file
@@ -0,0 +1,43 @@
|
|||||||
|
import pybullet as p
|
||||||
|
import time
|
||||||
|
p.connect(p.GUI)
|
||||||
|
planeUidA = p.loadURDF("plane_transparent.urdf",[0,0,0])
|
||||||
|
planeUid = p.loadURDF("plane_transparent.urdf",[0,0,-1])
|
||||||
|
|
||||||
|
texUid = p.loadTexture("tex256.png")
|
||||||
|
|
||||||
|
p.changeVisualShape(planeUidA,-1,rgbaColor=[1,1,1,0.5])
|
||||||
|
p.changeVisualShape(planeUid,-1,rgbaColor=[1,1,1,0.5])
|
||||||
|
p.changeVisualShape(planeUid,-1, textureUniqueId = texUid)
|
||||||
|
|
||||||
|
width = 256
|
||||||
|
height = 256
|
||||||
|
pixels = [255]*width*height*3
|
||||||
|
colorR = 0
|
||||||
|
colorG = 0
|
||||||
|
colorB = 0
|
||||||
|
|
||||||
|
|
||||||
|
#p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
|
#p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
|
|
||||||
|
blue=0
|
||||||
|
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "renderbench.json")
|
||||||
|
for i in range (100000):
|
||||||
|
p.stepSimulation()
|
||||||
|
for i in range (width):
|
||||||
|
for j in range(height):
|
||||||
|
pixels[(i+j*width)*3+0]=i
|
||||||
|
pixels[(i+j*width)*3+1]=(j+blue)%256
|
||||||
|
pixels[(i+j*width)*3+2]=blue
|
||||||
|
blue=blue+1
|
||||||
|
p.changeTexture(texUid, pixels,width,height)
|
||||||
|
start = time.time()
|
||||||
|
p.getCameraImage(300,300,renderer=p.ER_BULLET_HARDWARE_OPENGL)
|
||||||
|
end = time.time()
|
||||||
|
print("rendering duraction")
|
||||||
|
print(end-start)
|
||||||
|
p.stopStateLogging(logId)
|
||||||
|
#p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
#p.configureDebugVisualizer(p.COV_ENABLE_GUI,1)
|
||||||
|
|
||||||
@@ -1433,7 +1433,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar
|
|||||||
int i;
|
int i;
|
||||||
for (i = 0; i < numControlledDofs; i++)
|
for (i = 0; i < numControlledDofs; i++)
|
||||||
{
|
{
|
||||||
int jointIndex = pybullet_internalGetFloatFromSequence(jointIndicesSeq, i);
|
int jointIndex = pybullet_internalGetIntFromSequence(jointIndicesSeq, i);
|
||||||
if ((jointIndex >= numJoints) || (jointIndex < 0))
|
if ((jointIndex >= numJoints) || (jointIndex < 0))
|
||||||
{
|
{
|
||||||
Py_DECREF(jointIndicesSeq);
|
Py_DECREF(jointIndicesSeq);
|
||||||
@@ -4551,6 +4551,75 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
|
|||||||
return Py_None;
|
return Py_None;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static PyObject* pybullet_changeTexture(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
|
{
|
||||||
|
b3SharedMemoryCommandHandle commandHandle = 0;
|
||||||
|
b3SharedMemoryStatusHandle statusHandle=0;
|
||||||
|
int statusType = -1;
|
||||||
|
int textureUniqueId = -1;
|
||||||
|
int physicsClientId = 0;
|
||||||
|
int width=-1;
|
||||||
|
int height=-1;
|
||||||
|
|
||||||
|
PyObject* pixelsObj = 0;
|
||||||
|
|
||||||
|
b3PhysicsClientHandle sm = 0;
|
||||||
|
static char* kwlist[] = {"textureUniqueId", "pixels", "width", "height", "physicsClientId", NULL};
|
||||||
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOii|i", kwlist, &textureUniqueId, &pixelsObj, &width, &height, &physicsClientId))
|
||||||
|
{
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
sm = getPhysicsClient(physicsClientId);
|
||||||
|
if (sm == 0)
|
||||||
|
{
|
||||||
|
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (textureUniqueId>=0 && width>=0 && height>=0 && pixelsObj)
|
||||||
|
{
|
||||||
|
PyObject* seqPixels = PySequence_Fast(pixelsObj, "expected a sequence");
|
||||||
|
PyObject* item;
|
||||||
|
int i;
|
||||||
|
int numPixels = width*height;
|
||||||
|
unsigned char* pixelBuffer = (char*) malloc (numPixels*3);
|
||||||
|
if (PyList_Check(seqPixels))
|
||||||
|
{
|
||||||
|
for (i=0;i<numPixels*3;i++)
|
||||||
|
{
|
||||||
|
item = PyList_GET_ITEM(seqPixels, i);
|
||||||
|
pixelBuffer[i] = PyLong_AsLong(item);
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
for (i=0;i<numPixels*3;i++)
|
||||||
|
{
|
||||||
|
item = PyTuple_GET_ITEM(seqPixels, i);
|
||||||
|
pixelBuffer[i] = PyLong_AsLong(item);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
commandHandle = b3CreateChangeTextureCommandInit(sm,textureUniqueId, width,height,pixelBuffer);
|
||||||
|
free(pixelBuffer);
|
||||||
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||||
|
statusType = b3GetStatusType(statusHandle);
|
||||||
|
if (statusType == CMD_CLIENT_COMMAND_COMPLETED)
|
||||||
|
{
|
||||||
|
Py_INCREF(Py_None);
|
||||||
|
return Py_None;
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
PyErr_SetString(SpamError, "Error processing changeTexture.");
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
PyErr_SetString(SpamError, "Error: invalid arguments in changeTexture.");
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject* keywds)
|
static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
{
|
{
|
||||||
const char* filename = 0;
|
const char* filename = 0;
|
||||||
@@ -7029,6 +7098,9 @@ static PyMethodDef SpamMethods[] = {
|
|||||||
{"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS | METH_KEYWORDS,
|
{"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS | METH_KEYWORDS,
|
||||||
"Load texture file."},
|
"Load texture file."},
|
||||||
|
|
||||||
|
{"changeTexture", (PyCFunction)pybullet_changeTexture, METH_VARARGS | METH_KEYWORDS,
|
||||||
|
"Change a texture file."},
|
||||||
|
|
||||||
{"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS,
|
{"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS,
|
||||||
"Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to "
|
"Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to "
|
||||||
"quaternion [x,y,z,w]"},
|
"quaternion [x,y,z,w]"},
|
||||||
|
|||||||
Reference in New Issue
Block a user