overview-simple.cpp
Go to the documentation of this file.
1 #include "pinocchio/parsers/sample-models.hpp"
2 #include "pinocchio/algorithm/joint-configuration.hpp"
3 #include "pinocchio/algorithm/rnea.hpp"
4 
5 int main()
6 {
9  pinocchio::Data data(model);
10 
12  Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
13  Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
14 
15  const Eigen::VectorXd & tau = pinocchio::rnea(model,data,q,v,a);
16  std::cout << "tau = " << tau.transpose() << std::endl;
17 }
q
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
int main()
Vec3f a
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
int nv
Dimension of the velocity vector space.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:32