overview-urdf.cpp
Go to the documentation of this file.
2 
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
18  // example.
19  const std::string urdf_filename =
20  (argc <= 1) ? PINOCCHIO_MODEL_DIR
21  + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf")
22  : argv[1];
23 
24  // Load the urdf model
25  Model model;
27  std::cout << "model name: " << model.name << std::endl;
28 
29  // Create data required by the algorithms
30  Data data(model);
31 
32  // Sample a random configuration
33  Eigen::VectorXd q = randomConfiguration(model);
34  std::cout << "q: " << q.transpose() << std::endl;
35 
36  // Perform the forward kinematics over the kinematic tree
38 
39  // Print out the placement of each joint of the kinematic tree
40  for (JointIndex joint_id = 0; joint_id < (JointIndex)model.njoints; ++joint_id)
41  std::cout << std::setw(24) << std::left << model.names[joint_id] << ": " << std::fixed
42  << std::setprecision(2) << data.oMi[joint_id].translation().transpose() << std::endl;
43 }
append-urdf-model-with-another-model.urdf_filename
string urdf_filename
Definition: append-urdf-model-with-another-model.py:16
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::forwardKinematics
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.
kinematics.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::randomConfiguration
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.
Definition: joint-configuration.hpp:315
joint-configuration.hpp
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: overview-urdf.cpp:10
urdf.hpp
pinocchio::urdf::buildModel
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...
main
int main(int argc, char **argv)
Definition: overview-urdf.cpp:13
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:32