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:
@@ -358,10 +358,11 @@ struct SendDesiredStateArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
int m_controlMode;
|
||||
|
||||
|
||||
//PD parameters in case m_controlMode == CONTROL_MODE_POSITION_VELOCITY_PD
|
||||
double m_Kp[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
|
||||
double m_Kd[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
|
||||
double m_rhsClamp[MAX_DEGREE_OF_FREEDOM];
|
||||
|
||||
int m_hasDesiredStateFlags[MAX_DEGREE_OF_FREEDOM];
|
||||
|
||||
@@ -389,6 +390,7 @@ enum EnumSimDesiredStateUpdateFlags
|
||||
SIM_DESIRED_STATE_HAS_KD=4,
|
||||
SIM_DESIRED_STATE_HAS_KP=8,
|
||||
SIM_DESIRED_STATE_HAS_MAX_FORCE=16,
|
||||
SIM_DESIRED_STATE_HAS_RHS_CLAMP=32
|
||||
};
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user