forward-dynamics-derivatives.cpp
Go to the documentation of this file.
1 #include "pinocchio/parsers/urdf.hpp"
2 
3 #include "pinocchio/algorithm/joint-configuration.hpp"
4 #include "pinocchio/algorithm/aba-derivatives.hpp"
5 
6 #include <iostream>
7 
8 // PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here.
9 #ifndef PINOCCHIO_MODEL_DIR
10  #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
11 #endif
12 
13 int main(int argc, char ** argv)
14 {
15  using namespace pinocchio;
16 
17  // You should change here to set up your own URDF file or just pass it as an argument of this example.
18  const std::string urdf_filename = (argc<=1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf") : argv[1];
19 
20  // Load the URDF model
21  Model model;
22  pinocchio::urdf::buildModel(urdf_filename,model);
23 
24  // Build a data related to model
25  Data data(model);
26 
27  // Sample a random joint configuration as well as random joint velocity and torque
29  Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
30  Eigen::VectorXd tau = Eigen::VectorXd::Zero(model.nv);
31 
32  // Allocate result container
33  Eigen::MatrixXd djoint_acc_dq = Eigen::MatrixXd::Zero(model.nv,model.nv);
34  Eigen::MatrixXd djoint_acc_dv = Eigen::MatrixXd::Zero(model.nv,model.nv);
35  Eigen::MatrixXd djoint_acc_dtau = Eigen::MatrixXd::Zero(model.nv,model.nv);
36 
37  // Computes the forward dynamics (ABA) derivatives for all the joints of the robot
38  computeABADerivatives(model, data, q, v, tau, djoint_acc_dq, djoint_acc_dv, djoint_acc_dtau);
39 
40  // Get access to the joint acceleration
41  std::cout << "Joint acceleration: " << data.ddq.transpose() << std::endl;
42 }
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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.
#define PINOCCHIO_MODEL_DIR
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, 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...
TangentVectorType ddq
The joint accelerations computed from ABA.
Main pinocchio namespace.
Definition: timings.cpp:28
int nv
Dimension of the velocity vector space.
void computeABADerivatives(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 Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
JointCollectionTpl & model
int main(int argc, char **argv)


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