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> class JointCollectionTpl,
33  typename ConfigVectorType>
34  inline void updateGeometryPlacements(
35  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
36  DataTpl<Scalar, Options, JointCollectionTpl> & data,
37  const GeometryModel & geom_model,
38  GeometryData & geom_data,
39  const Eigen::MatrixBase<ConfigVectorType> & q);
40 
53  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
54  inline void updateGeometryPlacements(
55  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
56  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
57  const GeometryModel & geom_model,
58  GeometryData & geom_data);
59 
77  inline void appendGeometryModel(GeometryModel & geom_model1, const GeometryModel & geom_model2);
78 
79 } // namespace pinocchio
80 
81 /* --- Details -------------------------------------------------------------------- */
82 #include "pinocchio/algorithm/geometry.hxx"
83 
84 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
85  #include "pinocchio/algorithm/geometry.txx"
86 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
87 
88 // In Pinocchio 2, this header declare computeCollision and computeDistances
89 #if defined(PINOCCHIO_WITH_HPP_FCL) && defined(PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_2)
92 #endif // PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_2
93 
94 #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:1082
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:25
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
collisions.geom_data
geom_data
Definition: collisions.py:42
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:44