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:
@@ -223,6 +223,18 @@ int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle,
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_LOAD_URDF);
|
||||
command->m_updateFlags |=URDF_ARGS_USE_GLOBAL_SCALING;
|
||||
command->m_urdfArguments.m_globalScaling = globalScaling;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
@@ -234,6 +246,19 @@ int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, i
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_LOAD_SDF);
|
||||
command->m_updateFlags |=URDF_ARGS_USE_GLOBAL_SCALING;
|
||||
command->m_sdfArguments.m_globalScaling = globalScaling;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
|
||||
@@ -267,6 +267,9 @@ int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHand
|
||||
int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody);
|
||||
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase);
|
||||
int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
|
||||
int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling);
|
||||
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName);
|
||||
b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName);
|
||||
@@ -301,6 +304,9 @@ int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle status
|
||||
|
||||
b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName);
|
||||
int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody);
|
||||
int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling);
|
||||
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName);
|
||||
|
||||
|
||||
@@ -2284,7 +2284,7 @@ bool PhysicsServerCommandProcessor::loadMjcf(const char* fileName, char* bufferS
|
||||
return loadOk;
|
||||
}
|
||||
|
||||
bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags)
|
||||
bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags, btScalar globalScaling)
|
||||
{
|
||||
btAssert(m_data->m_dynamicsWorld);
|
||||
if (!m_data->m_dynamicsWorld)
|
||||
@@ -2295,7 +2295,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling);
|
||||
|
||||
bool forceFixedBase = false;
|
||||
bool loadOk =u2b.loadSDF(fileName,forceFixedBase);
|
||||
@@ -2311,7 +2311,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
|
||||
|
||||
bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags)
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags, btScalar globalScaling)
|
||||
{
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
*bodyUniqueIdPtr = -1;
|
||||
@@ -2326,7 +2326,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
|
||||
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling);
|
||||
|
||||
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
|
||||
|
||||
@@ -3579,7 +3579,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (sdfArgs.m_useMultiBody!=0) : true;
|
||||
|
||||
int flags = CUF_USE_SDF; //CUF_USE_URDF_INERTIA
|
||||
bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody, flags);
|
||||
btScalar globalScaling = 1.f;
|
||||
if (clientCmd.m_updateFlags & URDF_ARGS_USE_GLOBAL_SCALING)
|
||||
{
|
||||
globalScaling = sdfArgs.m_globalScaling;
|
||||
}
|
||||
bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody, flags, globalScaling);
|
||||
if (completedOk)
|
||||
{
|
||||
m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
|
||||
@@ -4016,10 +4021,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (urdfArgs.m_useMultiBody!=0) : true;
|
||||
bool useFixedBase = (clientCmd.m_updateFlags & URDF_ARGS_USE_FIXED_BASE) ? (urdfArgs.m_useFixedBase!=0): false;
|
||||
int bodyUniqueId;
|
||||
btScalar globalScaling = 1.f;
|
||||
if (clientCmd.m_updateFlags & URDF_ARGS_USE_GLOBAL_SCALING)
|
||||
{
|
||||
globalScaling = urdfArgs.m_globalScaling;
|
||||
}
|
||||
//load the actual URDF and send a report: completed or failed
|
||||
bool completedOk = loadUrdf(urdfArgs.m_urdfFileName,
|
||||
initialPos,initialOrn,
|
||||
useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes, urdfFlags);
|
||||
useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes, urdfFlags, globalScaling);
|
||||
|
||||
if (completedOk && bodyUniqueId>=0)
|
||||
{
|
||||
|
||||
@@ -27,10 +27,10 @@ protected:
|
||||
|
||||
|
||||
|
||||
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags);
|
||||
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags, btScalar globalScaling);
|
||||
|
||||
bool loadUrdf(const char* fileName, const class btVector3& pos, const class btQuaternion& orn,
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags=0);
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags, btScalar globalScaling);
|
||||
|
||||
bool loadMjcf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags);
|
||||
|
||||
|
||||
@@ -65,6 +65,7 @@ struct SdfArgs
|
||||
{
|
||||
char m_sdfFileName[MAX_URDF_FILENAME_LENGTH];
|
||||
int m_useMultiBody;
|
||||
double m_globalScaling;
|
||||
};
|
||||
|
||||
struct FileArgs
|
||||
@@ -79,7 +80,8 @@ enum EnumUrdfArgsUpdateFlags
|
||||
URDF_ARGS_INITIAL_ORIENTATION=4,
|
||||
URDF_ARGS_USE_MULTIBODY=8,
|
||||
URDF_ARGS_USE_FIXED_BASE=16,
|
||||
URDF_ARGS_HAS_CUSTOM_URDF_FLAGS = 32
|
||||
URDF_ARGS_HAS_CUSTOM_URDF_FLAGS = 32,
|
||||
URDF_ARGS_USE_GLOBAL_SCALING =64,
|
||||
};
|
||||
|
||||
|
||||
@@ -91,6 +93,7 @@ struct UrdfArgs
|
||||
int m_useMultiBody;
|
||||
int m_useFixedBase;
|
||||
int m_urdfFlags;
|
||||
double m_globalScaling;
|
||||
};
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user