leave m_useGlobalVelocities to false, until enabled, for backward compatibility
use URDF_GLOBAL_VELOCITIES_MB flag in PyBullet loadURDF. fix robot_bases.py due to new fields in getJointInfo. backward compabitibility: BulletMJCFImporter, keep creating btMultiSphereShape for MJCF capsules with fromto, instead of shifted btCapsuleShapeZ, unless if CUF_USE_IMPLICIT_CYLINDER is used.
This commit is contained in:
@@ -2704,7 +2704,7 @@ bool PhysicsServerCommandProcessor::loadMjcf(const char* fileName, char* bufferS
|
||||
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletMJCFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
|
||||
BulletMJCFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, flags);
|
||||
|
||||
bool useFixedBase = false;
|
||||
MyMJCFLogger2 logger;
|
||||
|
||||
Reference in New Issue
Block a user