allow auxilary link to be used for gear btMultiBodyGearConstraint.
This commit is contained in:
@@ -1949,6 +1949,20 @@ int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHa
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_CONSTRAINT);
|
||||
b3Assert(command->m_updateFlags & USER_CONSTRAINT_CHANGE_CONSTRAINT);
|
||||
|
||||
command->m_updateFlags |=USER_CONSTRAINT_CHANGE_GEAR_AUX_LINK;
|
||||
command->m_userConstraintArguments.m_gearAuxLink = gearAuxLink;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
||||
@@ -107,7 +107,7 @@ int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHan
|
||||
int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double jointChildFrameOrn[4]);
|
||||
int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce);
|
||||
int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHandle, double gearRatio);
|
||||
|
||||
int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId);
|
||||
|
||||
|
||||
@@ -6450,6 +6450,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
userConstraintPtr->m_mbConstraint->setGearRatio(clientCmd.m_userConstraintArguments.m_gearRatio);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & USER_CONSTRAINT_CHANGE_GEAR_AUX_LINK)
|
||||
{
|
||||
userConstraintPtr->m_mbConstraint->setGearAuxLink(clientCmd.m_userConstraintArguments.m_gearAuxLink);
|
||||
}
|
||||
|
||||
}
|
||||
if (userConstraintPtr->m_rbConstraint)
|
||||
|
||||
@@ -645,6 +645,8 @@ enum EnumUserConstraintFlags
|
||||
USER_CONSTRAINT_CHANGE_MAX_FORCE=32,
|
||||
USER_CONSTRAINT_REQUEST_INFO=64,
|
||||
USER_CONSTRAINT_CHANGE_GEAR_RATIO=128,
|
||||
USER_CONSTRAINT_CHANGE_GEAR_AUX_LINK=256,
|
||||
|
||||
};
|
||||
|
||||
enum EnumBodyChangeFlags
|
||||
|
||||
@@ -235,6 +235,7 @@ struct b3UserConstraint
|
||||
double m_maxAppliedForce;
|
||||
int m_userConstraintUniqueId;
|
||||
double m_gearRatio;
|
||||
int m_gearAuxLink;
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -12,10 +12,10 @@ useRealTimeSim = 1
|
||||
#for video recording (works best on Mac and Linux, not well on Windows)
|
||||
#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "racecar.mp4")
|
||||
p.setRealTimeSimulation(useRealTimeSim) # either this
|
||||
#p.loadURDF("plane.urdf")
|
||||
p.loadSDF("stadium.sdf")
|
||||
p.loadURDF("plane.urdf")
|
||||
#p.loadSDF("stadium.sdf")
|
||||
|
||||
car = p.loadURDF("racecar/racecar_differential.urdf")#, [0,0,2],useFixedBase=True)
|
||||
car = p.loadURDF("racecar/racecar_differential.urdf") #, [0,0,2],useFixedBase=True)
|
||||
for i in range (p.getNumJoints(car)):
|
||||
print (p.getJointInfo(car,i))
|
||||
for wheel in range(p.getNumJoints(car)):
|
||||
@@ -26,7 +26,6 @@ wheels = [8,15]
|
||||
print("----------------")
|
||||
|
||||
#p.setJointMotorControl2(car,10,p.VELOCITY_CONTROL,targetVelocity=1,force=10)
|
||||
|
||||
c = p.createConstraint(car,9,car,11,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||
|
||||
@@ -39,12 +38,17 @@ p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
c = p.createConstraint(car,16,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,17,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,16,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,17,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,1,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15, maxForce=10000)
|
||||
c = p.createConstraint(car,3,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15,maxForce=10000)
|
||||
|
||||
|
||||
steering = [0,2]
|
||||
|
||||
@@ -4804,11 +4804,12 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
|
||||
static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
static char* kwlist[] = {"userConstraintUniqueId", "jointChildPivot", "jointChildFrameOrientation", "maxForce", "gearRatio", "physicsClientId", NULL};
|
||||
static char* kwlist[] = {"userConstraintUniqueId", "jointChildPivot", "jointChildFrameOrientation", "maxForce", "gearRatio", "gearAuxLink", "physicsClientId", NULL};
|
||||
int userConstraintUniqueId = -1;
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int gearAuxLink = -1;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
PyObject* jointChildPivotObj = 0;
|
||||
@@ -4817,7 +4818,7 @@ static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, P
|
||||
double jointChildFrameOrn[4];
|
||||
double maxForce = -1;
|
||||
double gearRatio = 0;
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOddi", kwlist, &userConstraintUniqueId, &jointChildPivotObj, &jointChildFrameOrnObj, &maxForce, &gearRatio, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOddii", kwlist, &userConstraintUniqueId, &jointChildPivotObj, &jointChildFrameOrnObj, &maxForce, &gearRatio, &gearAuxLink, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -4847,6 +4848,10 @@ static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, P
|
||||
{
|
||||
b3InitChangeUserConstraintSetGearRatio(commandHandle,gearRatio);
|
||||
}
|
||||
if (gearAuxLink>=0)
|
||||
{
|
||||
b3InitChangeUserConstraintSetGearAuxLink(commandHandle,gearAuxLink);
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
Py_INCREF(Py_None);
|
||||
|
||||
Reference in New Issue
Block a user