inverse-dynamics-derivatives.cpp
Go to the documentation of this file.
2 
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
18  // example.
19  const std::string urdf_filename =
20  (argc <= 1) ? PINOCCHIO_MODEL_DIR
21  + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf")
22  : argv[1];
23 
24  // Load the URDF model
25  Model model;
27 
28  // Build a data related to model
29  Data data(model);
30 
31  // Sample a random joint configuration as well as random joint velocity and acceleration
32  Eigen::VectorXd q = randomConfiguration(model);
33  Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
34  Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
35 
36  // Allocate result container
37  Eigen::MatrixXd djoint_torque_dq = Eigen::MatrixXd::Zero(model.nv, model.nv);
38  Eigen::MatrixXd djoint_torque_dv = Eigen::MatrixXd::Zero(model.nv, model.nv);
39  Eigen::MatrixXd djoint_torque_da = Eigen::MatrixXd::Zero(model.nv, model.nv);
40 
41  // Computes the inverse dynamics (RNEA) derivatives for all the joints of the robot
43  model, data, q, v, a, djoint_torque_dq, djoint_torque_dv, djoint_torque_da);
44 
45  // Get access to the joint torque
46  std::cout << "Joint torque: " << data.tau.transpose() << std::endl;
47 }
append-urdf-model-with-another-model.urdf_filename
string urdf_filename
Definition: append-urdf-model-with-another-model.py:15
pinocchio::computeRNEADerivatives
void computeRNEADerivatives(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, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da)
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint c...
pinocchio::DataTpl
Definition: context/generic.hpp:25
rnea-derivatives.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::randomConfiguration
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.
Definition: joint-configuration.hpp:315
joint-configuration.hpp
main
int main(int argc, char **argv)
Definition: inverse-dynamics-derivatives.cpp:13
urdf.hpp
pinocchio::urdf::buildModel
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...
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: inverse-dynamics-derivatives.cpp:10
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1084
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


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