run_rnea.cpp
Go to the documentation of this file.
1 #include <pinocchio/parsers/sample-models.hpp>
2 #include <pinocchio/algorithm/rnea.hpp>
3 #include <pinocchio/algorithm/joint-configuration.hpp>
4 
5 #include <iostream>
6 
7 int main(int /*argc*/, char ** /*argv*/)
8 {
9  using namespace pinocchio;
10 
11  Model model;
13 
15  Model::VectorXs v = Model::VectorXs::Random(model.nv);
16  Model::VectorXs a = Model::VectorXs::Random(model.nv);
17 
18  Data data(model);
19  rnea(model,data,q,v,a);
20 
21  return 0;
22 }
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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...
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.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
void humanoid(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a 28-DOF kinematic chain of a floating humanoid robot.
int main(int, char **)
Definition: run_rnea.cpp:7
Vec3f a
Main pinocchio namespace.
Definition: timings.cpp:28
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
int nv
Dimension of the velocity vector space.
JointCollectionTpl & model


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