algorithm/geometry.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2022 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_algo_geometry_hpp__
6 #define __pinocchio_algo_geometry_hpp__
7 
11 
13 
14 namespace pinocchio
15 {
16 
29  template<
30  typename Scalar,
31  int Options,
32  template<typename, int>
33  class JointCollectionTpl,
34  typename ConfigVectorType>
35  inline void updateGeometryPlacements(
36  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
37  DataTpl<Scalar, Options, JointCollectionTpl> & data,
38  const GeometryModel & geom_model,
39  GeometryData & geom_data,
40  const Eigen::MatrixBase<ConfigVectorType> & q);
41 
54  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
55  inline void updateGeometryPlacements(
56  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
57  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
58  const GeometryModel & geom_model,
59  GeometryData & geom_data);
60 
78  inline void appendGeometryModel(GeometryModel & geom_model1, const GeometryModel & geom_model2);
79 
80 } // namespace pinocchio
81 
82 /* --- Details -------------------------------------------------------------------- */
83 #include "pinocchio/algorithm/geometry.hxx"
84 
85 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
86  #include "pinocchio/algorithm/geometry.txx"
87 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
88 
89 // In Pinocchio 2, this header declare computeCollision and computeDistances
90 #if defined(PINOCCHIO_WITH_HPP_FCL) && defined(PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_2)
93 #endif // PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_2
94 
95 #endif // ifndef __pinocchio_algo_geometry_hpp__
pinocchio::appendGeometryModel
void appendGeometryModel(GeometryModel &geom_model1, const GeometryModel &geom_model2)
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.
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
kinematics.hpp
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
collision.hpp
distance.hpp
data.hpp
geometry.hpp
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:26
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
collisions.geom_data
geom_data
Definition: collisions.py:45
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:37