mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 13:20:07 +00:00
Merge pull request #3963 from erwincoumans/master
revert linkNames in createMultiBody, we cannot pass pointers pointing… …
This commit is contained in:
commit
47c3f5e994
@ -2160,8 +2160,7 @@ B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandl
|
||||
const double linkInertialFrameOrientation[4],
|
||||
int linkParentIndex,
|
||||
int linkJointType,
|
||||
const double linkJointAxis[3],
|
||||
const char* const linkName)
|
||||
const double linkJointAxis[3])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||
b3Assert(command);
|
||||
@ -2206,7 +2205,7 @@ B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandl
|
||||
command->m_createMultiBodyArgs.m_linkJointAxis[3 * linkIndex + 2] = linkJointAxis[2];
|
||||
|
||||
command->m_createMultiBodyArgs.m_linkMasses[linkIndex] = linkMass;
|
||||
command->m_createMultiBodyArgs.m_linkNames[linkIndex] = linkName;
|
||||
|
||||
command->m_createMultiBodyArgs.m_numLinks++;
|
||||
return numLinks;
|
||||
}
|
||||
|
@ -564,8 +564,7 @@ extern "C"
|
||||
const double linkInertialFrameOrientation[/*4*/],
|
||||
int linkParentIndex,
|
||||
int linkJointType,
|
||||
const double linkJointAxis[/*3*/],
|
||||
const char* const linkName);
|
||||
const double linkJointAxis[/*3*/]);
|
||||
|
||||
//batch creation is an performance feature to create a large number of multi bodies in one command
|
||||
B3_SHARED_API int b3CreateMultiBodySetBatchPositions(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, double* batchPositions, int numBatchObjects);
|
||||
|
@ -2250,11 +2250,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const
|
||||
{
|
||||
// Allow user overrides on default-created link names.
|
||||
if(m_createBodyArgs.m_linkNames[linkIndex] != 0
|
||||
&& strlen(m_createBodyArgs.m_linkNames[linkIndex]) > 0){
|
||||
return std::string(m_createBodyArgs.m_linkNames[linkIndex]);
|
||||
}
|
||||
|
||||
std::string linkName = "link";
|
||||
char numstr[21]; // enough to hold all numbers up to 64-bits
|
||||
sprintf(numstr, "%d", linkIndex);
|
||||
@ -2332,11 +2328,6 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
|
||||
|
||||
virtual std::string getJointName(int linkIndex) const
|
||||
{
|
||||
// Allow user overrides on default-created joint names.
|
||||
if(m_createBodyArgs.m_linkNames[linkIndex] != 0
|
||||
&& strlen(m_createBodyArgs.m_linkNames[linkIndex]) > 0){
|
||||
return std::string(m_createBodyArgs.m_linkNames[linkIndex]);
|
||||
}
|
||||
std::string jointName = "joint";
|
||||
char numstr[21]; // enough to hold all numbers up to 64-bits
|
||||
sprintf(numstr, "%d", linkIndex);
|
||||
|
@ -1066,7 +1066,6 @@ struct b3CreateMultiBodyArgs
|
||||
int m_flags;
|
||||
int m_numBatchObjects;
|
||||
|
||||
const char* m_linkNames[MAX_CREATE_MULTI_BODY_LINKS];
|
||||
};
|
||||
|
||||
struct b3CreateMultiBodyResultArgs
|
||||
|
@ -2431,8 +2431,7 @@ int b3RobotSimulatorClientAPI_NoDirect::createMultiBody(struct b3RobotSimulatorC
|
||||
doubleLinkInertialFrameOrientation,
|
||||
linkParentIndex,
|
||||
linkJointType,
|
||||
doubleLinkJointAxis,
|
||||
0);
|
||||
doubleLinkJointAxis);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
|
@ -9596,19 +9596,19 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
|
||||
PyObject* linkInertialFramePositionObj = 0;
|
||||
PyObject* linkInertialFrameOrientationObj = 0;
|
||||
PyObject* objBatchPositions = 0;
|
||||
PyObject* linkNamesObj = 0;
|
||||
|
||||
|
||||
static char* kwlist[] = {
|
||||
"baseMass", "baseCollisionShapeIndex", "baseVisualShapeIndex", "basePosition", "baseOrientation",
|
||||
"baseInertialFramePosition", "baseInertialFrameOrientation", "linkMasses", "linkCollisionShapeIndices",
|
||||
"linkVisualShapeIndices", "linkPositions", "linkOrientations", "linkInertialFramePositions", "linkInertialFrameOrientations", "linkParentIndices",
|
||||
"linkJointTypes", "linkJointAxis", "useMaximalCoordinates", "flags", "batchPositions", "linkNames", "physicsClientId", NULL};
|
||||
"linkJointTypes", "linkJointAxis", "useMaximalCoordinates", "flags", "batchPositions", "physicsClientId", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diiOOOOOOOOOOOOOOiiOOi", kwlist,
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diiOOOOOOOOOOOOOOiiOi", kwlist,
|
||||
&baseMass, &baseCollisionShapeIndex, &baseVisualShapeIndex, &basePosObj, &baseOrnObj,
|
||||
&baseInertialFramePositionObj, &baseInertialFrameOrientationObj, &linkMassesObj, &linkCollisionShapeIndicesObj,
|
||||
&linkVisualShapeIndicesObj, &linkPositionsObj, &linkOrientationsObj, &linkInertialFramePositionObj, &linkInertialFrameOrientationObj, &linkParentIndicesObj,
|
||||
&linkJointTypesObj, &linkJointAxisObj, &useMaximalCoordinates, &flags, &objBatchPositions, &linkNamesObj, &physicsClientId))
|
||||
&linkJointTypesObj, &linkJointAxisObj, &useMaximalCoordinates, &flags, &objBatchPositions, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@ -9645,7 +9645,6 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
|
||||
PyObject* seqLinkInertialFrameOrientations = linkInertialFrameOrientationObj ? PySequence_Fast(linkInertialFrameOrientationObj, "expected a sequence") : 0;
|
||||
|
||||
PyObject* seqBatchPositions = objBatchPositions ? PySequence_Fast(objBatchPositions, "expected a sequence") : 0;
|
||||
PyObject* seqLinkNames = linkNamesObj ? PySequence_Fast(linkNamesObj, "expected a sequence") : 0;
|
||||
|
||||
if ((numLinkMasses == numLinkCollisionShapes) &&
|
||||
(numLinkMasses == numLinkVisualShapes) &&
|
||||
@ -9705,7 +9704,6 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
|
||||
pybullet_internalGetVector3FromSequence(seqLinkJoinAxis, i, linkJointAxis);
|
||||
linkParentIndex = pybullet_internalGetIntFromSequence(seqLinkParentIndices, i);
|
||||
linkJointType = pybullet_internalGetIntFromSequence(seqLinkJointTypes, i);
|
||||
linkName = seqLinkNames? pybullet_internalGetCStringFromSequence(seqLinkNames, i) : 0;
|
||||
|
||||
b3CreateMultiBodyLink(commandHandle,
|
||||
linkMass,
|
||||
@ -9717,8 +9715,7 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
|
||||
linkInertialFrameOrientation,
|
||||
linkParentIndex,
|
||||
linkJointType,
|
||||
linkJointAxis,
|
||||
linkName);
|
||||
linkJointAxis);
|
||||
}
|
||||
|
||||
if (seqLinkMasses)
|
||||
|
2
setup.py
2
setup.py
@ -501,7 +501,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
|
||||
|
||||
setup(
|
||||
name='pybullet',
|
||||
version='3.1.7',
|
||||
version='3.1.8',
|
||||
description=
|
||||
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||
long_description=
|
||||
|
@ -25,7 +25,7 @@ subject to the following restrictions:
|
||||
#include <float.h>
|
||||
|
||||
/* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/
|
||||
#define BT_BULLET_VERSION 317
|
||||
#define BT_BULLET_VERSION 318
|
||||
|
||||
inline int btGetVersion()
|
||||
{
|
||||
|
@ -481,7 +481,7 @@ public:
|
||||
|
||||
buffer[9] = '3';
|
||||
buffer[10] = '1';
|
||||
buffer[11] = '7';
|
||||
buffer[11] = '8';
|
||||
}
|
||||
|
||||
virtual void startSerialization()
|
||||
|
Loading…
Reference in New Issue
Block a user