examples/multiprecision.cpp
Go to the documentation of this file.
2 
4 
7 
8 #include <boost/multiprecision/cpp_dec_float.hpp>
9 
10 #include <iostream>
11 
12 // PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here.
13 #ifndef PINOCCHIO_MODEL_DIR
14  #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
15 #endif
16 
17 int main(int argc, char ** argv)
18 {
19  using namespace pinocchio;
20 
21  // You should change here to set up your own URDF file or just pass it as an argument of this
22  // example.
23  const std::string urdf_filename =
24  (argc <= 1) ? PINOCCHIO_MODEL_DIR
25  + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf")
26  : argv[1];
27 
28  // Load the URDF model
29  Model model;
31 
32  // Build a data related to model
33  Data data(model);
34 
35  // Define Model and Data for multiprecision types
36  typedef ::boost::multiprecision::number<
37  ::boost::multiprecision::cpp_dec_float<100>, ::boost::multiprecision::et_off>
38  float_100;
39  typedef ModelTpl<float_100> ModelMulti;
40  typedef DataTpl<float_100> DataMulti;
41 
42  ModelMulti model_multi = model.cast<float_100>();
43  DataMulti data_multi(model_multi);
44 
45  // Sample a random joint configuration as well as random joint velocity and acceleration
46  ModelMulti::ConfigVectorType q_multi = randomConfiguration(model_multi);
47  ModelMulti::TangentVectorType v_multi = ModelMulti::TangentVectorType::Random(model.nv);
48  ModelMulti::TangentVectorType a_multi = ModelMulti::TangentVectorType::Random(model.nv);
49 
50  Model::ConfigVectorType q = q_multi.cast<double>();
51  Model::TangentVectorType v = v_multi.cast<double>();
52  Model::TangentVectorType a = a_multi.cast<double>();
53 
54  // Computes the inverse dynamics (aka RNEA)
55  rnea(model, data, q, v, a);
56  rnea(model_multi, data_multi, q_multi, v_multi, a_multi);
57 
58  // Get access to the joint torque with standard or multiprecision arithmetic and print sufficient
59  // decimals for both precisions
60  std::cout << "Joint torque standard arithmetic:\n"
61  << std::setprecision(std::numeric_limits<float_100>::max_digits10) << data.tau
62  << std::endl;
63  std::cout << "Joint torque multiprecision arithmetic:\n"
64  << std::setprecision(std::numeric_limits<float_100>::max_digits10) << data_multi.tau
65  << std::endl;
66 }
append-urdf-model-with-another-model.urdf_filename
string urdf_filename
Definition: append-urdf-model-with-another-model.py:16
pinocchio::DataTpl
Definition: context/generic.hpp:25
main
int main(int argc, char **argv)
Definition: examples/multiprecision.cpp:17
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
rnea.hpp
joint-configuration.hpp
pinocchio::ModelTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: multibody/model.hpp:95
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::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
multiprecision.hpp
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::ModelTpl::ConfigVectorType
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: multibody/model.hpp:87
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: examples/multiprecision.cpp:14
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 Thu Dec 19 2024 03:41:32