Namespaces | Classes | Typedefs | Functions | Variables
next_best_view Namespace Reference

this namespace contains all generally usable classes. More...

Namespaces

 msg
 

Classes

struct  BaseScoreContainer
 BaseScore implements no such functionalities, but the corresponding RatingModule has to implement a BaseScore class itself. More...
 
class  CameraModelFilter
 CameraModelFilter class was built to generalize the filtering for different camera models. More...
 
class  CameraModelFilterAbstractFactory
 
class  CommonClass
 
class  CropBoxFilter
 The CropBoxFilter class, used to filter objects in crop boxes. More...
 
class  CropBoxWrapper
 
class  DebugHelper
 The DebugHelper class is responsible for debug output. More...
 
class  DefaultHypothesisUpdater
 
class  DefaultHypothesisUpdaterFactory
 
class  DefaultRatingModule
 DefaultRatingModule implements the functionlities offered by RatingModule. More...
 
class  DefaultRatingModuleFactory
 
struct  DefaultScoreContainer
 DefaultScoreContainer implements the BaseScoreContainer base class. More...
 
struct  DefaultViewportPoint
 DefaultViewportPoint. More...
 
class  GeneralFilter
 
class  HypothesisUpdater
 HypothesisUpdater is an abstract class for updating the objects in the point cloud. More...
 
class  HypothesisUpdaterAbstractFactory
 
class  MapBasedHexagonSpaceSampler
 MapBasedHexagonSpaceSampler implements the space sampling with a hexagon pattern. More...
 
class  MapBasedHexagonSpaceSamplerFactory
 
class  MapBasedRandomSpaceSampler
 
class  MapBasedRandomSpaceSamplerFactory
 
class  MapHelper
 
class  MarkerHelper
 MarkerHelper is a convenience class to reduce the mess created if marker initialization is used by hand. More...
 
class  MathHelper
 MathHelper unites the generally needed math operations. More...
 
class  NextBestView
 NextBestView is a configuration class of the related node. More...
 
class  NextBestViewCalculator
 
class  ObjectHelper
 
class  PerspectiveHypothesisUpdater
 
class  PerspectiveHypothesisUpdaterFactory
 
class  PlaneSubSpaceSampler
 PlaneSubSpaceSampler implements the space sampling in a plane. More...
 
class  PlaneSubSpaceSamplerFactory
 
class  RatingModule
 RatingModule is a generalization for the rating of the point cloud objects and viewports. More...
 
class  RatingModuleAbstractFactory
 
class  Raytracing2DBasedSpaceSampler
 Raytracing2DBasedSpaceSampler. More...
 
class  Raytracing2DBasedSpaceSamplerFactory
 
struct  RayTracingIndex
 
struct  RealObjectPoint
 RealObjectPoint. More...
 
class  SingleCameraModelFilter
 SingleCameraModelFilter class implements the frustum filter for a single camera. More...
 
class  SingleCameraModelFilterFactory
 
struct  SpaceSamplePoint
 SpaceSamplePoint. More...
 
class  SpaceSampler
 SpaceSampler class generalizes the sampling of the space. More...
 
class  SpaceSamplerAbstractFactory
 
class  SpiralApproxUnitSphereSampler
 SpiralApproxUnitSphereSampler samples a unit sphere in a spiral manner. More...
 
class  SpiralApproxUnitSphereSamplerFactory
 
class  StereoCameraModelFilter
 StereoCameraModelFilter class implements the frustum filtering for stereo cameras. More...
 
class  StereoCameraModelFilterFactory
 
class  TypeHelper
 
class  UnitSphereSampler
 UnitSphereSampler samples a unit sphere. More...
 
class  UnitSphereSamplerAbstractFactory
 
class  VisualizationHelper
 

Typedefs

typedef boost::shared_ptr< BaseScoreContainerBaseScoreContainerPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< CameraModelFilterAbstractFactoryCameraModelFilterAbstractFactoryPtr
 
typedef boost::shared_ptr< CameraModelFilterCameraModelFilterPtr
 Definition for the shared pointer type of the class. More...
 
typedef SimpleVector4 Color
 
typedef pcl::CropBox< ObjectPointCropBox
 
typedef boost::shared_ptr< CropBoxFilterCropBoxFilterPtr
 CropBoxFilterPtr typedef for consistency/less code to create boost::shared_ptr to CropBoxFilter. More...
 
typedef CropBox::Ptr CropBoxPtr
 
typedef boost::shared_ptr< CropBoxWrapperCropBoxWrapperPtr
 
typedef boost::shared_ptr< DebugHelperDebugHelperPtr
 
typedef boost::shared_ptr< DefaultHypothesisUpdaterFactoryDefaultHypothesisUpdaterFactoryPtr
 
typedef boost::shared_ptr< DefaultHypothesisUpdaterDefaultHypothesisUpdaterPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< DefaultRatingModuleFactoryDefaultRatingModuleFactoryPtr
 
typedef boost::shared_ptr< DefaultRatingModuleDefaultRatingModulePtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< DefaultScoreContainerDefaultScoreContainerPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< DefaultViewportPointDefaultViewportPointPtr
 
typedef boost::shared_ptr< asr_next_best_view::DynamicParametersConfig > DynamicParametersConfigPtr
 
typedef pcl::FrustumCulling< ObjectPointFrustumCulling
 
typedef FrustumCulling::Ptr FrustumCullingPtr
 
typedef boost::shared_ptr< GeneralFilterGeneralFilterPtr
 
typedef Eigen::Matrix< int, 3, 1 > GridVector3
 
typedef boost::shared_ptr< HypothesisUpdaterAbstractFactoryHypothesisUpdaterAbstractFactoryPtr
 
typedef boost::shared_ptr< HypothesisUpdaterHypothesisUpdaterPtr
 Definition for the shared pointer type of the class. More...
 
typedef std::vector< int > Indices
 
typedef boost::shared_ptr< const IndicesPtrIndicesConstPtr
 
typedef boost::shared_ptr< IndicesIndicesPtr
 
typedef asr_world_model::GetIntermediateObjectWeight::Response IntermediateObjectWeightResponse
 
typedef IntermediateObjectWeightResponse::Ptr IntermediateObjectWeightResponsePtr
 
typedef pcl::KdTreeFLANN< ObjectPointKdTree
 
typedef KdTree::ConstPtr KdTreeConstPtr
 
typedef KdTree::Ptr KdTreePtr
 
typedef boost::shared_ptr< MapBasedHexagonSpaceSamplerFactoryMapBasedHexagonSpaceSamplerFactoryPtr
 
typedef boost::shared_ptr< MapBasedHexagonSpaceSamplerMapBasedHexagonSpaceSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< MapBasedRandomSpaceSamplerFactoryMapBasedRandomSpaceSamplerFactoryPtr
 
typedef boost::shared_ptr< MapBasedRandomSpaceSamplerMapBasedRandomSpaceSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< Raytracing2DBasedSpaceSamplerMapBasedSpaceSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< MapHelperMapHelperPtr
 
typedef asr_object_database::ObjectMetaData::Response ObjectMetaDataResponse
 
typedef ObjectMetaDataResponse::Ptr ObjectMetaDataResponsePtr
 
typedef RealObjectPoint ObjectPoint
 
typedef pcl::PointCloud< ObjectPointObjectPointCloud
 
typedef ObjectPointCloud::ConstPtr ObjectPointCloudConstPtr
 
typedef ObjectPointCloud::Ptr ObjectPointCloudPtr
 
typedef std::vector< std::string > ObjectTypeList
 
typedef boost::shared_ptr< ObjectTypeListObjectTypeListPtr
 
typedef std::set< ObjectTypeSetPtrObjectTypePowerSet
 
typedef boost::shared_ptr< ObjectTypePowerSetObjectTypePowerSetPtr
 
typedef std::set< std::string > ObjectTypeSet
 
typedef boost::shared_ptr< ObjectTypeSetObjectTypeSetPtr
 
typedef boost::shared_ptr< PerspectiveHypothesisUpdaterFactoryPerspectiveHypothesisUpdaterFactoryPtr
 
typedef boost::shared_ptr< PerspectiveHypothesisUpdaterPerspectiveHypothesisUpdaterPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< PlaneSubSpaceSamplerFactoryPlaneSubSpaceSamplerFactoryPtr
 
typedef boost::shared_ptr< PlaneSubSpaceSamplerPlaneSubSpaceSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef float Precision
 
typedef boost::shared_ptr< RatingModuleAbstractFactoryRatingModuleAbstractFactoryPtr
 
typedef boost::shared_ptr< RatingModuleRatingModulePtr
 Definition for the shared pointer type of the class. More...
 
typedef std::vector< RayTracingIndexRay
 
typedef boost::shared_ptr< Raytracing2DBasedSpaceSamplerFactoryRaytracing2DBasedSpaceSamplerFactoryPtr
 
typedef boost::shared_ptr< RayTracingIndexRayTracingIndexPtr
 
typedef boost::shared_ptr< RealObjectPointRealObjectPointPtr
 
typedef SpaceSamplePoint SamplePoint
 
typedef pcl::PointCloud< SamplePointSamplePointCloud
 
typedef SamplePointCloud::ConstPtr SamplePointCloudConstPtr
 
typedef SamplePointCloud::Ptr SamplePointCloudPtr
 
typedef Eigen::Matrix< Precision, 2, 2 > SimpleMatrix2
 
typedef Eigen::Matrix< Precision, 3, 3 > SimpleMatrix3
 
typedef std::vector< SimpleMatrix3, Eigen::aligned_allocator< SimpleMatrix3 > > SimpleMatrix3Collection
 
typedef boost::shared_ptr< SimpleMatrix3CollectionSimpleMatrix3CollectionPtr
 
typedef Eigen::Matrix< Precision, 4, 4 > SimpleMatrix4
 
typedef std::vector< SimpleMatrix4, Eigen::aligned_allocator< SimpleMatrix4 > > SimpleMatrix4Collection
 
typedef boost::shared_ptr< SimpleMatrix4CollectionSimpleMatrix4CollectionPtr
 
typedef Eigen::Matrix< Precision, Eigen::Dynamic, Eigen::Dynamic > SimpleMatrixX
 
typedef Eigen::Quaternion< PrecisionSimpleQuaternion
 
typedef std::vector< SimpleQuaternion, Eigen::aligned_allocator< SimpleQuaternion > > SimpleQuaternionCollection
 
typedef boost::shared_ptr< SimpleQuaternionCollectionSimpleQuaternionCollectionPtr
 
typedef SimpleVector3 SimpleSphereCoordinates
 
typedef Eigen::Matrix< Precision, 2, 1 > SimpleVector2
 
typedef Eigen::Matrix< Precision, 3, 1 > SimpleVector3
 
typedef std::vector< SimpleVector3, Eigen::aligned_allocator< SimpleVector3 > > SimpleVector3Collection
 
typedef boost::shared_ptr< SimpleVector3CollectionSimpleVector3CollectionPtr
 
typedef Eigen::Matrix< Precision, 4, 1 > SimpleVector4
 
typedef std::vector< SimpleVector4, Eigen::aligned_allocator< SimpleVector4 > > SimpleVector4Collection
 
typedef boost::shared_ptr< SimpleVector4CollectionSimpleVector4CollectionPtr
 
typedef Eigen::Matrix< Precision, Eigen::Dynamic, 1 > SimpleVectorX
 
typedef boost::shared_ptr< SingleCameraModelFilterFactorySingleCameraModelFilterFactoryPtr
 
typedef boost::shared_ptr< SingleCameraModelFilterSingleCameraModelFilterPtr
 the type definition for the corresponding shared pointer of the class. More...
 
typedef boost::shared_ptr< SpaceSamplePointSpaceSamplePointPtr
 
typedef boost::shared_ptr< SpaceSamplerAbstractFactorySpaceSamplerAbstractFactoryPtr
 
typedef boost::shared_ptr< SpaceSamplerSpaceSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef boost::shared_ptr< SpiralApproxUnitSphereSamplerFactorySpiralApproxUnitSphereSamplerFactoryPtr
 
typedef boost::shared_ptr< SpiralApproxUnitSphereSamplerSpiralApproxUnitSphereSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef std::vector< float > SquaredDistances
 
typedef boost::shared_ptr< StereoCameraModelFilterFactoryStereoCameraModelFilterFactoryPtr
 
typedef boost::shared_ptr< StereoCameraModelFilterStereoCameraModelFilterPtr
 the type definition for the corresponding shared pointer of the class. More...
 
typedef boost::shared_ptr< UnitSphereSamplerAbstractFactoryUnitSphereSamplerAbstractFactoryPtr
 
typedef boost::shared_ptr< UnitSphereSamplerUnitSphereSamplerPtr
 Definition for the shared pointer type of the class. More...
 
typedef DefaultViewportPoint ViewportPoint
 
typedef pcl::PointCloud< ViewportPointViewportPointCloud
 
typedef ViewportPointCloud::ConstPtr ViewportPointCloudConstPtr
 
typedef ViewportPointCloud::Ptr ViewportPointCloudPtr
 
typedef boost::shared_ptr< VisualizationHelperVisualizationHelperPtr
 
typedef pcl::PointXYZ WorldPoint
 
typedef pcl::PointCloud< WorldPointWorldPointCloud
 
typedef WorldPointCloud::ConstPtr WorldPointCloudConstPtr
 
typedef WorldPointCloud::Ptr WorldPointCloudPtr
 

Functions

std::ostream & operator<< (std::ostream &strm, const next_best_view::SpaceSamplePoint &p)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::SpaceSamplePointPtr &p)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::RealObjectPoint &p)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::RealObjectPointPtr &p)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::DefaultViewportPoint &p)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::DefaultViewportPointPtr &p)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::DefaultScoreContainer &score)
 
std::ostream & operator<< (std::ostream &strm, const next_best_view::DefaultScoreContainerPtr &score)
 

Variables

struct next_best_view::DefaultViewportPoint EIGEN_ALIGN16
 

Detailed Description

this namespace contains all generally usable classes.

Copyright (c) 2016, Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
  3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
  4. The use is explicitly not permitted to any application which deliberately try to kill or do harm to any living creature.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Typedef Documentation

Definition for the shared pointer type of the class.

Definition at line 66 of file BaseScoreContainer.hpp.

Definition at line 31 of file CameraModelFilterAbstractFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 208 of file CameraModelFilter.hpp.

Definition at line 130 of file typedef.hpp.

typedef pcl::CropBox<ObjectPoint> next_best_view::CropBox

Definition at line 105 of file typedef.hpp.

CropBoxFilterPtr typedef for consistency/less code to create boost::shared_ptr to CropBoxFilter.

Definition at line 58 of file CropBoxFilter.hpp.

typedef CropBox::Ptr next_best_view::CropBoxPtr

Definition at line 106 of file typedef.hpp.

Definition at line 27 of file CropBoxWrapper.hpp.

Definition at line 161 of file DebugHelper.hpp.

Definition at line 39 of file DefaultHypothesisUpdaterFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 37 of file DefaultHypothesisUpdater.hpp.

Definition at line 72 of file DefaultRatingModuleFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 317 of file DefaultRatingModule.hpp.

Definition for the shared pointer type of the class.

Definition at line 200 of file DefaultScoreContainer.hpp.

Definition at line 183 of file DefaultViewportPoint.hpp.

typedef boost::shared_ptr<asr_next_best_view::DynamicParametersConfig> next_best_view::DynamicParametersConfigPtr

Definition at line 1058 of file NextBestView.hpp.

typedef pcl::FrustumCulling<ObjectPoint> next_best_view::FrustumCulling

Definition at line 101 of file typedef.hpp.

typedef FrustumCulling::Ptr next_best_view::FrustumCullingPtr

Definition at line 102 of file typedef.hpp.

Definition at line 30 of file GeneralFilter.hpp.

typedef Eigen::Matrix<int, 3, 1> next_best_view::GridVector3

Definition at line 57 of file typedef.hpp.

Definition at line 31 of file HypothesisUpdaterAbstractFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 47 of file HypothesisUpdater.hpp.

typedef std::vector<int> next_best_view::Indices

Definition at line 117 of file typedef.hpp.

Definition at line 119 of file typedef.hpp.

Definition at line 118 of file typedef.hpp.

typedef asr_world_model::GetIntermediateObjectWeight::Response next_best_view::IntermediateObjectWeightResponse

Definition at line 32 of file ObjectHelper.h.

typedef IntermediateObjectWeightResponse::Ptr next_best_view::IntermediateObjectWeightResponsePtr

Definition at line 33 of file ObjectHelper.h.

typedef pcl::KdTreeFLANN<ObjectPoint> next_best_view::KdTree

Definition at line 109 of file typedef.hpp.

typedef KdTree::ConstPtr next_best_view::KdTreeConstPtr

Definition at line 111 of file typedef.hpp.

typedef KdTree::Ptr next_best_view::KdTreePtr

Definition at line 110 of file typedef.hpp.

Definition at line 45 of file MapBasedHexagonSpaceSamplerFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 63 of file MapBasedHexagonSpaceSampler.hpp.

Definition at line 44 of file MapBasedRandomSpaceSamplerFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 46 of file MapBasedRandomSpaceSampler.hpp.

Definition for the shared pointer type of the class.

Definition at line 57 of file Raytracing2DBasedSpaceSampler.hpp.

Definition at line 424 of file MapHelper.hpp.

typedef asr_object_database::ObjectMetaData::Response next_best_view::ObjectMetaDataResponse

Definition at line 30 of file ObjectHelper.h.

typedef ObjectMetaDataResponse::Ptr next_best_view::ObjectMetaDataResponsePtr

Definition at line 31 of file ObjectHelper.h.

Definition at line 76 of file typedef.hpp.

Definition at line 85 of file typedef.hpp.

typedef ObjectPointCloud::ConstPtr next_best_view::ObjectPointCloudConstPtr

Definition at line 87 of file typedef.hpp.

typedef ObjectPointCloud::Ptr next_best_view::ObjectPointCloudPtr

Definition at line 86 of file typedef.hpp.

typedef std::vector<std::string> next_best_view::ObjectTypeList

Definition at line 122 of file typedef.hpp.

Definition at line 123 of file typedef.hpp.

Definition at line 126 of file typedef.hpp.

Definition at line 127 of file typedef.hpp.

Definition at line 124 of file typedef.hpp.

Definition at line 125 of file typedef.hpp.

Definition at line 47 of file PerspectiveHypothesisUpdaterFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 50 of file PerspectiveHypothesisUpdater.hpp.

Definition at line 39 of file PlaneSubSpaceSamplerFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 55 of file PlaneSubSpaceSampler.hpp.

Definition at line 36 of file typedef.hpp.

Definition at line 31 of file RatingModuleAbstractFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 124 of file RatingModule.hpp.

typedef std::vector<RayTracingIndex> next_best_view::Ray

Definition at line 62 of file MapHelper.hpp.

Definition at line 42 of file Raytracing2DBasedSpaceSamplerFactory.hpp.

Definition at line 61 of file MapHelper.hpp.

Definition at line 127 of file RealObjectPoint.hpp.

Definition at line 80 of file typedef.hpp.

Definition at line 92 of file typedef.hpp.

typedef SamplePointCloud::ConstPtr next_best_view::SamplePointCloudConstPtr

Definition at line 94 of file typedef.hpp.

typedef SamplePointCloud::Ptr next_best_view::SamplePointCloudPtr

Definition at line 93 of file typedef.hpp.

typedef Eigen::Matrix<Precision, 2, 2> next_best_view::SimpleMatrix2

Definition at line 39 of file typedef.hpp.

typedef Eigen::Matrix<Precision, 3, 3> next_best_view::SimpleMatrix3

Definition at line 40 of file typedef.hpp.

typedef std::vector<SimpleMatrix3, Eigen::aligned_allocator<SimpleMatrix3> > next_best_view::SimpleMatrix3Collection

Definition at line 45 of file typedef.hpp.

Definition at line 46 of file typedef.hpp.

typedef Eigen::Matrix<Precision, 4, 4> next_best_view::SimpleMatrix4

Definition at line 41 of file typedef.hpp.

typedef std::vector<SimpleMatrix4, Eigen::aligned_allocator<SimpleMatrix4> > next_best_view::SimpleMatrix4Collection

Definition at line 48 of file typedef.hpp.

Definition at line 49 of file typedef.hpp.

typedef Eigen::Matrix<Precision, Eigen::Dynamic, Eigen::Dynamic> next_best_view::SimpleMatrixX

Definition at line 42 of file typedef.hpp.

typedef Eigen::Quaternion<Precision> next_best_view::SimpleQuaternion

Definition at line 67 of file typedef.hpp.

typedef std::vector<SimpleQuaternion, Eigen::aligned_allocator<SimpleQuaternion> > next_best_view::SimpleQuaternionCollection

Definition at line 70 of file typedef.hpp.

Definition at line 71 of file typedef.hpp.

Definition at line 54 of file typedef.hpp.

typedef Eigen::Matrix<Precision, 2, 1> next_best_view::SimpleVector2

Definition at line 52 of file typedef.hpp.

typedef Eigen::Matrix<Precision, 3, 1> next_best_view::SimpleVector3

Definition at line 53 of file typedef.hpp.

typedef std::vector<SimpleVector3, Eigen::aligned_allocator<SimpleVector3> > next_best_view::SimpleVector3Collection

Definition at line 60 of file typedef.hpp.

Definition at line 61 of file typedef.hpp.

typedef Eigen::Matrix<Precision, 4, 1> next_best_view::SimpleVector4

Definition at line 55 of file typedef.hpp.

typedef std::vector<SimpleVector4, Eigen::aligned_allocator<SimpleVector4> > next_best_view::SimpleVector4Collection

Definition at line 63 of file typedef.hpp.

Definition at line 64 of file typedef.hpp.

typedef Eigen::Matrix<Precision, Eigen::Dynamic, 1> next_best_view::SimpleVectorX

Definition at line 56 of file typedef.hpp.

Definition at line 54 of file SingleCameraModelFilterFactory.hpp.

the type definition for the corresponding shared pointer of the class.

Definition at line 77 of file SingleCameraModelFilter.hpp.

Definition at line 86 of file SpaceSamplePoint.hpp.

Definition at line 31 of file SpaceSamplerAbstractFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 83 of file SpaceSampler.hpp.

Definition at line 42 of file SprialApproxUnitSphereSamplerFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 51 of file SpiralApproxUnitSphereSampler.hpp.

typedef std::vector<float> next_best_view::SquaredDistances

Definition at line 114 of file typedef.hpp.

Definition at line 57 of file StereoCameraModelFilterFactory.hpp.

the type definition for the corresponding shared pointer of the class.

Definition at line 115 of file StereoCameraModelFilter.hpp.

Definition at line 31 of file UnitSphereSamplerAbstractFactory.hpp.

Definition for the shared pointer type of the class.

Definition at line 72 of file UnitSphereSampler.hpp.

Definition at line 81 of file typedef.hpp.

Definition at line 96 of file typedef.hpp.

typedef ViewportPointCloud::ConstPtr next_best_view::ViewportPointCloudConstPtr

Definition at line 98 of file typedef.hpp.

typedef ViewportPointCloud::Ptr next_best_view::ViewportPointCloudPtr

Definition at line 97 of file typedef.hpp.

Definition at line 915 of file VisualizationsHelper.hpp.

typedef pcl::PointXYZ next_best_view::WorldPoint

Definition at line 82 of file typedef.hpp.

typedef pcl::PointCloud<WorldPoint> next_best_view::WorldPointCloud

Definition at line 88 of file typedef.hpp.

typedef WorldPointCloud::ConstPtr next_best_view::WorldPointCloudConstPtr

Definition at line 90 of file typedef.hpp.

typedef WorldPointCloud::Ptr next_best_view::WorldPointCloudPtr

Definition at line 89 of file typedef.hpp.

Function Documentation

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::SpaceSamplePoint p 
)

Definition at line 24 of file SpaceSamplePoint.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::SpaceSamplePointPtr p 
)

Definition at line 35 of file SpaceSamplePoint.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::RealObjectPoint p 
)

Definition at line 24 of file RealObjectPoint.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::RealObjectPointPtr p 
)

Definition at line 45 of file RealObjectPoint.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::DefaultViewportPoint p 
)

Definition at line 24 of file DefaultViewportPoint.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::DefaultViewportPointPtr p 
)

Definition at line 61 of file DefaultViewportPoint.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::DefaultScoreContainer score 
)

Definition at line 32 of file DefaultScoreContainer.cpp.

std::ostream & next_best_view::operator<< ( std::ostream &  strm,
const next_best_view::DefaultScoreContainerPtr score 
)

Definition at line 50 of file DefaultScoreContainer.cpp.

Variable Documentation

struct next_best_view::SpaceSamplePoint next_best_view::EIGEN_ALIGN16


asr_next_best_view
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Thu Jan 9 2020 07:20:18