expose b3LoadMJCFCommandSetFlags / pybullet.pybullet_loadMJCF(fileName,flags=pybullet.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
This commit is contained in:
@@ -19,7 +19,9 @@ 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
|
||||
CUF_USE_SELF_COLLISION=8,
|
||||
CUF_USE_SELF_COLLISION_EXCLUDE_PARENT=16,
|
||||
CUF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS=32,
|
||||
};
|
||||
|
||||
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
|
||||
|
||||
Reference in New Issue
Block a user