expose a maximum velocity due to the joint motor in position control.

see also pybullet/examples/motorMaxVelocity.py
this fixes issue 1444
This commit is contained in:
erwincoumans
2017-11-21 17:05:28 -08:00
parent 3f60be59ad
commit ab843b26f0
6 changed files with 42 additions and 4 deletions

View File

@@ -0,0 +1,12 @@
import pybullet as p
import time
p.connect(p.GUI)
cartpole=p.loadURDF("cartpole.urdf")
p.setRealTimeSimulation(1)
p.setJointMotorControl2(cartpole,1,p.POSITION_CONTROL,targetPosition=1000,targetVelocity=0,force=1000, positionGain=1, velocityGain=0, maxVelocity=0.5)
while (1):
p.setGravity(0,0,-10)
js = p.getJointState(cartpole,1)
print("position=",js[0],"velocity=",js[1])
time.sleep(0.01)

View File

@@ -1748,12 +1748,13 @@ static PyObject* pybullet_setJointMotorControl2(PyObject* self, PyObject* args,
double force = 100000.0;
double kp = 0.1;
double kd = 1.0;
double maxVelocity = -1;
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|dddddi", kwlist, &bodyUniqueId, &jointIndex, &controlMode,
&targetPosition, &targetVelocity, &force, &kp, &kd, &physicsClientId))
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "maxVelocity", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|ddddddi", kwlist, &bodyUniqueId, &jointIndex, &controlMode,
&targetPosition, &targetVelocity, &force, &kp, &kd, &maxVelocity, &physicsClientId))
{
//backward compatibility, bodyIndex -> bodyUniqueId, don't need to update this function: people have to migrate to bodyUniqueId
static char* kwlist2[] = {"bodyIndex", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "physicsClientId", NULL};
@@ -1816,6 +1817,10 @@ static PyObject* pybullet_setJointMotorControl2(PyObject* self, PyObject* args,
case CONTROL_MODE_POSITION_VELOCITY_PD:
{
if (maxVelocity>0)
{
b3JointControlSetMaximumVelocity(commandHandle, info.m_uIndex, maxVelocity);
}
b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex,
targetPosition);
b3JointControlSetKp(commandHandle, info.m_uIndex, kp);