diff --git a/Extras/InverseDynamics/btMultiBodyFromURDF.hpp b/Extras/InverseDynamics/btMultiBodyFromURDF.hpp index 978bad743..3e5f43978 100644 --- a/Extras/InverseDynamics/btMultiBodyFromURDF.hpp +++ b/Extras/InverseDynamics/btMultiBodyFromURDF.hpp @@ -11,6 +11,7 @@ #include "../Importers/ImportURDFDemo/URDF2Bullet.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" #include "../Importers/ImportURDFDemo/URDF2Bullet.h" +#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h" /// Create a btMultiBody model from URDF. /// This is adapted from Bullet URDF loader example @@ -44,7 +45,8 @@ public: void init() { this->createEmptyDynamicsWorld(); m_dynamicsWorld->setGravity(m_gravity); - BulletURDFImporter urdf_importer(&m_nogfx); + DefaultVisualShapeConverter visualConverter(&m_nogfx); + BulletURDFImporter urdf_importer(&m_nogfx, &visualConverter); URDFImporterInterface &u2b(urdf_importer); bool loadOk = u2b.loadURDF(m_filename.c_str(), m_base_fixed); diff --git a/data/kuka_iiwa/model.urdf b/data/kuka_iiwa/model.urdf index 0b290946a..56123c36d 100644 --- a/data/kuka_iiwa/model.urdf +++ b/data/kuka_iiwa/model.urdf @@ -47,6 +47,10 @@ + + + + @@ -97,7 +101,7 @@ - + @@ -126,7 +130,7 @@ - + @@ -184,7 +188,7 @@ - + @@ -213,7 +217,7 @@ - + diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 7dc6326b6..8d27fd502 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -246,6 +246,8 @@ SET(BulletExampleBrowser_SRCS ../Importers/ImportURDFDemo/urdfStringSplit.h ../Importers/ImportURDFDemo/BulletUrdfImporter.cpp ../Importers/ImportURDFDemo/BulletUrdfImporter.h + ../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp + ../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h ../VoronoiFracture/VoronoiFractureDemo.cpp ../VoronoiFracture/VoronoiFractureDemo.h ../VoronoiFracture/btConvexConvexMprAlgorithm.cpp diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index baf20915e..ae90f8d0b 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -238,8 +238,6 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli { gfxVertices[i].uv[j] = 0.5;//we don't have UV info... } - - } } diff --git a/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp b/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp index deabf1dac..f8e61c032 100644 --- a/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp +++ b/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp @@ -12,7 +12,7 @@ #include "../../Utils/b3ResourcePath.h" #include "../ImportURDFDemo/BulletUrdfImporter.h" - +#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h" #include "../ImportURDFDemo/URDF2Bullet.h" @@ -203,7 +203,8 @@ void ImportSDFSetup::initPhysics() m_dynamicsWorld->setGravity(gravity); - BulletURDFImporter u2b(m_guiHelper); + DefaultVisualShapeConverter visualConverter(m_guiHelper); + BulletURDFImporter u2b(m_guiHelper, &visualConverter); bool loadOk = u2b.loadSDF(m_fileName); diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index b409551f3..d0238abea 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -37,8 +37,10 @@ struct BulletURDFInternalData UrdfParser m_urdfParser; struct GUIHelperInterface* m_guiHelper; char m_pathPrefix[1024]; - btHashMap m_linkColors; + btAlignedObjectArray m_allocatedCollisionShapes; + + LinkVisualShapesConverter* m_customVisualShapesConverter; }; @@ -57,13 +59,13 @@ enum MyFileType -BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper) +BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter) { m_data = new BulletURDFInternalData; m_data->m_guiHelper = helper; m_data->m_pathPrefix[0]=0; - + m_data->m_customVisualShapesConverter = customConverter; } @@ -98,7 +100,6 @@ struct BulletErrorLogger : public ErrorLogger bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) { - m_data->m_linkColors.clear(); //int argc=0; @@ -153,9 +154,6 @@ void BulletURDFImporter::activateModel(int modelIndex) bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase) { - m_data->m_linkColors.clear(); - - //int argc=0; char relativeFileName[1024]; @@ -236,11 +234,9 @@ void BulletURDFImporter::getLinkChildIndices(int linkIndex, btAlignedObjectArray bool BulletURDFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const { - btVector4* rgbaPtr = m_data->m_linkColors[linkIndex]; - if (rgbaPtr) + if (m_data->m_customVisualShapesConverter) { - colorRGBA = *rgbaPtr; - return true; + return m_data->m_customVisualShapesConverter->getLinkColor(linkIndex, colorRGBA); } return false; } @@ -339,327 +335,6 @@ bool BulletURDFImporter::getRootTransformInWorld(btTransform& rootTransformInWor return true; } -void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut) -{ - - - GLInstanceGraphicsShape* glmesh = 0; - - btConvexShape* convexColShape = 0; - - switch (visual->m_geometry.m_type) - { - case URDF_GEOM_CYLINDER: - { - btAlignedObjectArray vertices; - - //int numVerts = sizeof(barrel_vertices)/(9*sizeof(float)); - int numSteps = 32; - for (int i = 0; im_geometry.m_cylinderRadius; - btScalar cylLength = visual->m_geometry.m_cylinderLength; - - btVector3 vert(cylRadius*btSin(SIMD_2_PI*(float(i) / numSteps)), cylRadius*btCos(SIMD_2_PI*(float(i) / numSteps)), cylLength / 2.); - vertices.push_back(vert); - vert[2] = -cylLength / 2.; - vertices.push_back(vert); - } - - btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); - cylZShape->setMargin(0.001); - convexColShape = cylZShape; - break; - } - case URDF_GEOM_BOX: - { - - btVector3 extents = visual->m_geometry.m_boxSize; - - btBoxShape* boxShape = new btBoxShape(extents*0.5f); - //btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5); - convexColShape = boxShape; - convexColShape->setMargin(0.001); - break; - } - case URDF_GEOM_SPHERE: - { - btScalar radius = visual->m_geometry.m_sphereRadius; - btSphereShape* sphereShape = new btSphereShape(radius); - convexColShape = sphereShape; - convexColShape->setMargin(0.001); - break; - - break; - } - case URDF_GEOM_MESH: - { - if (visual->m_name.length()) - { - //b3Printf("visual->name=%s\n", visual->m_name.c_str()); - } - if (1)//visual->m_geometry) - { - if (visual->m_geometry.m_meshFileName.length()) - { - const char* filename = visual->m_geometry.m_meshFileName.c_str(); - //b3Printf("mesh->filename=%s\n", filename); - char fullPath[1024]; - int fileType = 0; - - char tmpPathPrefix[1024]; - std::string xml_string; - int maxPathLen = 1024; - b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen); - - char visualPathPrefix[1024]; - sprintf(visualPathPrefix,"%s%s",urdfPathPrefix,tmpPathPrefix); - - - sprintf(fullPath, "%s%s", urdfPathPrefix, filename); - b3FileUtils::toLower(fullPath); - if (strstr(fullPath, ".dae")) - { - fileType = FILE_COLLADA; - } - if (strstr(fullPath, ".stl")) - { - fileType = FILE_STL; - } - if (strstr(fullPath,".obj")) - { - fileType = FILE_OBJ; - } - - - sprintf(fullPath, "%s%s", urdfPathPrefix, filename); - FILE* f = fopen(fullPath, "rb"); - if (f) - { - fclose(f); - - - - switch (fileType) - { - case FILE_OBJ: - { - glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); - break; - } - - case FILE_STL: - { - glmesh = LoadMeshFromSTL(fullPath); - break; - } - case FILE_COLLADA: - { - - btAlignedObjectArray visualShapes; - btAlignedObjectArray visualShapeInstances; - btTransform upAxisTrans; upAxisTrans.setIdentity(); - float unitMeterScaling = 1; - int upAxis = 2; - - LoadMeshFromCollada(fullPath, - visualShapes, - visualShapeInstances, - upAxisTrans, - unitMeterScaling, - upAxis); - - glmesh = new GLInstanceGraphicsShape; - // int index = 0; - glmesh->m_indices = new b3AlignedObjectArray(); - glmesh->m_vertices = new b3AlignedObjectArray(); - - for (int i = 0; im_shapeIndex]; - - b3AlignedObjectArray verts; - verts.resize(gfxShape->m_vertices->size()); - - int baseIndex = glmesh->m_vertices->size(); - - for (int i = 0; im_vertices->size(); i++) - { - verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; - verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; - verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; - verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; - verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; - verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; - verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; - verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; - verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; - - } - - int curNumIndices = glmesh->m_indices->size(); - int additionalIndices = gfxShape->m_indices->size(); - glmesh->m_indices->resize(curNumIndices + additionalIndices); - for (int k = 0; km_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex; - } - - //compensate upAxisTrans and unitMeterScaling here - btMatrix4x4 upAxisMat; - upAxisMat.setIdentity(); -// upAxisMat.setPureRotation(upAxisTrans.getRotation()); - btMatrix4x4 unitMeterScalingMat; - unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling)); - btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform; - //btMatrix4x4 worldMat = instance->m_worldTransform; - int curNumVertices = glmesh->m_vertices->size(); - int additionalVertices = verts.size(); - glmesh->m_vertices->reserve(curNumVertices + additionalVertices); - - for (int v = 0; vm_vertices->push_back(verts[v]); - } - } - glmesh->m_numIndices = glmesh->m_indices->size(); - glmesh->m_numvertices = glmesh->m_vertices->size(); - //glmesh = LoadMeshFromCollada(fullPath); - - break; - } - default: - { - b3Warning("Error: unsupported file type for Visual mesh: %s\n", fullPath); - btAssert(0); - } - } - - - if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices>0)) - { - //apply the geometry scaling - for (int i=0;im_vertices->size();i++) - { - glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0]; - glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1]; - glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2]; - } - - } - else - { - b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath); - } - - } - else - { - b3Warning("mesh geometry not found %s\n", fullPath); - } - - - } - } - - - break; - } - default: - { - b3Warning("Error: unknown visual geometry type\n"); - } - } - - //if we have a convex, tesselate into localVertices/localIndices - if ((glmesh==0) && convexColShape) - { - btShapeHull* hull = new btShapeHull(convexColShape); - hull->buildHull(0.0); - { - // int strideInBytes = 9*sizeof(float); - int numVertices = hull->numVertices(); - int numIndices = hull->numIndices(); - - - glmesh = new GLInstanceGraphicsShape; - // int index = 0; - glmesh->m_indices = new b3AlignedObjectArray(); - glmesh->m_vertices = new b3AlignedObjectArray(); - - - for (int i = 0; i < numVertices; i++) - { - GLInstanceVertex vtx; - btVector3 pos = hull->getVertexPointer()[i]; - vtx.xyzw[0] = pos.x(); - vtx.xyzw[1] = pos.y(); - vtx.xyzw[2] = pos.z(); - vtx.xyzw[3] = 1.f; - pos.normalize(); - vtx.normal[0] = pos.x(); - vtx.normal[1] = pos.y(); - vtx.normal[2] = pos.z(); - vtx.uv[0] = 0.5f; - vtx.uv[1] = 0.5f; - glmesh->m_vertices->push_back(vtx); - } - - btAlignedObjectArray indices; - for (int i = 0; i < numIndices; i++) - { - glmesh->m_indices->push_back(hull->getIndexPointer()[i]); - } - - glmesh->m_numvertices = glmesh->m_vertices->size(); - glmesh->m_numIndices = glmesh->m_indices->size(); - } - delete hull; - delete convexColShape; - convexColShape = 0; - - } - - if (glmesh && glmesh->m_numIndices>0 && glmesh->m_numvertices >0) - { - - int baseIndex = verticesOut.size(); - - - - for (int i = 0; i < glmesh->m_indices->size(); i++) - { - indicesOut.push_back(glmesh->m_indices->at(i) + baseIndex); - } - - for (int i = 0; i < glmesh->m_vertices->size(); i++) - { - GLInstanceVertex& v = glmesh->m_vertices->at(i); - btVector3 vert(v.xyzw[0],v.xyzw[1],v.xyzw[2]); - btVector3 vt = visualTransform*vert; - v.xyzw[0] = vt[0]; - v.xyzw[1] = vt[1]; - v.xyzw[2] = vt[2]; - btVector3 triNormal(v.normal[0],v.normal[1],v.normal[2]); - triNormal = visualTransform.getBasis()*triNormal; - v.normal[0] = triNormal[0]; - v.normal[1] = triNormal[1]; - v.normal[2] = triNormal[2]; - verticesOut.push_back(v); - } - } - delete glmesh; - -} - - btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, const char* urdfPathPrefix) @@ -910,61 +585,17 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co return shape; } - - - -int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const +int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionShape* colShape) const { - btAlignedObjectArray vertices; - btAlignedObjectArray indices; - btTransform startTrans; startTrans.setIdentity(); - int graphicsIndex = -1; -#if USE_ROS_URDF_PARSER - for (int v = 0; v < (int)m_data->m_links[linkIndex]->visual_array.size(); v++) - { - const Visual* vis = m_data->m_links[linkIndex]->visual_array[v].get(); - btVector3 childPos(vis->origin.position.x, vis->origin.position.y, vis->origin.position.z); - btQuaternion childOrn(vis->origin.rotation.x, vis->origin.rotation.y, vis->origin.rotation.z, vis->origin.rotation.w); - btTransform childTrans; - childTrans.setOrigin(childPos); - childTrans.setRotation(childOrn); - - convertURDFToVisualShape(vis, pathPrefix, inertialFrame.inverse()*childTrans, vertices, indices); - - } -#else - const UrdfModel& model = m_data->m_urdfParser.getModel(); - UrdfLink* const* linkPtr = model.m_links.getAtIndex(linkIndex); - if (linkPtr) - { + int graphicsIndex = -1; - const UrdfLink* link = *linkPtr; - - for (int v = 0; v < link->m_visualArray.size();v++) - { - const UrdfVisual& vis = link->m_visualArray[v]; - btTransform childTrans = vis.m_linkLocalFrame; - btHashString matName(vis.m_materialName.c_str()); - UrdfMaterial *const * matPtr = model.m_materials[matName]; - if (matPtr) - { - UrdfMaterial *const mat = *matPtr; - //printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]); - m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor); - } - convertURDFToVisualShape(&vis, pathPrefix, inertialFrame.inverse()*childTrans, vertices, indices); - - - } + if (m_data->m_customVisualShapesConverter) + { + const UrdfModel& model = m_data->m_urdfParser.getModel(); + graphicsIndex = m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, model, colShape); } -#endif - if (vertices.size() && indices.size()) - { - graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); - } - return graphicsIndex; - + } int BulletURDFImporter::getNumAllocatedCollisionShapes() const @@ -985,25 +616,6 @@ btCollisionShape* BulletURDFImporter::getAllocatedCollisionShape(int index) m_data->m_allocatedCollisionShapes.push_back(compoundShape); compoundShape->setMargin(0.001); -#if USE_ROS_URDF_PARSER - for (int v=0;v<(int)m_data->m_links[linkIndex]->collision_array.size();v++) - { - const Collision* col = m_data->m_links[linkIndex]->collision_array[v].get(); - btCollisionShape* childShape = convertURDFToCollisionShape(col ,pathPrefix); - - if (childShape) - { - btVector3 childPos(col->origin.position.x, col->origin.position.y, col->origin.position.z); - btQuaternion childOrn(col->origin.rotation.x, col->origin.rotation.y, col->origin.rotation.z, col->origin.rotation.w); - btTransform childTrans; - childTrans.setOrigin(childPos); - childTrans.setRotation(childOrn); - compoundShape->addChildShape(localInertiaFrame.inverse()*childTrans,childShape); - - } - } -#else - UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex); btAssert(linkPtr); if (linkPtr) @@ -1025,8 +637,6 @@ btCollisionShape* BulletURDFImporter::getAllocatedCollisionShape(int index) } } } - -#endif return compoundShape; } diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h index 5e1437158..469c5a43c 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h @@ -3,6 +3,8 @@ #include "URDFImporterInterface.h" +#include "LinkVisualShapesConverter.h" + ///BulletURDFImporter can deal with URDF and (soon) SDF files class BulletURDFImporter : public URDFImporterInterface @@ -13,7 +15,7 @@ class BulletURDFImporter : public URDFImporterInterface public: - BulletURDFImporter(struct GUIHelperInterface* guiHelper); + BulletURDFImporter(struct GUIHelperInterface* guiHelper, LinkVisualShapesConverter* customConverter); virtual ~BulletURDFImporter(); @@ -44,7 +46,7 @@ public: virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const; - virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const; + virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionShape* colShape) const; ///todo(erwincoumans) refactor this convertLinkCollisionShapes/memory allocation diff --git a/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp b/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp new file mode 100644 index 000000000..594a8bd5c --- /dev/null +++ b/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp @@ -0,0 +1,436 @@ +/* Copyright (C) 2016 Google + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + + +#include "DefaultVisualShapeConverter.h" + + + +#include "URDFImporterInterface.h" +#include "btBulletCollisionCommon.h" +#include "../ImportObjDemo/LoadMeshFromObj.h" +#include "../ImportSTLDemo/LoadMeshFromSTL.h" +#include "../ImportColladaDemo/LoadMeshFromCollada.h" +#include "BulletCollision/CollisionShapes/btShapeHull.h"//to create a tesselation of a generic btConvexShape +#include "../../CommonInterfaces/CommonGUIHelperInterface.h" +#include "Bullet3Common/b3FileUtils.h" +#include +#include "../../Utils/b3ResourcePath.h" + + + +#include +#include +#include "UrdfParser.h" + + +enum MyFileType +{ + MY_FILE_STL=1, + MY_FILE_COLLADA=2, + MY_FILE_OBJ=3, +}; + + +struct DefaultVisualShapeConverterInternalData +{ + struct GUIHelperInterface* m_guiHelper; + //char m_pathPrefix[1024]; + btHashMap m_linkColors; +}; + + +DefaultVisualShapeConverter::DefaultVisualShapeConverter(struct GUIHelperInterface* guiHelper) +{ + m_data = new DefaultVisualShapeConverterInternalData(); + m_data->m_guiHelper = guiHelper; +} +DefaultVisualShapeConverter::~DefaultVisualShapeConverter() +{ + delete m_data; +} + + + + +void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut) +{ + + + GLInstanceGraphicsShape* glmesh = 0; + + btConvexShape* convexColShape = 0; + + switch (visual->m_geometry.m_type) + { + case URDF_GEOM_CYLINDER: + { + btAlignedObjectArray vertices; + + //int numVerts = sizeof(barrel_vertices)/(9*sizeof(float)); + int numSteps = 32; + for (int i = 0; im_geometry.m_cylinderRadius; + btScalar cylLength = visual->m_geometry.m_cylinderLength; + + btVector3 vert(cylRadius*btSin(SIMD_2_PI*(float(i) / numSteps)), cylRadius*btCos(SIMD_2_PI*(float(i) / numSteps)), cylLength / 2.); + vertices.push_back(vert); + vert[2] = -cylLength / 2.; + vertices.push_back(vert); + } + + btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); + cylZShape->setMargin(0.001); + convexColShape = cylZShape; + break; + } + case URDF_GEOM_BOX: + { + + btVector3 extents = visual->m_geometry.m_boxSize; + + btBoxShape* boxShape = new btBoxShape(extents*0.5f); + //btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5); + convexColShape = boxShape; + convexColShape->setMargin(0.001); + break; + } + case URDF_GEOM_SPHERE: + { + btScalar radius = visual->m_geometry.m_sphereRadius; + btSphereShape* sphereShape = new btSphereShape(radius); + convexColShape = sphereShape; + convexColShape->setMargin(0.001); + break; + + break; + } + case URDF_GEOM_MESH: + { + if (visual->m_name.length()) + { + //b3Printf("visual->name=%s\n", visual->m_name.c_str()); + } + if (1)//visual->m_geometry) + { + if (visual->m_geometry.m_meshFileName.length()) + { + const char* filename = visual->m_geometry.m_meshFileName.c_str(); + //b3Printf("mesh->filename=%s\n", filename); + char fullPath[1024]; + int fileType = 0; + + char tmpPathPrefix[1024]; + std::string xml_string; + int maxPathLen = 1024; + b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen); + + char visualPathPrefix[1024]; + sprintf(visualPathPrefix,"%s%s",urdfPathPrefix,tmpPathPrefix); + + + sprintf(fullPath, "%s%s", urdfPathPrefix, filename); + b3FileUtils::toLower(fullPath); + if (strstr(fullPath, ".dae")) + { + fileType = MY_FILE_COLLADA; + } + if (strstr(fullPath, ".stl")) + { + fileType = MY_FILE_STL; + } + if (strstr(fullPath,".obj")) + { + fileType = MY_FILE_OBJ; + } + + + sprintf(fullPath, "%s%s", urdfPathPrefix, filename); + FILE* f = fopen(fullPath, "rb"); + if (f) + { + fclose(f); + + + + switch (fileType) + { + case MY_FILE_OBJ: + { + glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); + break; + } + + case MY_FILE_STL: + { + glmesh = LoadMeshFromSTL(fullPath); + break; + } + case MY_FILE_COLLADA: + { + + btAlignedObjectArray visualShapes; + btAlignedObjectArray visualShapeInstances; + btTransform upAxisTrans; upAxisTrans.setIdentity(); + float unitMeterScaling = 1; + int upAxis = 2; + + LoadMeshFromCollada(fullPath, + visualShapes, + visualShapeInstances, + upAxisTrans, + unitMeterScaling, + upAxis); + + glmesh = new GLInstanceGraphicsShape; + // int index = 0; + glmesh->m_indices = new b3AlignedObjectArray(); + glmesh->m_vertices = new b3AlignedObjectArray(); + + for (int i = 0; im_shapeIndex]; + + b3AlignedObjectArray verts; + verts.resize(gfxShape->m_vertices->size()); + + int baseIndex = glmesh->m_vertices->size(); + + for (int i = 0; im_vertices->size(); i++) + { + verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; + verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; + verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; + verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; + verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; + verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; + verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; + verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; + verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; + + } + + int curNumIndices = glmesh->m_indices->size(); + int additionalIndices = gfxShape->m_indices->size(); + glmesh->m_indices->resize(curNumIndices + additionalIndices); + for (int k = 0; km_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex; + } + + //compensate upAxisTrans and unitMeterScaling here + btMatrix4x4 upAxisMat; + upAxisMat.setIdentity(); +// upAxisMat.setPureRotation(upAxisTrans.getRotation()); + btMatrix4x4 unitMeterScalingMat; + unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling)); + btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform; + //btMatrix4x4 worldMat = instance->m_worldTransform; + int curNumVertices = glmesh->m_vertices->size(); + int additionalVertices = verts.size(); + glmesh->m_vertices->reserve(curNumVertices + additionalVertices); + + for (int v = 0; vm_vertices->push_back(verts[v]); + } + } + glmesh->m_numIndices = glmesh->m_indices->size(); + glmesh->m_numvertices = glmesh->m_vertices->size(); + //glmesh = LoadMeshFromCollada(fullPath); + + break; + } + default: + { + b3Warning("Error: unsupported file type for Visual mesh: %s\n", fullPath); + btAssert(0); + } + } + + + if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices>0)) + { + //apply the geometry scaling + for (int i=0;im_vertices->size();i++) + { + glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0]; + glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1]; + glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2]; + } + + } + else + { + b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath); + } + + } + else + { + b3Warning("mesh geometry not found %s\n", fullPath); + } + + + } + } + + + break; + } + default: + { + b3Warning("Error: unknown visual geometry type\n"); + } + } + + //if we have a convex, tesselate into localVertices/localIndices + if ((glmesh==0) && convexColShape) + { + btShapeHull* hull = new btShapeHull(convexColShape); + hull->buildHull(0.0); + { + // int strideInBytes = 9*sizeof(float); + int numVertices = hull->numVertices(); + int numIndices = hull->numIndices(); + + + glmesh = new GLInstanceGraphicsShape; + // int index = 0; + glmesh->m_indices = new b3AlignedObjectArray(); + glmesh->m_vertices = new b3AlignedObjectArray(); + + + for (int i = 0; i < numVertices; i++) + { + GLInstanceVertex vtx; + btVector3 pos = hull->getVertexPointer()[i]; + vtx.xyzw[0] = pos.x(); + vtx.xyzw[1] = pos.y(); + vtx.xyzw[2] = pos.z(); + vtx.xyzw[3] = 1.f; + pos.normalize(); + vtx.normal[0] = pos.x(); + vtx.normal[1] = pos.y(); + vtx.normal[2] = pos.z(); + vtx.uv[0] = 0.5f; + vtx.uv[1] = 0.5f; + glmesh->m_vertices->push_back(vtx); + } + + btAlignedObjectArray indices; + for (int i = 0; i < numIndices; i++) + { + glmesh->m_indices->push_back(hull->getIndexPointer()[i]); + } + + glmesh->m_numvertices = glmesh->m_vertices->size(); + glmesh->m_numIndices = glmesh->m_indices->size(); + } + delete hull; + delete convexColShape; + convexColShape = 0; + + } + + if (glmesh && glmesh->m_numIndices>0 && glmesh->m_numvertices >0) + { + + int baseIndex = verticesOut.size(); + + + + for (int i = 0; i < glmesh->m_indices->size(); i++) + { + indicesOut.push_back(glmesh->m_indices->at(i) + baseIndex); + } + + for (int i = 0; i < glmesh->m_vertices->size(); i++) + { + GLInstanceVertex& v = glmesh->m_vertices->at(i); + btVector3 vert(v.xyzw[0],v.xyzw[1],v.xyzw[2]); + btVector3 vt = visualTransform*vert; + v.xyzw[0] = vt[0]; + v.xyzw[1] = vt[1]; + v.xyzw[2] = vt[2]; + btVector3 triNormal(v.normal[0],v.normal[1],v.normal[2]); + triNormal = visualTransform.getBasis()*triNormal; + v.normal[0] = triNormal[0]; + v.normal[1] = triNormal[1]; + v.normal[2] = triNormal[2]; + verticesOut.push_back(v); + } + } + delete glmesh; + +} + + + +int DefaultVisualShapeConverter::convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionShape* colShape) +{ + btAlignedObjectArray vertices; + btAlignedObjectArray indices; + btTransform startTrans; startTrans.setIdentity(); + int graphicsIndex = -1; + + UrdfLink* const* linkPtr = model.m_links.getAtIndex(linkIndex); + if (linkPtr) + { + + const UrdfLink* link = *linkPtr; + + for (int v = 0; v < link->m_visualArray.size();v++) + { + const UrdfVisual& vis = link->m_visualArray[v]; + btTransform childTrans = vis.m_linkLocalFrame; + btHashString matName(vis.m_materialName.c_str()); + UrdfMaterial *const * matPtr = model.m_materials[matName]; + if (matPtr) + { + UrdfMaterial *const mat = *matPtr; + //printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]); + m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor); + } + convertURDFToVisualShape(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices); + + + } + } + if (vertices.size() && indices.size()) + { + graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); + } + return graphicsIndex; +} + +bool DefaultVisualShapeConverter::getLinkColor(int linkIndex, btVector4& colorRGBA) const +{ + const btVector4* rgbaPtr = m_data->m_linkColors[linkIndex]; + if (rgbaPtr) + { + colorRGBA = *rgbaPtr; + return true; + } + return false; +} + + diff --git a/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.h b/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.h new file mode 100644 index 000000000..fc59cd0a7 --- /dev/null +++ b/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.h @@ -0,0 +1,26 @@ +#ifndef DEFAULT_VISUAL_SHAPE_CONVERTER_H +#define DEFAULT_VISUAL_SHAPE_CONVERTER_H + + +#include "LinkVisualShapesConverter.h" + +struct DefaultVisualShapeConverter : public LinkVisualShapesConverter +{ + + struct DefaultVisualShapeConverterInternalData* m_data; + + DefaultVisualShapeConverter(struct GUIHelperInterface* guiHelper); + + virtual ~DefaultVisualShapeConverter(); + + virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionShape* colShape); + + virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const; + + +}; + + + + +#endif //DEFAULT_VISUAL_SHAPE_CONVERTER_H \ No newline at end of file diff --git a/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp b/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp index 0c6a81b33..e9c224a82 100644 --- a/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp +++ b/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp @@ -10,6 +10,7 @@ #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" #include "../CommonInterfaces/CommonParameterInterface.h" #include "../../Utils/b3ResourcePath.h" +#include "DefaultVisualShapeConverter.h" #include "BulletUrdfImporter.h" @@ -200,17 +201,10 @@ void ImportUrdfSetup::initPhysics() m_dynamicsWorld->setGravity(gravity); - - //now print the tree using the new interface - URDFImporterInterface* bla=0; + DefaultVisualShapeConverter visualConverter(m_guiHelper); + BulletURDFImporter u2b(m_guiHelper, &visualConverter); + - static bool newURDF = true; - if (newURDF) - { - b3Printf("using new URDF\n"); - bla = new BulletURDFImporter(m_guiHelper); - } - URDFImporterInterface& u2b = *bla; bool loadOk = u2b.loadURDF(m_fileName); #ifdef TEST_MULTIBODY_SERIALIZATION diff --git a/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h b/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h new file mode 100644 index 000000000..bff2ef263 --- /dev/null +++ b/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h @@ -0,0 +1,10 @@ +#ifndef LINK_VISUAL_SHAPES_CONVERTER_H +#define LINK_VISUAL_SHAPES_CONVERTER_H + +struct LinkVisualShapesConverter +{ + virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const class btTransform& localInertiaFrame, const struct UrdfModel& model, class btCollisionShape* colShape)=0; + virtual bool getLinkColor(int linkIndex, class btVector4& colorRGBA) const = 0; +}; + +#endif //LINK_VISUAL_SHAPES_CONVERTER_H diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index 6ff360788..140cce62c 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -209,9 +209,12 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat linkTransformInWorldSpace =parentTransformInWorldSpace*parent2joint; } - int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame); + btCompoundShape* compoundShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame); + + int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame,compoundShape); + if (compoundShape) { diff --git a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h index fd794ba3c..25b1769dd 100644 --- a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h +++ b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h @@ -42,9 +42,9 @@ public: virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const =0; ///quick hack: need to rethink the API/dependencies of this - virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const = 0; + virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionShape* colShape) const = 0; - virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const = 0; + virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const = 0; }; #endif //URDF_IMPORTER_INTERFACE_H diff --git a/examples/InverseDynamics/InverseDynamicsExample.cpp b/examples/InverseDynamics/InverseDynamicsExample.cpp index 7e53fd464..f80edd9b4 100644 --- a/examples/InverseDynamics/InverseDynamicsExample.cpp +++ b/examples/InverseDynamics/InverseDynamicsExample.cpp @@ -23,6 +23,8 @@ subject to the following restrictions: #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" #include "../Importers/ImportURDFDemo/URDF2Bullet.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" +#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h" + #include "../CommonInterfaces/CommonMultiBodyBase.h" #include "btBulletDynamicsCommon.h" @@ -153,7 +155,10 @@ void InverseDynamicsExample::initPhysics() case 0: case BT_ID_LOAD_URDF: { - BulletURDFImporter u2b(m_guiHelper); + + + DefaultVisualShapeConverter visualConverter(m_guiHelper); + BulletURDFImporter u2b(m_guiHelper, &visualConverter); bool loadOk = u2b.loadURDF("kuka_lwr/kuka.urdf"); if (loadOk) { diff --git a/examples/InverseDynamics/premake4.lua b/examples/InverseDynamics/premake4.lua index 99c89235d..463cc2f16 100644 --- a/examples/InverseDynamics/premake4.lua +++ b/examples/InverseDynamics/premake4.lua @@ -34,6 +34,7 @@ files { "../Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", "../Importers/ImportURDFDemo/BulletUrdfImporter.cpp", + "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", "../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", @@ -85,6 +86,7 @@ files { "../Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", "../Importers/ImportURDFDemo/BulletUrdfImporter.cpp", + "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", "../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", @@ -149,6 +151,7 @@ files { "../Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", "../Importers/ImportURDFDemo/BulletUrdfImporter.cpp", + "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", "../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index fbb485db1..4fca0de8e 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -235,6 +235,16 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) break; } + case CMD_REQUEST_CAMERA_IMAGE_DATA: + { + ///request an image from a simulated camera, using a software renderer. + + b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); + //void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight); + //void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); + b3SubmitClientCommand(m_physicsClientHandle, commandHandle); + break; + } case CMD_CREATE_BOX_COLLISION_SHAPE: { b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle); @@ -429,6 +439,7 @@ void PhysicsClientExample::createButtons() m_guiHelper->getParameterInterface()->removeAllParameters(); createButton("Load URDF",CMD_LOAD_URDF, isTrigger); + createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger); createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger); createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger); if (m_options!=eCLIENTEXAMPLE_SERVER) @@ -551,6 +562,16 @@ void PhysicsClientExample::stepSimulation(float deltaTime) { //b3Printf("bla\n"); } + if (statusType ==CMD_CAMERA_IMAGE_COMPLETED) + { + b3Printf("Camera image OK\n"); + } + if (statusType == CMD_CAMERA_IMAGE_FAILED) + { + b3Printf("Camera image FAILED\n"); + } + + if (statusType == CMD_URDF_LOADING_COMPLETED) { int bodyIndex = b3GetStatusBodyIndex(status); diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 65c22cdf5..e167054df 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -416,6 +416,18 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { break; } + + case CMD_CAMERA_IMAGE_COMPLETED: + { + b3Printf("Camera image OK\n"); + break; + } + + case CMD_CAMERA_IMAGE_FAILED: + { + b3Printf("Camera image FAILED\n"); + break; + } default: { b3Error("Unknown server status\n"); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 2570a6334..4b8067abd 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -4,6 +4,7 @@ #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" #include "../Importers/ImportURDFDemo/URDF2Bullet.h" +#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h" #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h" @@ -691,7 +692,9 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto return false; } - BulletURDFImporter u2b(m_data->m_guiHelper); + + DefaultVisualShapeConverter visualConverter(m_data->m_guiHelper); + BulletURDFImporter u2b(m_data->m_guiHelper, &visualConverter); bool loadOk = u2b.loadURDF(fileName, useFixedBase); @@ -964,7 +967,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm case CMD_REQUEST_CAMERA_IMAGE_DATA: { - serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED; + serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED; hasStatus = true; break; } diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 10fc7ebe4..f7d04f724 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -49,7 +49,9 @@ enum EnumSharedMemoryServerStatus CMD_DEBUG_LINES_OVERFLOW_FAILED, CMD_DESIRED_STATE_RECEIVED_COMPLETED, CMD_STEP_FORWARD_SIMULATION_COMPLETED, - CMD_RESET_SIMULATION_COMPLETED, + CMD_RESET_SIMULATION_COMPLETED, + CMD_CAMERA_IMAGE_COMPLETED, + CMD_CAMERA_IMAGE_FAILED, CMD_INVALID_STATUS, CMD_MAX_SERVER_COMMANDS }; diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index c92eefe43..dd9c6c923 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -46,9 +46,9 @@ files { "../Importers/ImportURDFDemo/MyMultiBodyCreator.h", "../Importers/ImportURDFDemo/BulletUrdfImporter.cpp", "../Importers/ImportURDFDemo/BulletUrdfImporter.h", + "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", + "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h", "../Importers/ImportURDFDemo/UrdfParser.cpp", - "../Importers/ImportURDFDemo/BulletUrdfImporter.cpp", - "../Importers/ImportURDFDemo/BulletUrdfImporter.h", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/UrdfParser.h", diff --git a/test/InverseDynamics/premake4.lua b/test/InverseDynamics/premake4.lua index b16efbaae..fb35a53e1 100644 --- a/test/InverseDynamics/premake4.lua +++ b/test/InverseDynamics/premake4.lua @@ -73,9 +73,8 @@ "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.h", "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp", "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.h", - "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", - "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp", - "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.h", + "../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", + "../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.h", "../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.h", diff --git a/test/SharedMemory/CMakeLists.txt b/test/SharedMemory/CMakeLists.txt index eb259f9b5..04c7d07f3 100644 --- a/test/SharedMemory/CMakeLists.txt +++ b/test/SharedMemory/CMakeLists.txt @@ -62,6 +62,8 @@ ENDIF() ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp + ../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp + ) ADD_TEST(Test_PhysicsClientServer_PASS Test_PhysicsClientServer) diff --git a/test/SharedMemory/premake4.lua b/test/SharedMemory/premake4.lua index f821c71f1..1b6d6dd2a 100644 --- a/test/SharedMemory/premake4.lua +++ b/test/SharedMemory/premake4.lua @@ -78,6 +78,7 @@ project ("Test_PhysicsServerLoopBack") "../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp", + "../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", @@ -135,6 +136,7 @@ project ("Test_PhysicsServerLoopBack") "../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp", + "../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", @@ -224,6 +226,7 @@ project ("Test_PhysicsServerInProcessExampleBrowser") "../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp", + "../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp", "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",