diff --git a/data/cube_no_friction.urdf b/data/cube_no_friction.urdf new file mode 100644 index 000000000..aef2bfa15 --- /dev/null +++ b/data/cube_no_friction.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/kiva_shelf/0_Bullet3Demo.txt b/data/kiva_shelf/0_Bullet3Demo.txt new file mode 100644 index 000000000..eb396d29f --- /dev/null +++ b/data/kiva_shelf/0_Bullet3Demo.txt @@ -0,0 +1,7 @@ +--start_demo_name=R2D2 Grasp +--mouse_move_multiplier=0.400000 +--mouse_wheel_multiplier=0.010000 +--background_color_red= 0.900000 +--background_color_green= 0.900000 +--background_color_blue= 1.000000 +--fixed_timestep= 0.000000 diff --git a/data/kiva_shelf/meshes/pod_lowres.stl b/data/kiva_shelf/meshes/pod_lowres.stl new file mode 100644 index 000000000..6e668f1d7 Binary files /dev/null and b/data/kiva_shelf/meshes/pod_lowres.stl differ diff --git a/data/kiva_shelf/model.sdf b/data/kiva_shelf/model.sdf new file mode 100644 index 000000000..b1f49e66b --- /dev/null +++ b/data/kiva_shelf/model.sdf @@ -0,0 +1,55 @@ + + + + 1 + 0 2 1.21 0 0 0 + + + 0.0 0.0 1.2045 0 0 0 + 76.26 + + 47 + -0.003456 + 0.001474 + 13.075 + -0.014439 + 47 + + + + + 0 0 0 1.5707 0 0 + + + meshes/pod_lowres.stl + + + + 0.9 0.8 0.5 1 + + + + + + 0 0 0 1.5707 0 0 + + + meshes/pod_lowres.stl + + + + + + 0.8 + 0.8 + 0.0 0.0 0.0 + 1.0 + 1.0 + + + + + + + + diff --git a/data/kuka_iiwa/model.sdf b/data/kuka_iiwa/model.sdf index 0df20cff7..3a962ee74 100644 --- a/data/kuka_iiwa/model.sdf +++ b/data/kuka_iiwa/model.sdf @@ -1,6 +1,7 @@ + 1 0 0 0 0 -0 0 @@ -34,7 +35,7 @@ 1 0 0 1 - 0 0 1 1 + 0.2 0.2 0.2 1 0.1 0.1 0.1 1 0 0 0 0 @@ -71,6 +72,12 @@ meshes/link_1.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -124,6 +131,12 @@ meshes/link_2.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -177,6 +190,12 @@ meshes/link_3.stl + + 1 0 0 1 + 1.0 0.42 0.04 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -230,6 +249,12 @@ meshes/link_4.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -283,6 +308,12 @@ meshes/link_5.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -336,6 +367,12 @@ meshes/link_6.stl + + 1 0 0 1 + 1.0 0.42 0.04 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -389,6 +426,12 @@ meshes/link_7.stl + + 1 0 0 1 + 0.2 0.2 0.2 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + diff --git a/data/plane.urdf b/data/plane.urdf new file mode 100644 index 000000000..57b746104 --- /dev/null +++ b/data/plane.urdf @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 16185efe4..5682275ce 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -248,7 +248,7 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1, "Physics Client (Direct)", "Create a physics client that can communicate with a physics server directly in-process.", PhysicsClientCreateFunc,eCLIENTEXAMPLE_DIRECT), ExampleEntry(1,"R2D2 Grasp","Load the R2D2 robot from URDF file and control it to grasp objects", R2D2GraspExampleCreateFunc, eROBOTIC_LEARN_GRASP), - ExampleEntry(1,"URDF Compliant Contact","Experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT), + ExampleEntry(1,"URDF Compliant Contact","Work-in-progress, experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT), diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 002a3cf93..64be1573b 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -225,6 +225,15 @@ bool UrdfParser::parseInertia(UrdfInertia& inertia, TiXmlElement* config, ErrorL { inertia.m_linkLocalFrame.setIdentity(); inertia.m_mass = 0.f; + if(m_parseSDF) + { + TiXmlElement* pose = config->FirstChildElement("pose"); + if (pose) + { + parseTransform(inertia.m_linkLocalFrame, pose,logger,m_parseSDF); + } + } + // Origin @@ -448,6 +457,15 @@ bool UrdfParser::parseCollision(UrdfCollision& collision, TiXmlElement* config, collision.m_linkLocalFrame.setIdentity(); + if(m_parseSDF) + { + TiXmlElement* pose = config->FirstChildElement("pose"); + if (pose) + { + parseTransform(collision.m_linkLocalFrame, pose,logger,m_parseSDF); + } + } + // Origin TiXmlElement *o = config->FirstChildElement("origin"); if (o) @@ -474,7 +492,15 @@ bool UrdfParser::parseCollision(UrdfCollision& collision, TiXmlElement* config, bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* config, ErrorLogger* logger) { visual.m_linkLocalFrame.setIdentity(); - + if(m_parseSDF) + { + TiXmlElement* pose = config->FirstChildElement("pose"); + if (pose) + { + parseTransform(visual.m_linkLocalFrame, pose,logger,m_parseSDF); + } + } + // Origin TiXmlElement *o = config->FirstChildElement("origin"); if (o) @@ -505,6 +531,8 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* { UrdfMaterial* matPtr = new UrdfMaterial; matPtr->m_name = "mat"; + if (name_char) + matPtr->m_name = name_char; TiXmlElement *diffuse = mat->FirstChildElement("diffuse"); if (diffuse) { std::string diffuseText = diffuse->GetText(); @@ -512,7 +540,7 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* parseVector4(rgba,diffuseText); matPtr->m_rgbaColor = rgba; model.m_materials.insert(matPtr->m_name.c_str(),matPtr); - visual.m_materialName = "mat"; + visual.m_materialName = matPtr->m_name; visual.m_hasLocalMaterial = true; } } @@ -670,6 +698,8 @@ bool UrdfParser::parseJointLimits(UrdfJoint& joint, TiXmlElement* config, ErrorL joint.m_upperLimit = 0.f; joint.m_effortLimit = 0.f; joint.m_velocityLimit = 0.f; + joint.m_jointDamping = 0.f; + joint.m_jointFriction = 0.f; if (m_parseSDF) { @@ -1281,15 +1311,22 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger) return false; } - TiXmlElement *world_xml = sdf_xml->FirstChildElement("world"); - if (!world_xml) - { - logger->reportError("expected a world element"); - return false; - } - + //apparently, SDF doesn't require a "world" element, optional? URDF does. + TiXmlElement *world_xml = sdf_xml->FirstChildElement("world"); + + TiXmlElement* robot_xml = 0; + + if (!world_xml) + { + logger->reportWarning("expected a world element, continuing without it."); + robot_xml = sdf_xml->FirstChildElement("model"); + } else + { + robot_xml = world_xml->FirstChildElement("model"); + } + // Get all model (robot) elements - for (TiXmlElement* robot_xml = world_xml->FirstChildElement("model"); robot_xml; robot_xml = robot_xml->NextSiblingElement("model")) + for (; robot_xml; robot_xml = robot_xml->NextSiblingElement("model")) { UrdfModel* localModel = new UrdfModel; m_tmpModels.push_back(localModel); diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 8e6dc6fb7..25f7e3e38 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -125,6 +125,15 @@ struct UrdfJoint double m_jointDamping; double m_jointFriction; + UrdfJoint() + :m_lowerLimit(0), + m_upperLimit(0), + m_effortLimit(0), + m_velocityLimit(0), + m_jointDamping(0), + m_jointFriction(0) + { + } }; struct UrdfModel diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index e20aed56b..e54d073cb 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -19,7 +19,7 @@ subject to the following restrictions: bool useShadowMap=true;//false;//true; int shadowMapWidth=4096;//8192; int shadowMapHeight=4096; -float shadowMapWorldSize=50; +float shadowMapWorldSize=25; #define MAX_POINTS_IN_BATCH 1024 #define MAX_LINES_IN_BATCH 1024 @@ -75,7 +75,7 @@ float shadowMapWorldSize=50; static InternalDataRenderer* sData2; GLint lineWidthRange[2]={1,1}; -static b3Vector3 gLightPos=b3MakeVector3(-5,200,-40); +static b3Vector3 gLightPos=b3MakeVector3(-5,12,-4); struct b3GraphicsInstance { diff --git a/examples/OpenGLWindow/Shaders/instancingPS.glsl b/examples/OpenGLWindow/Shaders/instancingPS.glsl index fd992e5a8..310f5fed4 100644 --- a/examples/OpenGLWindow/Shaders/instancingPS.glsl +++ b/examples/OpenGLWindow/Shaders/instancingPS.glsl @@ -25,7 +25,8 @@ void main(void) vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);//fragment.color; vec3 ct,cf; float intensity,at,af; - intensity = max(dot(lightDir,normalize(normal)),0); + + intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 ); cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient; af = 1.0; diff --git a/examples/OpenGLWindow/Shaders/instancingPS.h b/examples/OpenGLWindow/Shaders/instancingPS.h index a32e7b29c..8e2ed9f28 100644 --- a/examples/OpenGLWindow/Shaders/instancingPS.h +++ b/examples/OpenGLWindow/Shaders/instancingPS.h @@ -22,7 +22,8 @@ static const char* instancingFragmentShader= \ " vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);//fragment.color;\n" " vec3 ct,cf;\n" " float intensity,at,af;\n" -" intensity = max(dot(lightDir,normalize(normal)),0);\n" +" \n" +" intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );\n" " cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient;\n" " af = 1.0;\n" " \n" diff --git a/examples/OpenGLWindow/Shaders/instancingVS.glsl b/examples/OpenGLWindow/Shaders/instancingVS.glsl index 1663f3698..709c07a49 100644 --- a/examples/OpenGLWindow/Shaders/instancingVS.glsl +++ b/examples/OpenGLWindow/Shaders/instancingVS.glsl @@ -61,7 +61,7 @@ out vec3 lightDir,normal,ambient; void main(void) { vec4 q = instance_quaternion; - ambient = vec3(0.6,.6,0.6); + ambient = vec3(0.5,.5,0.5); vec4 worldNormal = (quatRotate3( vertexnormal,q)); normal = normalize(worldNormal).xyz; diff --git a/examples/OpenGLWindow/Shaders/instancingVS.h b/examples/OpenGLWindow/Shaders/instancingVS.h index 563d22127..8be2f548f 100644 --- a/examples/OpenGLWindow/Shaders/instancingVS.h +++ b/examples/OpenGLWindow/Shaders/instancingVS.h @@ -52,7 +52,7 @@ static const char* instancingVertexShader= \ "void main(void)\n" "{\n" " vec4 q = instance_quaternion;\n" -" ambient = vec3(0.6,.6,0.6);\n" +" ambient = vec3(0.5,.5,0.5);\n" " \n" " vec4 worldNormal = (quatRotate3( vertexnormal,q));\n" " normal = normalize(worldNormal).xyz;\n" diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl index cd780fbea..0902c5149 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl @@ -27,8 +27,7 @@ void main(void) vec3 ct,cf; float intensity,at,af; - intensity = clamp( dot( normalize(normal),lightDir ), 0,1 ); - + intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 ); af = 1.0; diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h index 0550ff58a..a9d53adb5 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h @@ -21,8 +21,7 @@ static const char* useShadowMapInstancingFragmentShader= \ " vec3 ct,cf;\n" " float intensity,at,af;\n" " \n" -" intensity = clamp( dot( normalize(normal),lightDir ), 0,1 );\n" -" \n" +" intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );\n" " \n" " af = 1.0;\n" " \n" diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl index 9de5c0aa5..222e73cfd 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl @@ -65,7 +65,7 @@ out vec3 lightDir,normal,ambient; void main(void) { vec4 q = instance_quaternion; - ambient = vec3(0.6,.6,0.6); + ambient = vec3(0.5,.5,0.5); vec4 worldNormal = (quatRotate3( vertexnormal,q)); diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h index e52ec62ee..a98e44f82 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h @@ -55,7 +55,7 @@ static const char* useShadowMapInstancingVertexShader= \ "void main(void)\n" "{\n" " vec4 q = instance_quaternion;\n" -" ambient = vec3(0.6,.6,0.6);\n" +" ambient = vec3(0.5,.5,0.5);\n" " \n" " vec4 worldNormal = (quatRotate3( vertexnormal,q));\n" " \n" diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index b0f007940..54a897af5 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -59,50 +59,89 @@ public: { bool connected = m_robotSim.connect(m_guiHelper); b3Printf("robotSim connected = %d",connected); - b3RobotSimLoadURDFArgs args(""); + if ((m_options & eROBOTIC_LEARN_GRASP)!=0) { - args.m_urdfFileName = "r2d2.urdf"; - args.m_startPosition.setValue(0,0,.5); - m_r2d2Index = m_robotSim.loadURDF(args); - int numJoints = m_robotSim.getNumJoints(m_r2d2Index); - b3Printf("numJoints = %d",numJoints); + { + b3RobotSimLoadFileArgs args(""); + args.m_fileName = "r2d2.urdf"; + args.m_startPosition.setValue(0,0,.5); + b3RobotSimLoadFileResults results; + if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) + { + int m_r2d2Index = results.m_uniqueObjectIds[0]; + int numJoints = m_robotSim.getNumJoints(m_r2d2Index); + b3Printf("numJoints = %d",numJoints); - for (int i=0;im_renderer && m_app->m_renderer->getActiveCamera()) { m_app->m_renderer->getActiveCamera()->setCameraDistance(dist); diff --git a/examples/RoboticsLearning/b3RobotSimAPI.cpp b/examples/RoboticsLearning/b3RobotSimAPI.cpp index 36df27411..235861913 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.cpp +++ b/examples/RoboticsLearning/b3RobotSimAPI.cpp @@ -598,36 +598,71 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const } } -int b3RobotSimAPI::loadURDF(const b3RobotSimLoadURDFArgs& args) +bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotSimLoadFileResults& results) { + bool statusOk = false; + int robotUniqueId = -1; b3Assert(m_data->m_connected); - + switch (args.m_fileType) { - b3SharedMemoryStatusHandle statusHandle; - int statusType; - b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(m_data->m_physicsClient, args.m_urdfFileName.c_str()); + case B3_URDF_FILE: + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(m_data->m_physicsClient, args.m_fileName.c_str()); - //setting the initial position, orientation and other arguments are optional + //setting the initial position, orientation and other arguments are optional - b3LoadUrdfCommandSetStartPosition(command, args.m_startPosition[0], - args.m_startPosition[1], - args.m_startPosition[2]); - b3LoadUrdfCommandSetStartOrientation(command,args.m_startOrientation[0] - ,args.m_startOrientation[1] - ,args.m_startOrientation[2] - ,args.m_startOrientation[3]); - if (args.m_forceOverrideFixedBase) - { - b3LoadUrdfCommandSetUseFixedBase(command,true); - } - statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); + b3LoadUrdfCommandSetStartPosition(command, args.m_startPosition[0], + args.m_startPosition[1], + args.m_startPosition[2]); + b3LoadUrdfCommandSetStartOrientation(command,args.m_startOrientation[0] + ,args.m_startOrientation[1] + ,args.m_startOrientation[2] + ,args.m_startOrientation[3]); + if (args.m_forceOverrideFixedBase) + { + b3LoadUrdfCommandSetUseFixedBase(command,true); + } + statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); + statusType = b3GetStatusType(statusHandle); + b3Assert(statusType==CMD_URDF_LOADING_COMPLETED); + robotUniqueId = b3GetStatusBodyIndex(statusHandle); + results.m_uniqueObjectIds.push_back(robotUniqueId); + statusOk = true; + break; + } + case B3_SDF_FILE: + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(m_data->m_physicsClient, args.m_fileName.c_str()); + statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); statusType = b3GetStatusType(statusHandle); - b3Assert(statusType==CMD_URDF_LOADING_COMPLETED); - robotUniqueId = b3GetStatusBodyIndex(statusHandle); - } + b3Assert(statusType == CMD_SDF_LOADING_COMPLETED); + if (statusType == CMD_SDF_LOADING_COMPLETED) + { + int numBodies = b3GetStatusBodyIndices(statusHandle, 0,0); + if (numBodies) + { + results.m_uniqueObjectIds.resize(numBodies); + int numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size()); - return robotUniqueId; + } + statusOk = true; + } + + break; + } + default: + { + b3Warning("Unknown file type in b3RobotSimAPI::loadFile"); + } + + } + + return statusOk; } bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper) diff --git a/examples/RoboticsLearning/b3RobotSimAPI.h b/examples/RoboticsLearning/b3RobotSimAPI.h index 35b56c67f..61320553f 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.h +++ b/examples/RoboticsLearning/b3RobotSimAPI.h @@ -6,22 +6,40 @@ #include "../SharedMemory/SharedMemoryPublic.h" #include "Bullet3Common/b3Vector3.h" #include "Bullet3Common/b3Quaternion.h" +#include "Bullet3Common/b3AlignedObjectArray.h" + #include - -struct b3RobotSimLoadURDFArgs +enum b3RigidSimFileType { - std::string m_urdfFileName; + B3_URDF_FILE=1, + B3_SDF_FILE, + B3_AUTO_DETECT_FILE//todo based on extension +}; + +struct b3RobotSimLoadFileArgs +{ + std::string m_fileName; b3Vector3 m_startPosition; b3Quaternion m_startOrientation; bool m_forceOverrideFixedBase; + int m_fileType; - b3RobotSimLoadURDFArgs(const std::string& urdfFileName) - :m_urdfFileName(urdfFileName), + b3RobotSimLoadFileArgs(const std::string& fileName) + :m_fileName(fileName), m_startPosition(b3MakeVector3(0,0,0)), m_startOrientation(b3Quaternion(0,0,0,1)), - m_forceOverrideFixedBase(false) + m_forceOverrideFixedBase(false), + m_fileType(B3_URDF_FILE) + { + } +}; + +struct b3RobotSimLoadFileResults +{ + b3AlignedObjectArray m_uniqueObjectIds; + b3RobotSimLoadFileResults() { } }; @@ -63,7 +81,7 @@ public: bool connect(struct GUIHelperInterface* guiHelper); void disconnect(); - int loadURDF(const struct b3RobotSimLoadURDFArgs& args); + bool loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotSimLoadFileResults& results=b3RobotSimLoadFileResults()); int getNumJoints(int bodyUniqueId) const; diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 2b1401a0f..d5b50d2ba 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -33,7 +33,7 @@ #define MAX_SDF_FILENAME_LENGTH 1024 #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH #define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM -#define MAX_SDF_BODIES 1024 +#define MAX_SDF_BODIES 500 struct TmpFloat3 { diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index aebf0440e..650948a1a 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -138,6 +138,7 @@ void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVerti */ } + m_model->reserveMemory(numVertices,numIndices); for (int i=0;iaddVertex(vertices[i*9], diff --git a/examples/TinyRenderer/model.cpp b/examples/TinyRenderer/model.cpp index f7a0bea75..8864d0a2f 100644 --- a/examples/TinyRenderer/model.cpp +++ b/examples/TinyRenderer/model.cpp @@ -76,6 +76,14 @@ void Model::loadDiffuseTexture(const char* relativeFileName) diffusemap_.read_tga_file(relativeFileName); } +void Model::reserveMemory(int numVertices, int numIndices) +{ + verts_.reserve(numVertices); + norms_.reserve(numVertices); + uv_.reserve(numVertices); + faces_.reserve(numIndices); +} + void Model::addVertex(float x,float y,float z, float normalX, float normalY, float normalZ, float u, float v) { verts_.push_back(Vec3f(x,y,z)); diff --git a/examples/TinyRenderer/model.h b/examples/TinyRenderer/model.h index aadb9291f..6cd9e383b 100644 --- a/examples/TinyRenderer/model.h +++ b/examples/TinyRenderer/model.h @@ -32,6 +32,7 @@ public: } void loadDiffuseTexture(const char* relativeFileName); void setDiffuseTextureFromData(unsigned char* textureImage,int textureWidth,int textureHeight); + void reserveMemory(int numVertices, int numIndices); void addVertex(float x,float y,float z, float normalX, float normalY, float normalZ, float u, float v); void addTriangle(int vertexposIndex0, int normalIndex0, int uvIndex0, int vertexposIndex1, int normalIndex1, int uvIndex1,