Go to the documentation of this file.
16 #include <boost/multiprecision/cpp_dec_float.hpp>
17 #include <boost/math/special_functions/gamma.hpp>
21 #include <boost/test/unit_test.hpp>
22 #include <boost/utility/binary.hpp>
24 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
28 using namespace boost::multiprecision;
31 cpp_dec_float_100
b = 2;
32 std::cout << std::numeric_limits<cpp_dec_float_100>::digits << std::endl;
33 std::cout << std::numeric_limits<cpp_dec_float_100>::digits10 << std::endl;
35 std::cout << std::setprecision(std::numeric_limits<cpp_dec_float_100>::max_digits10) <<
log(
b)
38 std::cout << boost::math::tgamma(
b) << std::endl;
40 std::cout << boost::math::tgamma(
b *
b) << std::endl;
43 std::cout << boost::math::tgamma(cpp_dec_float_100(1000)) << std::endl;
48 typedef boost::multiprecision::cpp_dec_float_100 float_100;
51 double initial_value = boost::math::constants::pi<double>();
52 float_100 value_100(initial_value);
53 double value_cast = value_100.convert_to<
double>();
54 BOOST_CHECK(initial_value == value_cast);
56 typedef Eigen::Matrix<float_100, Eigen::Dynamic, 1> VectorFloat100;
57 static const Eigen::DenseIndex
dim = 100;
58 Eigen::VectorXd initial_vec = Eigen::VectorXd::Random(
dim);
59 VectorFloat100 vec_float_100 = initial_vec.cast<float_100>();
60 Eigen::VectorXd
vec = vec_float_100.cast<
double>();
62 BOOST_CHECK(
vec == initial_vec);
65 #define BOOST_CHECK_IS_APPROX(double_field, multires_field, Scalar) \
66 BOOST_CHECK(double_field.isApprox(multires_field.cast<Scalar>()))
76 model.lowerPositionLimit.head<3>().
fill(-1.);
77 model.upperPositionLimit.head<3>().
fill(1.);
79 typedef boost::multiprecision::cpp_dec_float_100 float_100;
83 ModelMulti model_multi =
model.cast<float_100>();
84 DataMulti data_multi(model_multi);
87 ModelMulti::TangentVectorType v_multi = ModelMulti::TangentVectorType::Random(model_multi.nv);
88 ModelMulti::TangentVectorType a_multi = ModelMulti::TangentVectorType::Random(model_multi.nv);
89 ModelMulti::TangentVectorType tau_multi = ModelMulti::TangentVectorType::Random(model_multi.nv);
118 rnea(model_multi, data_multi, q_multi, v_multi, a_multi);
131 data_multi.M.triangularView<Eigen::StrictlyLower>() =
132 data_multi.M.transpose().triangularView<Eigen::StrictlyLower>();
135 data.M.triangularView<Eigen::StrictlyLower>() =
136 data.M.transpose().triangularView<Eigen::StrictlyLower>();
141 BOOST_AUTO_TEST_SUITE_END()
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.
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
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 >::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....
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)....
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
BOOST_AUTO_TEST_CASE(test_basic)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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...
#define BOOST_CHECK_IS_APPROX(double_field, multires_field, Scalar)
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:32