fix MSVC 2010 compile issue
urdfEditor: fix scale incorrectly saved in urdfEditor.saveUrdf urdfEditor: fix linkMeshScaleArray in wrong location
This commit is contained in:
@@ -255,7 +255,7 @@ class UrdfEditor(object):
|
|||||||
prec=precision)
|
prec=precision)
|
||||||
file.write(str)
|
file.write(str)
|
||||||
if urdfCollision.geom_type == p.GEOM_MESH:
|
if urdfCollision.geom_type == p.GEOM_MESH:
|
||||||
str = '\t\t\t\t<mesh filename=\"{}\"/> scale=\"{:.{prec}f} {:.{prec}f} {:.{prec}f}\"\n'.format(urdfCollision.geom_meshfilename,\
|
str = '\t\t\t\t<mesh filename=\"{}\" scale=\"{:.{prec}f} {:.{prec}f} {:.{prec}f}\"/>\n'.format(urdfCollision.geom_meshfilename,\
|
||||||
urdfCollision.geom_meshscale[0],urdfCollision.geom_meshscale[1],urdfCollision.geom_meshscale[2],prec=precision)
|
urdfCollision.geom_meshscale[0],urdfCollision.geom_meshscale[1],urdfCollision.geom_meshscale[2],prec=precision)
|
||||||
file.write(str)
|
file.write(str)
|
||||||
if urdfCollision.geom_type == p.GEOM_CYLINDER:
|
if urdfCollision.geom_type == p.GEOM_CYLINDER:
|
||||||
@@ -422,7 +422,7 @@ class UrdfEditor(object):
|
|||||||
linkVisualShapeIndices=[]
|
linkVisualShapeIndices=[]
|
||||||
linkPositions=[]
|
linkPositions=[]
|
||||||
linkOrientations=[]
|
linkOrientations=[]
|
||||||
linkMeshScaleArray=[]
|
|
||||||
linkInertialFramePositions=[]
|
linkInertialFramePositions=[]
|
||||||
linkInertialFrameOrientations=[]
|
linkInertialFrameOrientations=[]
|
||||||
linkParentIndices=[]
|
linkParentIndices=[]
|
||||||
@@ -446,6 +446,7 @@ class UrdfEditor(object):
|
|||||||
linkHalfExtentsArray=[]
|
linkHalfExtentsArray=[]
|
||||||
lengthsArray=[]
|
lengthsArray=[]
|
||||||
fileNameArray=[]
|
fileNameArray=[]
|
||||||
|
linkMeshScaleArray=[]
|
||||||
linkPositionsArray=[]
|
linkPositionsArray=[]
|
||||||
linkOrientationsArray=[]
|
linkOrientationsArray=[]
|
||||||
|
|
||||||
|
|||||||
@@ -605,6 +605,10 @@ static PyObject* pybullet_syncBodyInfo(PyObject* self, PyObject* args, PyObject*
|
|||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
static char* kwlist[] = {"physicsClientId", NULL};
|
static char* kwlist[] = {"physicsClientId", NULL};
|
||||||
|
b3SharedMemoryCommandHandle command;
|
||||||
|
b3SharedMemoryStatusHandle statusHandle;
|
||||||
|
int statusType;
|
||||||
|
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
|
||||||
{
|
{
|
||||||
return NULL;
|
return NULL;
|
||||||
@@ -616,9 +620,6 @@ static PyObject* pybullet_syncBodyInfo(PyObject* self, PyObject* args, PyObject*
|
|||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle command;
|
|
||||||
b3SharedMemoryStatusHandle statusHandle;
|
|
||||||
int statusType;
|
|
||||||
|
|
||||||
command = b3InitSyncBodyInfoCommand(sm);
|
command = b3InitSyncBodyInfoCommand(sm);
|
||||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||||
|
|||||||
Reference in New Issue
Block a user