1 #include "pinocchio/parsers/urdf.hpp" 3 #include "pinocchio/algorithm/joint-configuration.hpp" 4 #include "pinocchio/algorithm/kinematics.hpp" 9 #ifndef PINOCCHIO_MODEL_DIR 10 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 13 int main(
int argc,
char ** argv)
23 std::cout <<
"model name: " << model.
name << std::endl;
30 std::cout <<
"q: " << q.transpose() << std::endl;
37 std::cout << std::setw(24) << std::left
39 << std::fixed << std::setprecision(2)
40 << data.oMi[
joint_id].translation().transpose()
int njoints
Number of joints.
std::vector< std::string > names
Name of joint i
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.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_MODEL_DIR
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.
std::string name
Model name;.
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.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
int main(int argc, char **argv)
JointCollectionTpl & model