1 #include "pinocchio/parsers/urdf.hpp" 3 #include "pinocchio/algorithm/joint-configuration.hpp" 4 #include "pinocchio/algorithm/aba-derivatives.hpp" 9 #ifndef PINOCCHIO_MODEL_DIR 10 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 13 int main(
int argc,
char ** argv)
33 Eigen::MatrixXd djoint_acc_dq = Eigen::MatrixXd::Zero(model.
nv,model.
nv);
34 Eigen::MatrixXd djoint_acc_dv = Eigen::MatrixXd::Zero(model.
nv,model.
nv);
35 Eigen::MatrixXd djoint_acc_dtau = Eigen::MatrixXd::Zero(model.
nv,model.
nv);
41 std::cout <<
"Joint acceleration: " << data.
ddq.transpose() << std::endl;
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
#define PINOCCHIO_MODEL_DIR
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
TangentVectorType ddq
The joint accelerations computed from ABA.
Main pinocchio namespace.
int nv
Dimension of the velocity vector space.
void computeABADerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
JointCollectionTpl & model
int main(int argc, char **argv)