#include <NextBestViewCalculator.hpp>
Public Member Functions | |
| bool | calculateNextBestView (const ViewportPoint ¤tCameraViewport, 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 ¤tCameraViewport) |
| 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 ¤tCameraViewport, ViewportPoint &resultViewport, bool objectTypeSetIsKnown=false) |
| rates given viewports, which must contain child_indices More... | |
| bool | rateViewports (const ViewportPointCloudPtr &sampleNextBestViewports, const ViewportPoint ¤tCameraViewport, 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 ¤tCameraViewport, const SimpleQuaternionCollectionPtr &sampledOrientationsPtr, ViewportPoint &resultViewport) |
| bool | doIterationStep (const ViewportPoint ¤tCameraViewport, const ViewportPoint ¤tBestViewport, 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 ¤tCameraViewport, ViewportPoint &fullViewportPoint) |
| uses setSingleScoreContainer to use object_type_set of fullViewportPoint to rate. More... | |
| bool | rateSingleViewportOptimizeObjectTypes (const RatingModulePtr &ratingModulePtr, const ViewportPoint ¤tCameraViewport, ViewportPoint &fullViewportPoint) |
| uses setBestScoreContainer to optimize which objects should be recognized More... | |
| bool | rateViewportsInternal (const ViewportPointCloudPtr &sampleNextBestViewports, const ViewportPoint ¤tCameraViewport, 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 ¤tCameraViewport, 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< CameraModelFilterPtr > | mThreadCameraModels |
| std::vector< RatingModulePtr > | mThreadRatingModules |
| UnitSphereSamplerPtr | mUnitSphereSamplerPtr |
| VisualizationHelperPtr | mVisHelperPtr |
| std::map< std::string, std::string > | objectsResources |
Definition at line 50 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 90 of file NextBestViewCalculator.hpp.
|
inline |
Calculates the next best view. Starting point of iterative calculations for getNextBestView() service call.
Definition at line 115 of file NextBestViewCalculator.hpp.
|
inlineprivate |
combines space samples and orientation samples to viewport samples
| sampledSpacePointCloudPtr | |
| sampledOrientationsPtr | |
| feasibleIndicesPtr |
Definition at line 782 of file NextBestViewCalculator.hpp.
|
inline |
creates a new camera viewport with the given data
| 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 |
Definition at line 486 of file NextBestViewCalculator.hpp.
|
inline |
creates a new camera viewport with the given data
| 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 |
Definition at line 499 of file NextBestViewCalculator.hpp.
|
inline |
creates a new camera viewport with the given data
| resultViewportPoint |
Definition at line 510 of file NextBestViewCalculator.hpp.
|
inline |
creates a new camera viewport with the given data
| 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 |
Definition at line 520 of file NextBestViewCalculator.hpp.
|
inlineprivate |
Definition at line 352 of file NextBestViewCalculator.hpp.
|
inlineprivate |
Definition at line 406 of file NextBestViewCalculator.hpp.
|
inlineprivate |
|
inlineprivate |
generateSampleViewports
| spaceSampleStartVector | |
| contractor | |
| pointCloudHeight |
Definition at line 727 of file NextBestViewCalculator.hpp.
|
inlineprivate |
generateSpaceSamples
| spaceSampleStartVector | |
| contractor | |
| pointCloudHeight |
Definition at line 762 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 942 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1083 of file NextBestViewCalculator.hpp.
|
inline |
getCameraModelFilterAbstractFactoryPtr
Definition at line 1189 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1136 of file NextBestViewCalculator.hpp.
|
inline |
getFeasibleHypothesis finds object hypothesis near samplePoint
| samplePoint | the point to find nearby hypothesis |
| resultIndicesPtr | nearby object hypothesis |
Definition at line 200 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 151 of file NextBestViewCalculator.hpp.
|
inline |
getFeasibleViewports returns a vector of indices/sampleViewports which contain nearby (hypothesis)
| sampleViewportsPtr | viewports which may contain nearby object hypothesis |
| resultIndicesPtr |
Definition at line 175 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1122 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1023 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1114 of file NextBestViewCalculator.hpp.
|
inline |
Returns the path to a meshs resource file
Definition at line 880 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1233 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 946 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 970 of file NextBestViewCalculator.hpp.
|
inline |
|
inline |
Definition at line 957 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 928 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1098 of file NextBestViewCalculator.hpp.
|
inline |
getRatingModuleAbstractFactoryPtr
Definition at line 1167 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1241 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1068 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1053 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 983 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1038 of file NextBestViewCalculator.hpp.
|
inline |
initializeRobotState initializes the robotstate to the given viewport
| currentCameraViewport | the camera viewport of the robot |
Definition at line 141 of file NextBestViewCalculator.hpp.
|
inlineprivate |
Definition at line 866 of file NextBestViewCalculator.hpp.
|
inlineprivate |
Definition at line 872 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 910 of file NextBestViewCalculator.hpp.
|
inlineprivate |
uses setSingleScoreContainer to use object_type_set of fullViewportPoint to rate.
| ratingModulePtr | [in] used to rate |
| currentCameraViewport | [in] used to rate |
| fullViewportPoint | [out] resulting rated viewport |
Definition at line 347 of file NextBestViewCalculator.hpp.
|
inlineprivate |
uses setBestScoreContainer to optimize which objects should be recognized
| ratingModulePtr | [in] used to rate |
| currentCameraViewport | [in] used to rate |
| fullViewportPoint | [out] resulting rated viewport |
Definition at line 334 of file NextBestViewCalculator.hpp.
|
inline |
rates given viewports, which must contain child_indices
| sampleNextBestViewports | [in] viewports to rate |
| currentCameraViewport | [in] current camera viewport to rate |
| resultViewport | [out] viewport with best rating |
| objectTypeSetIsKnown |
Definition at line 232 of file NextBestViewCalculator.hpp.
|
inline |
rates given viewports, which must contain child_indices
| sampleNextBestViewports | [in] viewports to rate |
| currentCameraViewport | [in] current camera viewport to rate |
| ratedNextBestViewports | [out] rated viewports, which might be fewer |
| objectTypeSetIsKnown |
Definition at line 245 of file NextBestViewCalculator.hpp.
|
inlineprivate |
rates viewports and returns vector with rated wiewports and the best rated viewport
| 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 |
Definition at line 262 of file NextBestViewCalculator.hpp.
|
inlineprivate |
ratingThread
| threadId | |
| mutex | |
| sampleNextBestViewports | viewport sampling, which contains a good estimation for nearby objects per viewport |
| currentCameraViewport | current camera viewport, used to rate |
| ratedNextBestViewports | results |
| objectTypeSetIsKnown | if object_types_set is set fixed and hould not be optimized |
Definition at line 290 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 997 of file NextBestViewCalculator.hpp.
|
inline |
sets the active indices.
Definition at line 935 of file NextBestViewCalculator.hpp.
|
inline |
Sets the camera model filter.
| cameraModelFilterPtr | - the pointer to the camera model filter. |
Definition at line 1076 of file NextBestViewCalculator.hpp.
|
inline |
setCameraModelFilterAbstractFactoryPtr used to generate camera models per thread.
| cameraModelFilterAbstractFactoryPtr |
Definition at line 1175 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 915 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 920 of file NextBestViewCalculator.hpp.
|
inline |
| epsilon | - error threshold |
Definition at line 1129 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 472 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1118 of file NextBestViewCalculator.hpp.
|
inline |
sets the map helper
| mapHelperPtr | - the pointer to map helper. |
Definition at line 1106 of file NextBestViewCalculator.hpp.
|
inline |
Max number of hierarchical iterations when calculating a next-best-view.
| maxIterationSteps | - max number of iteration steps |
Definition at line 1144 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1237 of file NextBestViewCalculator.hpp.
|
inlineprivate |
Definition at line 805 of file NextBestViewCalculator.hpp.
|
inlineprivate |
Definition at line 829 of file NextBestViewCalculator.hpp.
|
inline |
sets number of threads used to rate samples, negative numbers use boost::thread::hardware_concurrency() as number of threads.
| value |
Definition at line 1205 of file NextBestViewCalculator.hpp.
|
inline |
///
Sets the point cloud points from point cloud message
| message | - message containing the point cloud |
Definition at line 610 of file NextBestViewCalculator.hpp.
|
inline |
Sets the point cloud ptr.
Definition at line 896 of file NextBestViewCalculator.hpp.
|
inline |
Sets the rating module.
| ratingModulePtr | - the pointer to the rating module |
Definition at line 1091 of file NextBestViewCalculator.hpp.
|
inline |
setRatingModuleAbstractFactoryPtr used to generate rating modules per thread.
| ratingModuleAbstractFactoryPtr |
Definition at line 1153 of file NextBestViewCalculator.hpp.
|
inline |
Definition at line 1245 of file NextBestViewCalculator.hpp.
|
inline |
sets the robot model
| robotModelPtr | - the pointer to robot model. |
Definition at line 1061 of file NextBestViewCalculator.hpp.
|
inline |
Sets the space sampler.
| spaceSamplerPtr | - the pointer to the space sampler |
Definition at line 1046 of file NextBestViewCalculator.hpp.
|
inline |
Sets the unit sphere sampler.
| unitSphereSamplerPtr | - the pointer to the unit sphere sampler |
Definition at line 1031 of file NextBestViewCalculator.hpp.
|
inline |
updates point cloud with external viewport point list
| viewportPointList | the list of viewport points |
Definition at line 545 of file NextBestViewCalculator.hpp.
|
inline |
Updates the point cloud under the assumption that the given viewport was chosen.
| objectTypeSetPtr | the object type names that shall be updated. |
| viewportPoint | the viewport that was chosen |
Definition at line 584 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 54 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 68 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 63 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 70 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 73 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 76 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 77 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 71 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 65 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 55 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 60 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 79 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 85 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 81 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 72 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 52 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 67 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 64 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 86 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 62 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 61 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 82 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 83 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 59 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 74 of file NextBestViewCalculator.hpp.
|
private |
Definition at line 56 of file NextBestViewCalculator.hpp.