#include <geometry.hpp>

Public Types | |
| enum | { Options = _Options } |
| typedef Base::Data | Data |
| typedef Base::DataVector | DataVector |
| typedef ::pinocchio::GeometryData | GeometryData |
| typedef std::vector< GeometryData, Eigen::aligned_allocator< GeometryData > > | GeometryDataVector |
| typedef ::pinocchio::GeometryModel | GeometryModel |
| typedef std::vector< GeometryModel, Eigen::aligned_allocator< GeometryModel > > | GeometryModelVector |
| typedef Base::Model | Model |
| typedef _Scalar | Scalar |
Public Types inherited from pinocchio::ModelPoolTpl< _Scalar, _Options, JointCollectionTpl > | |
| enum | { Options = _Options } |
| typedef DataTpl< Scalar, Options, JointCollectionTpl > | Data |
| typedef std::vector< Data, Eigen::aligned_allocator< Data > > | DataVector |
| typedef ModelTpl< Scalar, Options, JointCollectionTpl > | Model |
| typedef std::vector< Model, Eigen::aligned_allocator< Model > > | ModelVector |
Public Member Functions | |
| const GeometryData & | geometry_data (const size_t index) const |
| Returns the geometry_data at index. More... | |
| GeometryData & | geometry_data (const size_t index) |
| Returns the geometry_data at index. More... | |
| const GeometryDataVector & | geometry_datas () const |
| Vector of Geometry Data. More... | |
| GeometryDataVector & | geometry_datas () |
| Vector of Geometry Data. More... | |
| const GeometryModel & | geometry_model () const |
| Returns the geometry model. More... | |
| GeometryModel & | geometry_model () |
| Returns the geometry model. More... | |
| GeometryPoolTpl (const Model &model, const GeometryModel &geometry_model, const int pool_size=omp_get_max_threads()) | |
| Default constructor from a model and a pool size. More... | |
| GeometryPoolTpl (const GeometryPoolTpl &other) | |
| Copy constructor from an other GeometryPoolTpl. More... | |
| void | update (const GeometryData &geometry_data) |
| Update the geometry datas with the new value. More... | |
| void | update (const GeometryModel &geometry_model) |
| Update the geometry model with the new input value. In this case, all the geometry_datas will be replaced. More... | |
| void | update (const GeometryModel &geometry_model, const GeometryData &geometry_data) |
| Update the geometry model and data with the new input values. In this case, all the geometry_datas will be replaced. More... | |
| virtual | ~GeometryPoolTpl () |
| . More... | |
Public Member Functions inherited from pinocchio::ModelPoolTpl< _Scalar, _Options, JointCollectionTpl > | |
| const Data & | data (const size_t index) const |
| Return a specific data. More... | |
| Data & | data (const size_t index) |
| Returns a specific data. More... | |
| const DataVector & | datas () const |
| Returns the data vectors. More... | |
| DataVector & | datas () |
| Returns the data vectors. More... | |
| const Model & | model () const |
| Returns the model stored within the pool. More... | |
| Model & | model () |
| Returns the model stored within the pool. More... | |
| ModelPoolTpl (const Model &model, const int pool_size=omp_get_max_threads()) | |
| Default constructor from a model and a pool size. More... | |
| ModelPoolTpl (const ModelPoolTpl &pool_model) | |
| Copy constructor from an other PoolModel. More... | |
| void | resize (const int new_size) |
| Set the size of the pool and perform the appropriate resize. More... | |
| int | size () const |
| Returns the size of the pool. More... | |
| void | update (const Model &model) |
| Update the model, meaning that all the datas will be refreshed accordingly. More... | |
| void | update (const Data &data) |
| Update all the datas with the input data value. More... | |
| void | update (const Model &model, const Data &data) |
| Update the model and data with the new input values. In this case, all the geometry_datas will be replaced. More... | |
| virtual | ~ModelPoolTpl () |
| . More... | |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelPoolTpl< _Scalar, _Options, JointCollectionTpl > | Base |
Public Attributes inherited from pinocchio::ModelPoolTpl< _Scalar, _Options, JointCollectionTpl > | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Protected Member Functions | |
| virtual void | do_resize (const int new_size) |
| . More... | |
Protected Attributes | |
| GeometryDataVector | m_geometry_datas |
| Vector of Geometry Data associated to the pool. More... | |
| GeometryModel | m_geometry_model |
| Geometry Model associated to the pool. More... | |
Protected Attributes inherited from pinocchio::ModelPoolTpl< _Scalar, _Options, JointCollectionTpl > | |
| DataVector | m_datas |
| . More... | |
| Model | m_model |
| Model stored within the pool. More... | |
| int | m_size |
| Number of threads used for parallel computations. More... | |
Definition at line 16 of file src/multibody/pool/geometry.hpp.
| typedef Base::Data pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::Data |
Definition at line 28 of file src/multibody/pool/geometry.hpp.
| typedef Base::DataVector pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::DataVector |
Definition at line 29 of file src/multibody/pool/geometry.hpp.
| typedef ::pinocchio::GeometryData pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::GeometryData |
Definition at line 31 of file src/multibody/pool/geometry.hpp.
| typedef std::vector<GeometryData,Eigen::aligned_allocator<GeometryData> > pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::GeometryDataVector |
Definition at line 34 of file src/multibody/pool/geometry.hpp.
| typedef ::pinocchio::GeometryModel pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::GeometryModel |
Definition at line 30 of file src/multibody/pool/geometry.hpp.
| typedef std::vector<GeometryModel,Eigen::aligned_allocator<GeometryModel> > pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::GeometryModelVector |
Definition at line 33 of file src/multibody/pool/geometry.hpp.
| typedef Base::Model pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::Model |
Definition at line 27 of file src/multibody/pool/geometry.hpp.
| typedef _Scalar pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::Scalar |
Definition at line 24 of file src/multibody/pool/geometry.hpp.
| anonymous enum |
| Enumerator | |
|---|---|
| Options | |
Definition at line 25 of file src/multibody/pool/geometry.hpp.
|
inline |
Default constructor from a model and a pool size.
| [in] | model | input model used for parallel computations. |
| [in] | geometry_model | input geometry model used for parallel computations. |
| [in] | pool_size | total size of the pool. |
Definition at line 42 of file src/multibody/pool/geometry.hpp.
|
inline |
Copy constructor from an other GeometryPoolTpl.
| [in] | other | GeometryPoolTpl to copy. |
Definition at line 53 of file src/multibody/pool/geometry.hpp.
|
inlinevirtual |
|
inlineprotectedvirtual |
.
Method to implement in the derived classes.
Reimplemented from pinocchio::ModelPoolTpl< _Scalar, _Options, JointCollectionTpl >.
Definition at line 141 of file src/multibody/pool/geometry.hpp.
|
inline |
Returns the geometry_data at index.
Definition at line 66 of file src/multibody/pool/geometry.hpp.
|
inline |
Returns the geometry_data at index.
Definition at line 74 of file src/multibody/pool/geometry.hpp.
|
inline |
Vector of Geometry Data.
Definition at line 82 of file src/multibody/pool/geometry.hpp.
|
inline |
Vector of Geometry Data.
Definition at line 85 of file src/multibody/pool/geometry.hpp.
|
inline |
Returns the geometry model.
Definition at line 60 of file src/multibody/pool/geometry.hpp.
|
inline |
Returns the geometry model.
Definition at line 63 of file src/multibody/pool/geometry.hpp.
|
inline |
Update the geometry datas with the new value.
| [in] | geometry_data | new geometry data value |
Definition at line 97 of file src/multibody/pool/geometry.hpp.
|
inline |
Update the geometry model with the new input value. In this case, all the geometry_datas will be replaced.
| [in] | geometry_model | new geometry model value. |
Definition at line 108 of file src/multibody/pool/geometry.hpp.
|
inline |
Update the geometry model and data with the new input values. In this case, all the geometry_datas will be replaced.
| [in] | geometry_model | new geometry model value. |
| [in] | geometry_data | new geometry data value |
Definition at line 122 of file src/multibody/pool/geometry.hpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelPoolTpl<_Scalar,_Options,JointCollectionTpl> pinocchio::GeometryPoolTpl< _Scalar, _Options, JointCollectionTpl >::Base |
Definition at line 23 of file src/multibody/pool/geometry.hpp.
|
protected |
Vector of Geometry Data associated to the pool.
Definition at line 138 of file src/multibody/pool/geometry.hpp.
|
protected |
Geometry Model associated to the pool.
Definition at line 130 of file src/multibody/pool/geometry.hpp.