5 #ifndef __pinocchio_algo_geometry_hpp__ 6 #define __pinocchio_algo_geometry_hpp__ 8 #include "pinocchio/multibody/visitor.hpp" 9 #include "pinocchio/multibody/model.hpp" 10 #include "pinocchio/multibody/data.hpp" 12 #include "pinocchio/algorithm/kinematics.hpp" 13 #include "pinocchio/multibody/geometry.hpp" 30 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
32 DataTpl<Scalar,Options,JointCollectionTpl> & data,
35 const Eigen::MatrixBase<ConfigVectorType> &
q);
47 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
49 const DataTpl<Scalar,Options,JointCollectionTpl> & data,
61 template<
typename Vector3Like>
65 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
85 #ifdef PINOCCHIO_WITH_HPP_FCL 115 const bool stopAtFirstCollision =
false);
135 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
140 const Eigen::MatrixBase<ConfigVectorType> &
q,
141 const bool stopAtFirstCollision =
false);
154 fcl::DistanceResult & computeDistance(
const GeometryModel & geom_model,
173 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
178 const Eigen::MatrixBase<ConfigVectorType> & q);
193 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
208 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
212 #endif // PINOCCHIO_WITH_HPP_FCL 237 #include "pinocchio/algorithm/geometry.hxx" 239 #endif // ifndef __pinocchio_algo_geometry_hpp__
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.
void appendGeometryModel(GeometryModel &geom_model1, const GeometryModel &geom_model2)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
Index ngeoms
The number of GeometryObjects.
Main pinocchio namespace.
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.
JointCollectionTpl & model