expose pybullet.URDF_USE_SELF_COLLISION flag, experimental (likely doesn't work well for many URDF files)
This commit is contained in:
@@ -19,6 +19,7 @@ enum ConvertURDFFlags {
|
||||
// Use inertia values in URDF instead of recomputing them from collision shape.
|
||||
CUF_USE_URDF_INERTIA = 2,
|
||||
CUF_USE_MJCF = 4,
|
||||
CUF_USE_SELF_COLLISION=8
|
||||
};
|
||||
|
||||
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
|
||||
|
||||
@@ -1810,6 +1810,10 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
mb->setUserIndex2(bodyUniqueId);
|
||||
bodyHandle->m_multiBody = mb;
|
||||
|
||||
if (flags & URDF_USE_SELF_COLLISION)
|
||||
{
|
||||
mb->setHasSelfCollision(true);
|
||||
}
|
||||
createJointMotors(mb);
|
||||
|
||||
|
||||
|
||||
@@ -451,6 +451,7 @@ enum eCONNECT_METHOD {
|
||||
enum eURDF_Flags
|
||||
{
|
||||
URDF_USE_INERTIA_FROM_FILE=2,//sync with URDF2Bullet.h 'ConvertURDFFlags'
|
||||
URDF_USE_SELF_COLLISION=8,//see CUF_USE_SELF_COLLISION
|
||||
};
|
||||
|
||||
#endif//SHARED_MEMORY_PUBLIC_H
|
||||
|
||||
@@ -1,4 +1,5 @@
|
||||
|
||||
|
||||
#include "../SharedMemory/PhysicsClientC_API.h"
|
||||
#include "../SharedMemory/PhysicsDirectC_API.h"
|
||||
#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
|
||||
@@ -5434,6 +5435,7 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_INERTIA_FROM_FILE", URDF_USE_INERTIA_FROM_FILE);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION);
|
||||
|
||||
PyModule_AddIntConstant(m, "B3G_F1", B3G_F1);
|
||||
PyModule_AddIntConstant(m, "B3G_F2", B3G_F2);
|
||||
|
||||
Reference in New Issue
Block a user