fix loading urdf at default position (0,0,0) and adding b3 cmd to change orientation if args provided

This commit is contained in:
Jasmine Hsu
2016-06-23 14:00:44 -07:00
parent 0b249361c2
commit e0448c7613

View File

@@ -135,7 +135,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
const char* urdfFileName="";
float startPosX =0;
float startPosY =0;
float startPosZ = 1;
float startPosZ = 0;
float startOrnX = 0;
float startOrnY = 0;
float startOrnZ = 0;
@@ -165,6 +165,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
return NULL;
}
{
printf("(%f, %f, %f) (%f, %f, %f, %f)\n", startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW);
b3SharedMemoryStatusHandle statusHandle;
int statusType;
@@ -172,6 +173,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
//setting the initial position, orientation and other arguments are optional
b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
b3LoadUrdfCommandSetStartOrientation(command, startOrnX, startOrnY,startOrnZ, startOrnW );
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType!=CMD_URDF_LOADING_COMPLETED)