diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index fdb5bbe87..dee00ed27 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -256,8 +256,14 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) case CMD_LOAD_SDF: { + /* b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf");//kuka_iiwa/model.sdf"); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); + */ + b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "sphere_big.urdf"); + //setting the initial position, orientation and other arguments are optional + b3LoadUrdfCommandSetStartPosition(commandHandle,0.5,0.5,0.5); + b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_CAMERA_IMAGE_DATA: diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 58e164ca7..73d6935a4 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -34,6 +34,7 @@ subject to the following restrictions: #include "../Importers/ImportURDFDemo/UrdfParser.h" #include "../SharedMemory/SharedMemoryPublic.h"//for b3VisualShapeData #include "../TinyRenderer/model.h" +#include "../ThirdPartyLibs/stb_image/stb_image.h" enum MyFileType @@ -833,9 +834,14 @@ void TinyRendererVisualShapeConverter::resetAll() // Get shapeUniqueId from getVisualShapesData? void TinyRendererVisualShapeConverter::activateShapeTexture(int shapeUniqueId, int textureUniqueId) { + int width,height,n; + const char filename[] = "/Users/yunfeibai/Documents/dev/bullet-change-texture/bullet3/data/checker_huge.gif"; + unsigned char* image=0; + + image = stbi_load(filename, &width, &height, &n, 3); // Use shapeUniqueId? - int objectArrayIndex = 1; + int objectArrayIndex = 8; int objectIndex = 0; printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(objectArrayIndex); @@ -845,7 +851,8 @@ void TinyRendererVisualShapeConverter::activateShapeTexture(int shapeUniqueId, i unsigned char textureImage[3] = {255, 0, 0}; int textureWidth = 1; int textureHeight = 1; - ptr->m_renderObjects[objectIndex]->m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight); + //ptr->m_renderObjects[objectIndex]->m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight); + ptr->m_renderObjects[objectIndex]->m_model->setDiffuseTextureFromData(image,width,height); } diff --git a/examples/TinyRenderer/model.cpp b/examples/TinyRenderer/model.cpp index 7bbd5b357..f0ef25563 100644 --- a/examples/TinyRenderer/model.cpp +++ b/examples/TinyRenderer/model.cpp @@ -57,12 +57,12 @@ void Model::setDiffuseTextureFromData(unsigned char* textureImage,int textureWid for (int j=0;j