algorithm/geometry.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_algo_geometry_hpp__
6 #define __pinocchio_algo_geometry_hpp__
7 
11 
14 
15 namespace pinocchio
16 {
17 
30  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
31  inline void updateGeometryPlacements(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
32  DataTpl<Scalar,Options,JointCollectionTpl> & data,
33  const GeometryModel & geom_model,
34  GeometryData & geom_data,
35  const Eigen::MatrixBase<ConfigVectorType> & q);
36 
47  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
48  inline void updateGeometryPlacements(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
49  const DataTpl<Scalar,Options,JointCollectionTpl> & data,
50  const GeometryModel & geom_model,
51  GeometryData & geom_data);
52 
61  template<typename Vector3Like>
62  PINOCCHIO_DEPRECATED
63  inline void setGeometryMeshScales(GeometryModel & geom_model, const Eigen::MatrixBase<Vector3Like> & meshScale)
64  {
65  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
66  for(GeomIndex index=0; index<geom_model.ngeoms; index++)
67  geom_model.geometryObjects[index].meshScale = meshScale;
68  }
69 
78  PINOCCHIO_DEPRECATED
80  {
81  for(GeomIndex index=0; index<geom_model.ngeoms; index++)
82  geom_model.geometryObjects[index].meshScale.setConstant(meshScale);
83  }
84 
85 #ifdef PINOCCHIO_WITH_HPP_FCL
86 
98  bool computeCollision(const GeometryModel & geom_model,
99  GeometryData & geom_data,
100  const PairIndex pair_id);
101 
113  inline bool computeCollisions(const GeometryModel & geom_model,
114  GeometryData & geom_data,
115  const bool stopAtFirstCollision = false);
116 
135  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
136  inline bool computeCollisions(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
137  DataTpl<Scalar,Options,JointCollectionTpl> & data,
138  const GeometryModel & geom_model,
139  GeometryData & geom_data,
140  const Eigen::MatrixBase<ConfigVectorType> & q,
141  const bool stopAtFirstCollision = false);
142 
154  fcl::DistanceResult & computeDistance(const GeometryModel & geom_model,
155  GeometryData & geom_data,
156  const PairIndex pair_id);
157 
173  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
174  inline std::size_t computeDistances(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
175  DataTpl<Scalar,Options,JointCollectionTpl> & data,
176  const GeometryModel & geom_model,
177  GeometryData & geom_data,
178  const Eigen::MatrixBase<ConfigVectorType> & q);
179 
193  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
194  inline std::size_t computeDistances(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
195  const DataTpl<Scalar,Options,JointCollectionTpl> & data,
196  const GeometryModel & geom_model,
197  GeometryData & geom_data);
198 
208  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
209  inline void computeBodyRadius(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
210  const GeometryModel & geom_model,
211  GeometryData & geom_data);
212 #endif // PINOCCHIO_WITH_HPP_FCL
213 
231  inline void appendGeometryModel(GeometryModel & geom_model1,
232  const GeometryModel & geom_model2);
233 
234 } // namespace pinocchio
235 
236 /* --- Details -------------------------------------------------------------------- */
237 #include "pinocchio/algorithm/geometry.hxx"
238 
239 #endif // ifndef __pinocchio_algo_geometry_hpp__
pinocchio::appendGeometryModel
void appendGeometryModel(GeometryModel &geom_model1, const GeometryModel &geom_model2)
pinocchio::computeCollisions
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
Definition: algorithm/parallel/geometry.hpp:16
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::setGeometryMeshScales
PINOCCHIO_DEPRECATED void setGeometryMeshScales(GeometryModel &geom_model, const Eigen::MatrixBase< Vector3Like > &meshScale)
Set a mesh scaling vector to each GeometryObject contained in the the GeometryModel.
Definition: algorithm/geometry.hpp:63
index
index
kinematics.hpp
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
visitor.hpp
meshcat-viewer-dae.meshScale
meshScale
Definition: meshcat-viewer-dae.py:28
data.hpp
pinocchio::PairIndex
Index PairIndex
Definition: multibody/fwd.hpp:31
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:747
collisions.geom_data
geom_data
Definition: collisions.py:39
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:22
pinocchio::GeomIndex
Index GeomIndex
Definition: multibody/fwd.hpp:29
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:746
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:58