diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h index 2c89fdbc9..2d8f01d06 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h @@ -34,7 +34,7 @@ public: virtual bool loadMJCF(const char* fileName, MJCFErrorLogger* logger, bool forceFixedBase = false); - virtual bool loadURDF(const char* fileName, bool forceFixedBase = false) + virtual bool loadURDF(const char* fileName, bool forceFixedBase = false, int flags = 0) { return false; } diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 5e3cf4d56..7f96628f8 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -117,7 +117,7 @@ struct BulletErrorLogger : public ErrorLogger } }; -bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) +bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase, int flags) { if (strlen(fileName) == 0) return false; @@ -155,7 +155,7 @@ bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) BulletErrorLogger loggie; m_data->m_urdfParser.setParseSDF(false); - bool result = m_data->m_urdfParser.loadUrdf(xml_string.c_str(), &loggie, forceFixedBase); + bool result = m_data->m_urdfParser.loadUrdf(xml_string.c_str(), &loggie, forceFixedBase, (flags & CUF_PARSE_SENSORS)); return result; } diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h index aa57abdae..0d58c06ae 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h @@ -23,7 +23,7 @@ public: virtual ~BulletURDFImporter(); - virtual bool loadURDF(const char* fileName, bool forceFixedBase = false); + virtual bool loadURDF(const char* fileName, bool forceFixedBase = false, int flags = 0); //warning: some quick test to load SDF: we 'activate' a model, so we can re-use URDF code path virtual bool loadSDF(const char* fileName, bool forceFixedBase = false); diff --git a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h index 4b03c86af..28924729f 100644 --- a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h +++ b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h @@ -12,7 +12,7 @@ class URDFImporterInterface public: virtual ~URDFImporterInterface() {} - virtual bool loadURDF(const char* fileName, bool forceFixedBase = false) = 0; + virtual bool loadURDF(const char* fileName, bool forceFixedBase = false, int flags = 0) = 0; virtual bool loadSDF(const char* fileName, bool forceFixedBase = false) { return false; } diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 0e04bf494..e190a8820 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -1,5 +1,5 @@ #include "UrdfParser.h" -#include "../../ThirdPartyLibs/tinyxml2/tinyxml2.h" +#include "third_party/tinyxml2/tinyxml2.h" #include "urdfStringSplit.h" #include "urdfLexicalCast.h" using namespace tinyxml2; diff --git a/examples/SharedMemory/PhysicsClientGRPC.cpp b/examples/SharedMemory/PhysicsClientGRPC.cpp index 6cc8498e5..94a73369d 100644 --- a/examples/SharedMemory/PhysicsClientGRPC.cpp +++ b/examples/SharedMemory/PhysicsClientGRPC.cpp @@ -14,7 +14,7 @@ using grpc::Channel; #include "Bullet3Common/b3AlignedObjectArray.h" #include "SharedMemory/grpc/ConvertGRPCBullet.h" -using pybullet_grpc::PyBulletAPI; +using pybullet_grpc::grpc::PyBulletAPI; static unsigned int b3DeserializeInt2(const unsigned char* input) { diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 835e3c59f..e2386fcde 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -27,7 +27,7 @@ #include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h" #include "Bullet3Common/b3HashMap.h" #include "../Utils/ChromeTraceUtil.h" -#include "stb_image/stb_image.h" +#include "third_party/stblib/stb_image.h" #include "BulletInverseDynamics/MultiBodyTree.hpp" #include "IKTrajectoryHelper.h" #include "btBulletDynamicsCommon.h" @@ -1990,7 +1990,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface { } - virtual bool loadURDF(const char* fileName, bool forceFixedBase = false) + virtual bool loadURDF(const char* fileName, bool forceFixedBase = false, int flags = 0) { b3Assert(0); return false; @@ -3014,7 +3014,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags); u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer); - bool loadOk = u2b.loadURDF(fileName, useFixedBase); + bool loadOk = u2b.loadURDF(fileName, useFixedBase, flags); if (loadOk) {