Expose optional "globalScaling" factor to pybullet.loadURDF and pybullet.loadSDF. This will scale the visual, collision shapes and transform locations.

Fix two_cubes.sdf (was lacking collision shape for second cube)
This commit is contained in:
Erwin Coumans
2017-08-14 14:59:41 -07:00
parent dfaa717fed
commit aafaa7e33e
15 changed files with 130 additions and 34 deletions

View File

@@ -15,10 +15,11 @@ class BulletURDFImporter : public URDFImporterInterface
public:
BulletURDFImporter(struct GUIHelperInterface* guiHelper, LinkVisualShapesConverter* customConverter);
BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, btScalar globalScaling);
virtual ~BulletURDFImporter();
virtual bool loadURDF(const char* fileName, bool forceFixedBase = false);
//warning: some quick test to load SDF: we 'activate' a model, so we can re-use URDF code path