overview-simple.cpp
Go to the documentation of this file.
1 #include <iostream>
2 
6 
7 int main()
8 {
12 
13  Eigen::VectorXd q = pinocchio::neutral(model);
14  Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
15  Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
16 
17  const Eigen::VectorXd & tau = pinocchio::rnea(model, data, q, v, a);
18  std::cout << "tau = " << tau.transpose() << std::endl;
19 }
pinocchio::DataTpl
Definition: context/generic.hpp:25
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::buildModels::manipulator
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.
rnea.hpp
anymal-simulation.model
model
Definition: anymal-simulation.py:8
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:25
joint-configuration.hpp
cartpole.v
v
Definition: cartpole.py:153
q
q
a
Vec3f a
pinocchio::rnea
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(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 > &a)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
pinocchio::neutral
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
Definition: joint-configuration.hpp:363
sample-models.hpp
main
int main()
Definition: overview-simple.cpp:7
pinocchio::ModelTpl
Definition: context/generic.hpp:20


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:47