overview-urdf.cpp
Go to the documentation of this file.
1 #include "pinocchio/parsers/urdf.hpp"
2 
3 #include "pinocchio/algorithm/joint-configuration.hpp"
4 #include "pinocchio/algorithm/kinematics.hpp"
5 
6 #include <iostream>
7 
8 // PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here.
9 #ifndef PINOCCHIO_MODEL_DIR
10  #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
11 #endif
12 
13 int main(int argc, char ** argv)
14 {
15  using namespace pinocchio;
16 
17  // You should change here to set up your own URDF file or just pass it as an argument of this example.
18  const std::string urdf_filename = (argc<=1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf") : argv[1];
19 
20  // Load the urdf model
21  Model model;
22  pinocchio::urdf::buildModel(urdf_filename,model);
23  std::cout << "model name: " << model.name << std::endl;
24 
25  // Create data required by the algorithms
26  Data data(model);
27 
28  // Sample a random configuration
30  std::cout << "q: " << q.transpose() << std::endl;
31 
32  // Perform the forward kinematics over the kinematic tree
33  forwardKinematics(model,data,q);
34 
35  // Print out the placement of each joint of the kinematic tree
37  std::cout << std::setw(24) << std::left
38  << model.names[joint_id] << ": "
39  << std::fixed << std::setprecision(2)
40  << data.oMi[joint_id].translation().transpose()
41  << std::endl;
42 }
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.
data
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.
Definition: timings.cpp:30
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
int main(int argc, char **argv)
JointCollectionTpl & model


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04