geometry-models.cpp
Go to the documentation of this file.
3 
7 
8 #include <iostream>
9 
10 // PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here.
11 #ifndef PINOCCHIO_MODEL_DIR
12  #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
13 #endif
14 
15 int main(int argc, char ** argv)
16 {
17  using namespace pinocchio;
18 
19  const std::string model_path =
20  (argc <= 1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots") : argv[1];
21  const std::string mesh_dir = (argc <= 1) ? PINOCCHIO_MODEL_DIR : argv[1];
22  const std::string urdf_filename = model_path + "/ur_description/urdf/ur5_robot.urdf";
23 
24  // Load the urdf model
25  Model model;
31  std::cout << "model name: " << model.name << std::endl;
32 
33  // Create data required by the algorithms
34  Data data(model);
37 
38  // Sample a random configuration
39  Eigen::VectorXd q = randomConfiguration(model);
40  std::cout << "q: " << q.transpose() << std::endl;
41 
42  // Perform the forward kinematics over the kinematic tree
44 
45  // Update Geometry models
48 
49  // Print out the placement of each joint of the kinematic tree
50  std::cout << "\nJoint placements:" << std::endl;
51  for (JointIndex joint_id = 0; joint_id < (JointIndex)model.njoints; ++joint_id)
52  std::cout << std::setw(24) << std::left << model.names[joint_id] << ": " << std::fixed
53  << std::setprecision(2) << data.oMi[joint_id].translation().transpose() << std::endl;
54 
55  // Print out the placement of each collision geometry object
56  std::cout << "\nCollision object placements:" << std::endl;
57  for (GeomIndex geom_id = 0; geom_id < (GeomIndex)collision_model.ngeoms; ++geom_id)
58  std::cout << geom_id << ": " << std::fixed << std::setprecision(2)
59  << collision_data.oMg[geom_id].translation().transpose() << std::endl;
60 
61  // Print out the placement of each visual geometry object
62  std::cout << "\nVisual object placements:" << std::endl;
63  for (GeomIndex geom_id = 0; geom_id < (GeomIndex)visual_model.ngeoms; ++geom_id)
64  std::cout << geom_id << ": " << std::fixed << std::setprecision(2)
65  << visual_data.oMg[geom_id].translation().transpose() << std::endl;
66 }
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.
pinocchio::updateGeometryPlacements
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q)
Apply a forward kinematics and update the placement of the geometry objects.
append-urdf-model-with-another-model.visual_model
visual_model
Definition: append-urdf-model-with-another-model.py:62
geometry-models.visual_data
visual_data
Definition: geometry-models.py:21
append-urdf-model-with-another-model.model_path
model_path
Definition: append-urdf-model-with-another-model.py:14
build-reduced-model.collision_model
collision_model
Definition: build-reduced-model.py:15
kinematics.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::GeometryData
Definition: multibody/geometry.hpp:233
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:325
fcl.hpp
main
int main(int argc, char **argv)
Definition: geometry-models.cpp:15
pinocchio::VISUAL
@ VISUAL
Definition: multibody/geometry-object.hpp:26
joint-configuration.hpp
geometry.hpp
pinocchio::urdf::buildModel
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...
urdf.hpp
append-urdf-model-with-another-model.mesh_dir
mesh_dir
Definition: append-urdf-model-with-another-model.py:15
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: geometry-models.cpp:12
pinocchio::urdf::buildGeom
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
collision-with-point-clouds.collision_data
collision_data
Definition: collision-with-point-clouds.py:113
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::GeomIndex
Index GeomIndex
Definition: multibody/fwd.hpp:27
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sun Jun 16 2024 02:43:10