Go to the documentation of this file.
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)
25 + std::string(
"/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf")
36 typedef ::boost::multiprecision::number<
37 ::boost::multiprecision::cpp_dec_float<100>, ::boost::multiprecision::et_off>
42 ModelMulti model_multi =
model.cast<float_100>();
43 DataMulti data_multi(model_multi);
47 ModelMulti::TangentVectorType v_multi = ModelMulti::TangentVectorType::Random(
model.nv);
48 ModelMulti::TangentVectorType a_multi = ModelMulti::TangentVectorType::Random(
model.nv);
56 rnea(model_multi, data_multi, q_multi, v_multi, a_multi);
60 std::cout <<
"Joint torque standard arithmetic:\n"
61 << std::setprecision(std::numeric_limits<float_100>::max_digits10) <<
data.tau
63 std::cout <<
"Joint torque multiprecision arithmetic:\n"
64 << std::setprecision(std::numeric_limits<float_100>::max_digits10) << data_multi.tau
int main(int argc, char **argv)
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)....
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...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
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...
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
#define PINOCCHIO_MODEL_DIR
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:12