Implement faster array versions of PyBullet: getJointStatesMultiDof, getLinkStates, setJointMotorControlMultiDofArray, resetJointStatesMultiDof,

Implement StablePD in C++ through setJointMotorControlMultiDofArray method for pybullet_envs.deep_mimic, see testHumanoid.py and examples/pybullet/examples/humanoidMotionCapture.py
Minor fix in ChromeTraceUtil in case startTime>endTime (why would it happen?)
This commit is contained in:
Erwin Coumans
2019-07-21 13:08:22 -07:00
parent dff277ad7b
commit 39a4e8dcd9
12 changed files with 1503 additions and 171 deletions

View File

@@ -1,7 +1,7 @@
#include "RBDModel.h"
#include "RBDUtil.h"
#include "KinTree.h"
#include "LinearMath/btQuickprof.h"
cRBDModel::cRBDModel()
{
}
@@ -38,11 +38,26 @@ void cRBDModel::Update(const Eigen::VectorXd& pose, const Eigen::VectorXd& vel)
SetPose(pose);
SetVel(vel);
UpdateJointSubspaceArr();
UpdateChildParentMatArr();
UpdateSpWorldTrans();
UpdateMassMat();
UpdateBiasForce();
{
BT_PROFILE("rbdModel::UpdateJointSubspaceArr");
UpdateJointSubspaceArr();
}
{
BT_PROFILE("rbdModel::UpdateChildParentMatArr");
UpdateChildParentMatArr();
}
{
BT_PROFILE("rbdModel::UpdateSpWorldTrans");
UpdateSpWorldTrans();
}
{
BT_PROFILE("UpdateMassMat");
UpdateMassMat();
}
{
BT_PROFILE("UpdateBiasForce");
UpdateBiasForce();
}
}
int cRBDModel::GetNumDof() const