Go to the documentation of this file.
8 int main(
int ,
char ** )
24 model.lowerPositionLimit.head<3>().
fill(-1.);
25 model.upperPositionLimit.head<3>().
fill(1.);
29 Eigen::VectorXd
q(
model.nq);
31 Eigen::VectorXd
v(Eigen::VectorXd::Random(
model.nv));
32 Eigen::VectorXd
a(Eigen::VectorXd::Random(
model.nv));
42 ConfigVectorAD q_ad(
model.nq);
43 q_ad = Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_q).
data(),
model.nq, 1);
46 TangentVectorAD v_ad(
model.nv);
47 v_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v).
data(),
model.nv, 1);
50 TangentVectorAD a_ad(
model.nv);
51 a_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_a).
data(),
model.nv, 1);
54 rnea(ad_model, ad_data, q_ad, v_ad, a_ad);
55 ::casadi::SX tau_ad(
model.nv, 1);
57 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
58 tau_ad(k) = ad_data.tau[k];
60 ::casadi::Function eval_rnea(
61 "eval_rnea", ::casadi::SXVector{cs_q, cs_v, cs_a}, ::casadi::SXVector{tau_ad});
64 std::vector<double> q_vec((
size_t)
model.nq);
65 Eigen::Map<Eigen::VectorXd>(q_vec.data(),
model.nq, 1) =
q;
67 std::vector<double> v_vec((
size_t)
model.nv);
68 Eigen::Map<Eigen::VectorXd>(v_vec.data(),
model.nv, 1) =
v;
70 std::vector<double> a_vec((
size_t)
model.nv);
71 Eigen::Map<Eigen::VectorXd>(a_vec.data(),
model.nv, 1) =
a;
73 ::casadi::DM tau_casadi_res = eval_rnea(::casadi::DMVector{q_vec, v_vec, a_vec})[0];
75 static_cast<std::vector<double>
>(tau_casadi_res).
data(),
model.nv, 1);
81 std::cout <<
"pinocchio double:\n" <<
"\ttau = " <<
data.tau.transpose() << std::endl;
82 std::cout <<
"pinocchio CasADi:\n" <<
"\ttau = " << tau_casadi_vec.transpose() << std::endl;
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
void sym(const Eigen::MatrixBase< MatrixDerived > &eig_mat, std::string const &name)
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true, bool mimic=false)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
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.
DataTpl< context::Scalar, context::Options > Data
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
CppAD::AD< Scalar > ADScalar
pinocchio::ModelTpl< ADScalar > ADModel
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...
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
ModelTpl< context::Scalar, context::Options > Model
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Wed Apr 16 2025 02:41:43