Public Member Functions | Private Member Functions | Private Attributes | List of all members
next_best_view::NextBestViewCalculator Class Reference

#include <NextBestViewCalculator.hpp>

Public Member Functions

bool calculateNextBestView (const ViewportPoint &currentCameraViewport, ViewportPoint &resultViewport)
 
bool doFrustumCulling (const SimpleVector3 &position, const SimpleQuaternion &orientation, const IndicesPtr &indices, ViewportPoint &viewportPoint)
 creates a new camera viewport with the given data More...
 
bool doFrustumCulling (const CameraModelFilterPtr &cameraModelFilterPtr, const SimpleVector3 &position, const SimpleQuaternion &orientation, const IndicesPtr &indices, ViewportPoint &resultViewport)
 creates a new camera viewport with the given data More...
 
bool doFrustumCulling (ViewportPoint &resultViewportPoint)
 creates a new camera viewport with the given data More...
 
bool doFrustumCulling (const CameraModelFilterPtr &cameraModelFilterPtr, ViewportPoint &resultViewportPoint)
 creates a new camera viewport with the given data More...
 
IndicesPtr getActiveIndices ()
 
CameraModelFilterPtr getCameraModelFilter ()
 
CameraModelFilterAbstractFactoryPtr getCameraModelFilterAbstractFactoryPtr ()
 getCameraModelFilterAbstractFactoryPtr More...
 
float getEpsilon ()
 
bool getFeasibleHypothesis (SimpleVector3 samplePoint, IndicesPtr &resultIndicesPtr)
 getFeasibleHypothesis finds object hypothesis near samplePoint More...
 
void getFeasibleSamplePoints (const SamplePointCloudPtr &sampledSpacePointCloudPtr, IndicesPtr &resultIndicesPtr)
 
void getFeasibleViewports (const ViewportPointCloudPtr &sampleViewportsPtr, IndicesPtr &resultIndicesPtr)
 getFeasibleViewports returns a vector of indices/sampleViewports which contain nearby (hypothesis) More...
 
HypothesisUpdaterPtr getHypothesisUpdater ()
 
KdTreePtr getKdTreePtr ()
 
MapHelperPtr getMapHelper ()
 
std::string getMeshPathByName (std::string objectType)
 
double getMinUtility () const
 
int getNumberActiveNormals ()
 
unsigned int getNumberActiveNormals (std::string type, std::string identifier)
 
int getNumberOfThreads () const
 getNumberOfThreads More...
 
unsigned int getNumberTotalNormals (std::string type, std::string identifier)
 
ObjectPointCloudPtr getPointCloudPtr ()
 
RatingModulePtr getRatingModule ()
 
RatingModuleAbstractFactoryPtr getRatingModuleAbstractFactoryPtr ()
 getRatingModuleAbstractFactoryPtr More...
 
bool getRequireMinUtility () const
 
robot_model_services::RobotModelPtr getRobotModel ()
 
SpaceSamplerPtr getSpaceSampler ()
 
std::vector< std::pair< std::string, std::string > > getTypeAndIds ()
 
UnitSphereSamplerPtr getUnitSphereSampler ()
 
void initializeRobotState (const ViewportPoint &currentCameraViewport)
 initializeRobotState initializes the robotstate to the given viewport More...
 
void loadCropBoxListFromFile (const std::string mCropBoxListFilePath)
 
 NextBestViewCalculator (const UnitSphereSamplerPtr &unitSphereSamplerPtr=UnitSphereSamplerPtr(), const MapHelperPtr &mapHelperPtr=MapHelperPtr(), const SpaceSamplerPtr &spaceSamplerPtr=SpaceSamplerPtr(), const robot_model_services::RobotModelPtr &robotModelPtr=robot_model_services::RobotModelPtr(), const CameraModelFilterPtr &cameraModelFilterPtr=CameraModelFilterPtr(), const RatingModulePtr &ratingModulePtr=RatingModulePtr())
 
bool rateViewports (const ViewportPointCloudPtr &sampleNextBestViewportsPtr, const ViewportPoint &currentCameraViewport, ViewportPoint &resultViewport, bool objectTypeSetIsKnown=false)
 rates given viewports, which must contain child_indices More...
 
bool rateViewports (const ViewportPointCloudPtr &sampleNextBestViewports, const ViewportPoint &currentCameraViewport, ViewportPointCloudPtr &ratedNextBestViewportsPtr, bool objectTypeSetIsKnown=false)
 rates given viewports, which must contain child_indices More...
 
bool removeObjects (std::string type, std::string identifier)
 
void setActiveIndices (const IndicesPtr &activeIndicesPtr)
 sets the active indices. More...
 
void setCameraModelFilter (const CameraModelFilterPtr &cameraModelFilterPtr)
 
void setCameraModelFilterAbstractFactoryPtr (const CameraModelFilterAbstractFactoryPtr &cameraModelFilterAbstractFactoryPtr)
 setCameraModelFilterAbstractFactoryPtr used to generate camera models per thread. More...
 
void setEnableCropBoxFiltering (const bool mEnableCropBoxFiltering)
 
void setEnableIntermediateObjectWeighting (const bool mEnableIntermediateObjectWeighting)
 
void setEpsilon (float epsilon)
 
void setHeight (SamplePointCloudPtr pointCloudPtr, double height)
 
void setHypothesisUpdater (const HypothesisUpdaterPtr &hypothesisUpdaterPtr)
 
void setMapHelper (const MapHelperPtr &mapHelperPtr)
 
void setMaxIterationSteps (int maxIterationSteps)
 
void setMinUtility (double minUtility)
 
void setNumberOfThreads (int value)
 sets number of threads used to rate samples, negative numbers use boost::thread::hardware_concurrency() as number of threads. More...
 
bool setPointCloudFromMessage (const asr_msgs::AsrAttributedPointCloud &msg)
 /// More...
 
void setPointCloudPtr (const ObjectPointCloudPtr &pointCloudPtr)
 
void setRatingModule (const RatingModulePtr &ratingModulePtr)
 
void setRatingModuleAbstractFactoryPtr (const RatingModuleAbstractFactoryPtr &ratingModuleAbstractFactoryPtr)
 setRatingModuleAbstractFactoryPtr used to generate rating modules per thread. More...
 
void setRequireMinUtility (bool requireMinUtility)
 
void setRobotModel (const robot_model_services::RobotModelPtr &robotModelPtr)
 
void setSpaceSampler (const SpaceSamplerPtr &spaceSamplerPtr)
 
void setUnitSphereSampler (const UnitSphereSamplerPtr &unitSphereSamplerPtr)
 
void updateFromExternalViewportPointList (const std::vector< ViewportPoint > &viewportPointList)
 updates point cloud with external viewport point list More...
 
unsigned int updateObjectPointCloud (const ObjectTypeSetPtr &objectTypeSetPtr, const ViewportPoint &viewportPoint)
 Updates the point cloud under the assumption that the given viewport was chosen. More...
 

Private Member Functions

ViewportPointCloudPtr combineSamples (SamplePointCloudPtr sampledSpacePointCloudPtr, SimpleQuaternionCollectionPtr sampledOrientationsPtr)
 combines space samples and orientation samples to viewport samples More...
 
bool doIteration (const ViewportPoint &currentCameraViewport, const SimpleQuaternionCollectionPtr &sampledOrientationsPtr, ViewportPoint &resultViewport)
 
bool doIterationStep (const ViewportPoint &currentCameraViewport, const ViewportPoint &currentBestViewport, const SimpleQuaternionCollectionPtr &sampledOrientationsPtr, float contractor, ViewportPoint &resultViewport, int iterationStep)
 
SimpleQuaternionCollectionPtr generateOrientationSamples ()
 generateOrientationSamples More...
 
ViewportPointCloudPtr generateSampleViewports (SimpleVector3 spaceSampleStartVector, double contractor, double pointCloudHeight)
 generateSampleViewports More...
 
SamplePointCloudPtr generateSpaceSamples (SimpleVector3 spaceSampleStartVector, double contractor, double pointCloudHeight)
 generateSpaceSamples More...
 
bool isPointInCropbox (const SimpleVector3 &position, const Eigen::Vector3f &translation, const Eigen::Vector4f &max) const
 
bool isPointInRange (float point, float min, float lenght) const
 
bool rateSingleViewportFixedObjectTypes (const RatingModulePtr &ratingModulePtr, const ViewportPoint &currentCameraViewport, ViewportPoint &fullViewportPoint)
 uses setSingleScoreContainer to use object_type_set of fullViewportPoint to rate. More...
 
bool rateSingleViewportOptimizeObjectTypes (const RatingModulePtr &ratingModulePtr, const ViewportPoint &currentCameraViewport, ViewportPoint &fullViewportPoint)
 uses setBestScoreContainer to optimize which objects should be recognized More...
 
bool rateViewportsInternal (const ViewportPointCloudPtr &sampleNextBestViewports, const ViewportPoint &currentCameraViewport, ViewportPointCloudPtr &ratedNextBestViewports, ViewportPoint &resultViewport, bool objectTypeSetIsKnown)
 rates viewports and returns vector with rated wiewports and the best rated viewport More...
 
void ratingThread (int threadId, boost::mutex &mutex, const ViewportPointCloudPtr &sampleNextBestViewports, const ViewportPoint &currentCameraViewport, const ViewportPointCloudPtr &ratedNextBestViewports, bool objectTypeSetIsKnown)
 ratingThread More...
 
bool setNormals (const ObjectPoint &pointCloudPoint)
 
bool setNormalsInCropBoxMode (const ObjectPoint &pointCloudPoint)
 

Private Attributes

IndicesPtr mActiveIndicesPtr
 
CameraModelFilterAbstractFactoryPtr mCameraModelFilterAbstractFactoryPtr
 
CameraModelFilterPtr mCameraModelFilterPtr
 
CropBoxFilterPtr mCropBoxFilterPtr
 
DebugHelperPtr mDebugHelperPtr
 
bool mEnableCropBoxFiltering
 
bool mEnableIntermediateObjectWeighting
 
float mEpsilon
 
HypothesisUpdaterPtr mHypothesisUpdaterPtr
 
KdTreePtr mKdTreePtr
 
MapHelperPtr mMapHelperPtr
 
int mMaxIterationSteps
 
double mMinUtility
 
int mNumberOfThreads
 
ObjectTypeSetPtr mObjectTypeSetPtr
 
ObjectPointCloudPtr mPointCloudPtr
 
RatingModuleAbstractFactoryPtr mRatingModuleAbstractFactoryPtr
 
RatingModulePtr mRatingModulePtr
 
bool mRequireMinUtility
 
robot_model_services::RobotModelPtr mRobotModelPtr
 
SpaceSamplerPtr mSpaceSamplerPtr
 
std::vector< CameraModelFilterPtrmThreadCameraModels
 
std::vector< RatingModulePtrmThreadRatingModules
 
UnitSphereSamplerPtr mUnitSphereSamplerPtr
 
VisualizationHelperPtr mVisHelperPtr
 
std::map< std::string, std::string > objectsResources
 

Detailed Description

Definition at line 50 of file NextBestViewCalculator.hpp.

Constructor & Destructor Documentation

next_best_view::NextBestViewCalculator::NextBestViewCalculator ( const UnitSphereSamplerPtr unitSphereSamplerPtr = UnitSphereSamplerPtr(),
const MapHelperPtr mapHelperPtr = MapHelperPtr(),
const SpaceSamplerPtr spaceSamplerPtr = SpaceSamplerPtr(),
const robot_model_services::RobotModelPtr &  robotModelPtr = robot_model_services::RobotModelPtr(),
const CameraModelFilterPtr cameraModelFilterPtr = CameraModelFilterPtr(),
const RatingModulePtr ratingModulePtr = RatingModulePtr() 
)
inline

Definition at line 90 of file NextBestViewCalculator.hpp.

Member Function Documentation

bool next_best_view::NextBestViewCalculator::calculateNextBestView ( const ViewportPoint currentCameraViewport,
ViewportPoint resultViewport 
)
inline

Calculates the next best view. Starting point of iterative calculations for getNextBestView() service call.

Definition at line 115 of file NextBestViewCalculator.hpp.

ViewportPointCloudPtr next_best_view::NextBestViewCalculator::combineSamples ( SamplePointCloudPtr  sampledSpacePointCloudPtr,
SimpleQuaternionCollectionPtr  sampledOrientationsPtr 
)
inlineprivate

combines space samples and orientation samples to viewport samples

Parameters
sampledSpacePointCloudPtr
sampledOrientationsPtr
feasibleIndicesPtr
Returns

Definition at line 782 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::doFrustumCulling ( const SimpleVector3 position,
const SimpleQuaternion orientation,
const IndicesPtr indices,
ViewportPoint viewportPoint 
)
inline

creates a new camera viewport with the given data

Parameters
position[in] the position of the camera
orientation[in] the orientation of the camera
indices[in] the object point indices to be used
viewportPoint[out] the resulting camera viewport
Returns
whether there are objects in the resulting viewport

Definition at line 486 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::doFrustumCulling ( const CameraModelFilterPtr cameraModelFilterPtr,
const SimpleVector3 position,
const SimpleQuaternion orientation,
const IndicesPtr indices,
ViewportPoint resultViewport 
)
inline

creates a new camera viewport with the given data

Parameters
cameraModelFilterPtr[in] the cameraModel used to filter objects
position[in] the position of the camera
orientation[in] the orientation of the camera
indices[in] the object point indices to be used
viewportPoint[out] the resulting camera viewport
Returns
whether there are objects in the resulting viewport

Definition at line 499 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::doFrustumCulling ( ViewportPoint resultViewportPoint)
inline

creates a new camera viewport with the given data

Parameters
resultViewportPoint
Returns
whether there are objects in the resulting viewport

Definition at line 510 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::doFrustumCulling ( const CameraModelFilterPtr cameraModelFilterPtr,
ViewportPoint resultViewportPoint 
)
inline

creates a new camera viewport with the given data

Parameters
cameraModelFilterPtr[in] the cameraModel used to filter objects
resultViewportPoint[out|in] the resulting camera viewport containg the camera position and orientation and the object point indices to be used
Returns
whether there are objects in the resulting viewport

Definition at line 520 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::doIteration ( const ViewportPoint currentCameraViewport,
const SimpleQuaternionCollectionPtr sampledOrientationsPtr,
ViewportPoint resultViewport 
)
inlineprivate

Definition at line 352 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::doIterationStep ( const ViewportPoint currentCameraViewport,
const ViewportPoint currentBestViewport,
const SimpleQuaternionCollectionPtr sampledOrientationsPtr,
float  contractor,
ViewportPoint resultViewport,
int  iterationStep 
)
inlineprivate

Definition at line 406 of file NextBestViewCalculator.hpp.

SimpleQuaternionCollectionPtr next_best_view::NextBestViewCalculator::generateOrientationSamples ( )
inlineprivate

generateOrientationSamples

Returns

Definition at line 742 of file NextBestViewCalculator.hpp.

ViewportPointCloudPtr next_best_view::NextBestViewCalculator::generateSampleViewports ( SimpleVector3  spaceSampleStartVector,
double  contractor,
double  pointCloudHeight 
)
inlineprivate

generateSampleViewports

Parameters
spaceSampleStartVector
contractor
pointCloudHeight
Returns

Definition at line 727 of file NextBestViewCalculator.hpp.

SamplePointCloudPtr next_best_view::NextBestViewCalculator::generateSpaceSamples ( SimpleVector3  spaceSampleStartVector,
double  contractor,
double  pointCloudHeight 
)
inlineprivate

generateSpaceSamples

Parameters
spaceSampleStartVector
contractor
pointCloudHeight
Returns

Definition at line 762 of file NextBestViewCalculator.hpp.

IndicesPtr next_best_view::NextBestViewCalculator::getActiveIndices ( )
inline
Returns
the active Indices.

Definition at line 942 of file NextBestViewCalculator.hpp.

CameraModelFilterPtr next_best_view::NextBestViewCalculator::getCameraModelFilter ( )
inline
Returns
the pointer to the camera model filter

Definition at line 1083 of file NextBestViewCalculator.hpp.

CameraModelFilterAbstractFactoryPtr next_best_view::NextBestViewCalculator::getCameraModelFilterAbstractFactoryPtr ( )
inline

getCameraModelFilterAbstractFactoryPtr

Returns

Definition at line 1189 of file NextBestViewCalculator.hpp.

float next_best_view::NextBestViewCalculator::getEpsilon ( )
inline
Returns
epsilon

Definition at line 1136 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::getFeasibleHypothesis ( SimpleVector3  samplePoint,
IndicesPtr resultIndicesPtr 
)
inline

getFeasibleHypothesis finds object hypothesis near samplePoint

Parameters
samplePointthe point to find nearby hypothesis
resultIndicesPtrnearby object hypothesis
Returns
true if more than 0 object hypothesis are in range of samplePoint

Definition at line 200 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::getFeasibleSamplePoints ( const SamplePointCloudPtr sampledSpacePointCloudPtr,
IndicesPtr resultIndicesPtr 
)
inline

Definition at line 151 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::getFeasibleViewports ( const ViewportPointCloudPtr sampleViewportsPtr,
IndicesPtr resultIndicesPtr 
)
inline

getFeasibleViewports returns a vector of indices/sampleViewports which contain nearby (hypothesis)

Parameters
sampleViewportsPtrviewports which may contain nearby object hypothesis
resultIndicesPtr

Definition at line 175 of file NextBestViewCalculator.hpp.

HypothesisUpdaterPtr next_best_view::NextBestViewCalculator::getHypothesisUpdater ( )
inline

Definition at line 1122 of file NextBestViewCalculator.hpp.

KdTreePtr next_best_view::NextBestViewCalculator::getKdTreePtr ( )
inline
Returns
the point cloud pointer

Definition at line 1023 of file NextBestViewCalculator.hpp.

MapHelperPtr next_best_view::NextBestViewCalculator::getMapHelper ( )
inline
Returns
the map helper ptr

Definition at line 1114 of file NextBestViewCalculator.hpp.

std::string next_best_view::NextBestViewCalculator::getMeshPathByName ( std::string  objectType)
inline

Returns the path to a meshs resource file

Definition at line 880 of file NextBestViewCalculator.hpp.

double next_best_view::NextBestViewCalculator::getMinUtility ( ) const
inline

Definition at line 1233 of file NextBestViewCalculator.hpp.

int next_best_view::NextBestViewCalculator::getNumberActiveNormals ( )
inline

Definition at line 946 of file NextBestViewCalculator.hpp.

unsigned int next_best_view::NextBestViewCalculator::getNumberActiveNormals ( std::string  type,
std::string  identifier 
)
inline

Definition at line 970 of file NextBestViewCalculator.hpp.

int next_best_view::NextBestViewCalculator::getNumberOfThreads ( ) const
inline

getNumberOfThreads

Returns

Definition at line 1197 of file NextBestViewCalculator.hpp.

unsigned int next_best_view::NextBestViewCalculator::getNumberTotalNormals ( std::string  type,
std::string  identifier 
)
inline

Definition at line 957 of file NextBestViewCalculator.hpp.

ObjectPointCloudPtr next_best_view::NextBestViewCalculator::getPointCloudPtr ( )
inline
Returns
the point cloud pointer

Definition at line 928 of file NextBestViewCalculator.hpp.

RatingModulePtr next_best_view::NextBestViewCalculator::getRatingModule ( )
inline
Returns
the pointer to the rating module.

Definition at line 1098 of file NextBestViewCalculator.hpp.

RatingModuleAbstractFactoryPtr next_best_view::NextBestViewCalculator::getRatingModuleAbstractFactoryPtr ( )
inline

getRatingModuleAbstractFactoryPtr

Returns

Definition at line 1167 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::getRequireMinUtility ( ) const
inline

Definition at line 1241 of file NextBestViewCalculator.hpp.

robot_model_services::RobotModelPtr next_best_view::NextBestViewCalculator::getRobotModel ( )
inline
Returns
the robot ptr

Definition at line 1068 of file NextBestViewCalculator.hpp.

SpaceSamplerPtr next_best_view::NextBestViewCalculator::getSpaceSampler ( )
inline
Returns
the pointer to the space sampler.

Definition at line 1053 of file NextBestViewCalculator.hpp.

std::vector<std::pair<std::string, std::string> > next_best_view::NextBestViewCalculator::getTypeAndIds ( )
inline

Definition at line 983 of file NextBestViewCalculator.hpp.

UnitSphereSamplerPtr next_best_view::NextBestViewCalculator::getUnitSphereSampler ( )
inline
Returns
the unit sphere sampler.

Definition at line 1038 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::initializeRobotState ( const ViewportPoint currentCameraViewport)
inline

initializeRobotState initializes the robotstate to the given viewport

Parameters
currentCameraViewportthe camera viewport of the robot

Definition at line 141 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::isPointInCropbox ( const SimpleVector3 position,
const Eigen::Vector3f &  translation,
const Eigen::Vector4f &  max 
) const
inlineprivate

Definition at line 866 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::isPointInRange ( float  point,
float  min,
float  lenght 
) const
inlineprivate

Definition at line 872 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::loadCropBoxListFromFile ( const std::string  mCropBoxListFilePath)
inline

Definition at line 910 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::rateSingleViewportFixedObjectTypes ( const RatingModulePtr ratingModulePtr,
const ViewportPoint currentCameraViewport,
ViewportPoint fullViewportPoint 
)
inlineprivate

uses setSingleScoreContainer to use object_type_set of fullViewportPoint to rate.

Parameters
ratingModulePtr[in] used to rate
currentCameraViewport[in] used to rate
fullViewportPoint[out] resulting rated viewport
Returns

Definition at line 347 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::rateSingleViewportOptimizeObjectTypes ( const RatingModulePtr ratingModulePtr,
const ViewportPoint currentCameraViewport,
ViewportPoint fullViewportPoint 
)
inlineprivate

uses setBestScoreContainer to optimize which objects should be recognized

Parameters
ratingModulePtr[in] used to rate
currentCameraViewport[in] used to rate
fullViewportPoint[out] resulting rated viewport
Returns

Definition at line 334 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::rateViewports ( const ViewportPointCloudPtr sampleNextBestViewportsPtr,
const ViewportPoint currentCameraViewport,
ViewportPoint resultViewport,
bool  objectTypeSetIsKnown = false 
)
inline

rates given viewports, which must contain child_indices

Parameters
sampleNextBestViewports[in] viewports to rate
currentCameraViewport[in] current camera viewport to rate
resultViewport[out] viewport with best rating
objectTypeSetIsKnown
Returns
if valid result

Definition at line 232 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::rateViewports ( const ViewportPointCloudPtr sampleNextBestViewports,
const ViewportPoint currentCameraViewport,
ViewportPointCloudPtr ratedNextBestViewportsPtr,
bool  objectTypeSetIsKnown = false 
)
inline

rates given viewports, which must contain child_indices

Parameters
sampleNextBestViewports[in] viewports to rate
currentCameraViewport[in] current camera viewport to rate
ratedNextBestViewports[out] rated viewports, which might be fewer
objectTypeSetIsKnown
Returns
if valid result

Definition at line 245 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::rateViewportsInternal ( const ViewportPointCloudPtr sampleNextBestViewports,
const ViewportPoint currentCameraViewport,
ViewportPointCloudPtr ratedNextBestViewports,
ViewportPoint resultViewport,
bool  objectTypeSetIsKnown 
)
inlineprivate

rates viewports and returns vector with rated wiewports and the best rated viewport

Parameters
sampleNextBestViewports[in] viewports to rate
currentCameraViewport[in] current camera viewport to rate
ratedNextBestViewports[out] rated (unsorted in most cases) vector of viewports
resultViewport[out] best viewport
objectTypeSetIsKnown
Returns
if valid result

Definition at line 262 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::ratingThread ( int  threadId,
boost::mutex &  mutex,
const ViewportPointCloudPtr sampleNextBestViewports,
const ViewportPoint currentCameraViewport,
const ViewportPointCloudPtr ratedNextBestViewports,
bool  objectTypeSetIsKnown 
)
inlineprivate

ratingThread

Parameters
threadId
mutex
sampleNextBestViewportsviewport sampling, which contains a good estimation for nearby objects per viewport
currentCameraViewportcurrent camera viewport, used to rate
ratedNextBestViewportsresults
objectTypeSetIsKnownif object_types_set is set fixed and hould not be optimized

Definition at line 290 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::removeObjects ( std::string  type,
std::string  identifier 
)
inline

Definition at line 997 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setActiveIndices ( const IndicesPtr activeIndicesPtr)
inline

sets the active indices.

Definition at line 935 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setCameraModelFilter ( const CameraModelFilterPtr cameraModelFilterPtr)
inline

Sets the camera model filter.

Parameters
cameraModelFilterPtr- the pointer to the camera model filter.

Definition at line 1076 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setCameraModelFilterAbstractFactoryPtr ( const CameraModelFilterAbstractFactoryPtr cameraModelFilterAbstractFactoryPtr)
inline

setCameraModelFilterAbstractFactoryPtr used to generate camera models per thread.

Parameters
cameraModelFilterAbstractFactoryPtr

Definition at line 1175 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setEnableCropBoxFiltering ( const bool  mEnableCropBoxFiltering)
inline

Definition at line 915 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setEnableIntermediateObjectWeighting ( const bool  mEnableIntermediateObjectWeighting)
inline

Definition at line 920 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setEpsilon ( float  epsilon)
inline
Parameters
epsilon- error threshold

Definition at line 1129 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setHeight ( SamplePointCloudPtr  pointCloudPtr,
double  height 
)
inline

Definition at line 472 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setHypothesisUpdater ( const HypothesisUpdaterPtr hypothesisUpdaterPtr)
inline

Definition at line 1118 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setMapHelper ( const MapHelperPtr mapHelperPtr)
inline

sets the map helper

Parameters
mapHelperPtr- the pointer to map helper.

Definition at line 1106 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setMaxIterationSteps ( int  maxIterationSteps)
inline

Max number of hierarchical iterations when calculating a next-best-view.

Parameters
maxIterationSteps- max number of iteration steps

Definition at line 1144 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setMinUtility ( double  minUtility)
inline

Definition at line 1237 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::setNormals ( const ObjectPoint pointCloudPoint)
inlineprivate

Definition at line 805 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::setNormalsInCropBoxMode ( const ObjectPoint pointCloudPoint)
inlineprivate

Definition at line 829 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setNumberOfThreads ( int  value)
inline

sets number of threads used to rate samples, negative numbers use boost::thread::hardware_concurrency() as number of threads.

Parameters
value

Definition at line 1205 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::setPointCloudFromMessage ( const asr_msgs::AsrAttributedPointCloud &  msg)
inline

///

Sets the point cloud points from point cloud message

Parameters
message- message containing the point cloud

Definition at line 610 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setPointCloudPtr ( const ObjectPointCloudPtr pointCloudPtr)
inline

Sets the point cloud ptr.

Definition at line 896 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setRatingModule ( const RatingModulePtr ratingModulePtr)
inline

Sets the rating module.

Parameters
ratingModulePtr- the pointer to the rating module

Definition at line 1091 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setRatingModuleAbstractFactoryPtr ( const RatingModuleAbstractFactoryPtr ratingModuleAbstractFactoryPtr)
inline

setRatingModuleAbstractFactoryPtr used to generate rating modules per thread.

Parameters
ratingModuleAbstractFactoryPtr

Definition at line 1153 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setRequireMinUtility ( bool  requireMinUtility)
inline

Definition at line 1245 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setRobotModel ( const robot_model_services::RobotModelPtr &  robotModelPtr)
inline

sets the robot model

Parameters
robotModelPtr- the pointer to robot model.

Definition at line 1061 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setSpaceSampler ( const SpaceSamplerPtr spaceSamplerPtr)
inline

Sets the space sampler.

Parameters
spaceSamplerPtr- the pointer to the space sampler

Definition at line 1046 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::setUnitSphereSampler ( const UnitSphereSamplerPtr unitSphereSamplerPtr)
inline

Sets the unit sphere sampler.

Parameters
unitSphereSamplerPtr- the pointer to the unit sphere sampler

Definition at line 1031 of file NextBestViewCalculator.hpp.

void next_best_view::NextBestViewCalculator::updateFromExternalViewportPointList ( const std::vector< ViewportPoint > &  viewportPointList)
inline

updates point cloud with external viewport point list

Parameters
viewportPointListthe list of viewport points
Returns
the number of deactivated normals

Definition at line 545 of file NextBestViewCalculator.hpp.

unsigned int next_best_view::NextBestViewCalculator::updateObjectPointCloud ( const ObjectTypeSetPtr objectTypeSetPtr,
const ViewportPoint viewportPoint 
)
inline

Updates the point cloud under the assumption that the given viewport was chosen.

Parameters
objectTypeSetPtrthe object type names that shall be updated.
viewportPointthe viewport that was chosen
Returns
the number of deactivated normals

Definition at line 584 of file NextBestViewCalculator.hpp.

Member Data Documentation

IndicesPtr next_best_view::NextBestViewCalculator::mActiveIndicesPtr
private

Definition at line 54 of file NextBestViewCalculator.hpp.

CameraModelFilterAbstractFactoryPtr next_best_view::NextBestViewCalculator::mCameraModelFilterAbstractFactoryPtr
private

Definition at line 68 of file NextBestViewCalculator.hpp.

CameraModelFilterPtr next_best_view::NextBestViewCalculator::mCameraModelFilterPtr
private

Definition at line 63 of file NextBestViewCalculator.hpp.

CropBoxFilterPtr next_best_view::NextBestViewCalculator::mCropBoxFilterPtr
private

Definition at line 70 of file NextBestViewCalculator.hpp.

DebugHelperPtr next_best_view::NextBestViewCalculator::mDebugHelperPtr
private

Definition at line 73 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::mEnableCropBoxFiltering
private

Definition at line 76 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::mEnableIntermediateObjectWeighting
private

Definition at line 77 of file NextBestViewCalculator.hpp.

float next_best_view::NextBestViewCalculator::mEpsilon
private

Definition at line 71 of file NextBestViewCalculator.hpp.

HypothesisUpdaterPtr next_best_view::NextBestViewCalculator::mHypothesisUpdaterPtr
private

Definition at line 65 of file NextBestViewCalculator.hpp.

KdTreePtr next_best_view::NextBestViewCalculator::mKdTreePtr
private

Definition at line 55 of file NextBestViewCalculator.hpp.

MapHelperPtr next_best_view::NextBestViewCalculator::mMapHelperPtr
private

Definition at line 60 of file NextBestViewCalculator.hpp.

int next_best_view::NextBestViewCalculator::mMaxIterationSteps
private

Definition at line 79 of file NextBestViewCalculator.hpp.

double next_best_view::NextBestViewCalculator::mMinUtility
private

Definition at line 85 of file NextBestViewCalculator.hpp.

int next_best_view::NextBestViewCalculator::mNumberOfThreads
private

Definition at line 81 of file NextBestViewCalculator.hpp.

ObjectTypeSetPtr next_best_view::NextBestViewCalculator::mObjectTypeSetPtr
private

Definition at line 72 of file NextBestViewCalculator.hpp.

ObjectPointCloudPtr next_best_view::NextBestViewCalculator::mPointCloudPtr
private

Definition at line 52 of file NextBestViewCalculator.hpp.

RatingModuleAbstractFactoryPtr next_best_view::NextBestViewCalculator::mRatingModuleAbstractFactoryPtr
private

Definition at line 67 of file NextBestViewCalculator.hpp.

RatingModulePtr next_best_view::NextBestViewCalculator::mRatingModulePtr
private

Definition at line 64 of file NextBestViewCalculator.hpp.

bool next_best_view::NextBestViewCalculator::mRequireMinUtility
private

Definition at line 86 of file NextBestViewCalculator.hpp.

robot_model_services::RobotModelPtr next_best_view::NextBestViewCalculator::mRobotModelPtr
private

Definition at line 62 of file NextBestViewCalculator.hpp.

SpaceSamplerPtr next_best_view::NextBestViewCalculator::mSpaceSamplerPtr
private

Definition at line 61 of file NextBestViewCalculator.hpp.

std::vector<CameraModelFilterPtr> next_best_view::NextBestViewCalculator::mThreadCameraModels
private

Definition at line 82 of file NextBestViewCalculator.hpp.

std::vector<RatingModulePtr> next_best_view::NextBestViewCalculator::mThreadRatingModules
private

Definition at line 83 of file NextBestViewCalculator.hpp.

UnitSphereSamplerPtr next_best_view::NextBestViewCalculator::mUnitSphereSamplerPtr
private

Definition at line 59 of file NextBestViewCalculator.hpp.

VisualizationHelperPtr next_best_view::NextBestViewCalculator::mVisHelperPtr
private

Definition at line 74 of file NextBestViewCalculator.hpp.

std::map<std::string, std::string> next_best_view::NextBestViewCalculator::objectsResources
private

Definition at line 56 of file NextBestViewCalculator.hpp.


The documentation for this class was generated from the following file:


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