re-enable inverse dynamics/computed torque, instead of PD control in InverseDynamicsExample

This commit is contained in:
Erwin Coumans
2015-12-02 23:16:41 -08:00
parent 332017ff23
commit b22e968cdd

View File

@@ -43,7 +43,7 @@ subject to the following restrictions:
// as parameters and callbacks
static btScalar kp =10*10;
static btScalar kd = 2*10;
static bool useInverseModel = false;
static bool useInverseModel = true;
static std::vector<btScalar> qd;
static std::vector<std::string> qd_name;
static std::vector<std::string> q_name;