Go to the documentation of this file.
29 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
38 template<
typename Jo
intModel>
45 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
50 assert(
model.check(
data) &&
"data is not consistent with model.");
61 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
64 EmptyForwardStepUnaryVisitNoData<Scalar, Options, JointCollectionTpl>>
71 template<
typename Jo
intModel>
77 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
83 assert(
model.check(
data) &&
"data is not consistent with model.");
94 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
103 template<
typename Jo
intModel1,
typename Jo
intModel2>
104 EIGEN_DONT_INLINE
static void algo(
113 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
118 assert(
model.check(
data) &&
"data is not consistent with model.");
129 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
132 EmptyForwardStepBinaryVisitNoData<Scalar, Options, JointCollectionTpl>>
139 template<
typename Jo
intModel1,
typename Jo
intModel2>
140 EIGEN_DONT_INLINE
static void
146 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
152 assert(
model.check(
data) &&
"data is not consistent with model.");
164 int main(
int argc,
const char ** argv)
166 using namespace Eigen;
171 const int NBT = 1000 * 100;
174 std::cout <<
"(the time score in debug mode is not relevant) " << std::endl;
186 const std::string ff_option = argv[2];
187 if (ff_option ==
"-no-ff")
197 std::cout <<
"nq = " <<
model.nq << std::endl;
198 std::cout <<
"nv = " <<
model.nv << std::endl;
199 std::cout <<
"--" << std::endl;
202 const VectorXd qmax = Eigen::VectorXd::Ones(
model.nq);
208 for (
size_t i = 0;
i < NBT; ++
i)
211 qdots[
i] = Eigen::VectorXd::Random(
model.nv);
212 qddots[
i] = Eigen::VectorXd::Random(
model.nv);
213 taus[
i] = Eigen::VectorXd::Random(
model.nv);
221 std::cout <<
"RNEA = \t\t\t\t";
222 timer.
toc(std::cout, NBT);
229 std::cout <<
"NLE = \t\t\t\t";
230 timer.
toc(std::cout, NBT);
237 std::cout <<
"NLE via RNEA = \t\t\t";
238 timer.
toc(std::cout, NBT);
245 std::cout <<
"CRBA (original) = \t\t";
246 timer.
toc(std::cout, NBT);
253 std::cout <<
"CRBA = \t\t";
254 timer.
toc(std::cout, NBT);
261 std::cout <<
"computeAllTerms = \t\t";
262 timer.
toc(std::cout, NBT);
272 std::cout <<
"Sparse Cholesky = \t\t" << (total / NBT) <<
" "
276 Eigen::LDLT<Eigen::MatrixXd> Mldlt(
data.M);
280 data.M.triangularView<Eigen::StrictlyLower>() =
281 data.M.transpose().triangularView<Eigen::StrictlyLower>();
283 Mldlt.compute(
data.M);
286 std::cout <<
"Dense Cholesky = \t\t" << (total / NBT) <<
" " << timer.
unitName(timer.
DEFAULT_UNIT)
294 std::cout <<
"Jacobian = \t\t\t";
295 timer.
toc(std::cout, NBT);
302 std::cout <<
"Jacobian Derivative = \t\t";
303 timer.
toc(std::cout, NBT);
310 std::cout <<
"COM+Jcom = \t\t\t";
311 timer.
toc(std::cout, NBT);
318 std::cout <<
"COM+vCOM+aCOM = \t\t";
319 timer.
toc(std::cout, NBT);
326 std::cout <<
"Forward Kinematics(q) = \t";
327 timer.
toc(std::cout, NBT);
334 std::cout <<
"Forward Kinematics(q,v) = \t";
335 timer.
toc(std::cout, NBT);
342 std::cout <<
"Forward Kinematics(q,v,a) = \t";
343 timer.
toc(std::cout, NBT);
350 std::cout <<
"Frame Placement(q) = \t\t";
351 timer.
toc(std::cout, NBT);
361 std::cout <<
"Update Frame Placement = \t" << (total / NBT) <<
" "
369 std::cout <<
"CCRBA = \t\t\t";
370 timer.
toc(std::cout, NBT);
377 std::cout <<
"ABA (minimal) = \t\t";
378 timer.
toc(std::cout, NBT);
385 std::cout <<
"ABA = \t\t";
386 timer.
toc(std::cout, NBT);
393 std::cout <<
"Coriolis Matrix = \t\t";
394 timer.
toc(std::cout, NBT);
401 std::cout <<
"Minv(q) = \t\t\t";
402 timer.
toc(std::cout, NBT);
414 std::cout <<
"--" << std::endl;
421 std::cout <<
"Forward Pass(jmodel,jdata) = \t\t\t";
422 timer.
toc(std::cout, NBT);
429 std::cout <<
"Forward Pass(jmodel) = \t\t\t\t";
430 timer.
toc(std::cout, NBT);
437 std::cout <<
"Forward Pass(jmodel1,jmodel2,jdata1,jdata2) = \t";
438 timer.
toc(std::cout, NBT);
445 std::cout <<
"Forward Pass(jmodel1,jmodel2) = \t\t";
446 timer.
toc(std::cout, NBT);
448 std::cout <<
"--" << std::endl;
DataTpl< Scalar, Options, JointCollectionTpl > Data
void emptyForwardPassUnaryVisit(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
DataTpl< Scalar, Options, JointCollectionTpl > Data
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
ModelTpl< Scalar, Options, JointCollectionTpl > Model
ModelTpl< Scalar, Options, JointCollectionTpl > Model
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
Base structure for Binary visitation of two JointModels. This structure provides runners to call the ...
JointModelFreeFlyerTpl< Scalar > JointModelFreeFlyer
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & aba(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 Convention convention=Convention::LOCAL)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame....
static std::string unitName(Unit u)
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< Scalar, Options, JointCollectionTpl > Data
Base structure for Unary visitation of a JointModel. This structure provides runners to call the righ...
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & computeMinverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
pinocchio::JointIndex JointIndex
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel1 > &, const JointModelBase< JointModel2 > &)
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & jacobianCenterOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
Computes both the jacobian and the the center of mass position of a given model according to a partic...
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel1 > &, const JointModelBase< JointModel2 > &, JointDataBase< typename JointModel1::JointDataDerived > &, JointDataBase< typename JointModel2::JointDataDerived > &)
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, 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...
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects),...
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame....
int main(int argc, const char **argv)
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & decompose(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Compute the Cholesky decomposition of the joint space inertia matrix M contained in data.
void emptyForwardPassUnaryVisitNoData(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
ModelTpl< Scalar, Options, JointCollectionTpl > Model
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...
void emptyForwardPassBinaryVisit(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
void emptyForwardPassBinaryVisitNoData(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
static void algo(const JointModelBase< JointModel > &, JointDataBase< typename JointModel::JointDataDerived > &)
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
DataTpl< Scalar, Options, JointCollectionTpl > Data
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeCoriolisMatrix(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Coriolis Matrix of the Lagrangian dynamics:
void computeAllTerms(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the...
ModelTpl< Scalar, Options, JointCollectionTpl > Model
JointCollectionTpl & model
Main pinocchio namespace.
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
#define PINOCCHIO_MODEL_DIR
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
Computes the center of mass position of a given model according to a particular joint configuration....
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel > &)
pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:43:02