1 #include "pinocchio/math/multiprecision.hpp" 3 #include "pinocchio/parsers/urdf.hpp" 5 #include "pinocchio/algorithm/joint-configuration.hpp" 6 #include "pinocchio/algorithm/rnea.hpp" 8 #include <boost/multiprecision/cpp_dec_float.hpp> 13 #ifndef PINOCCHIO_MODEL_DIR 14 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 17 int main(
int argc,
char ** argv)
32 typedef boost::multiprecision::cpp_dec_float_100 float_100;
36 ModelMulti model_multi = model.
cast<float_100>();
37 DataMulti data_multi(model_multi);
41 ModelMulti::TangentVectorType v_multi = ModelMulti::TangentVectorType::Random(model.
nv);
42 ModelMulti::TangentVectorType a_multi = ModelMulti::TangentVectorType::Random(model.
nv);
49 rnea(model, data, q, v, a);
50 rnea(model_multi , data_multi , q_multi , v_multi , a_multi);
53 std::cout <<
"Joint torque standard arithmetic:\n" << std::setprecision(std::numeric_limits<float_100>::max_digits10) << data.
tau << std::endl;
54 std::cout <<
"Joint torque multiprecision arithmetic:\n" << std::setprecision(std::numeric_limits<float_100>::max_digits10) << data_multi.tau << std::endl;
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
TangentVectorType tau
Vector of joint torques (dim model.nv).
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
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.
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc). It also handles the notion of co-tangent vector (e.g. torque, etc).
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_MODEL_DIR
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...
Main pinocchio namespace.
int nv
Dimension of the velocity vector space.
int main(int argc, char **argv)
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
JointCollectionTpl & model
ModelTpl< NewScalar, Options, JointCollectionTpl > cast() const