Namespaces | |
hdf5features | |
hdf5util | |
intelem | |
manipulators | |
qttf | |
synthetic | |
Classes | |
class | AABB |
A struct to calculate the Axis Aligned Bounding Box and Average Point of a Point Cloud. More... | |
class | AdaptiveKSearchSurface |
A point cloud manager class that uses the STANN nearest neighbor search library to handle the data. This class calculates robust surface normals for the given point set as described in the SSRR2010 paper. More... | |
class | ArrayIO |
class | Arrow |
class | AsciiIO |
A import / export class for point cloud data in plain text formats. Currently the file extensions .xyz, .txt, .3d and .pts are supported. More... | |
class | AsciiRenderer |
class | AttributeMap |
Interface for attribute maps. More... | |
class | AttributeMapHandleIterator |
Iterator over keys of an attribute map. More... | |
class | AttributeMapHandleIteratorPtr |
Simple convinience wrapper for unique_ptr<AttributeMapHandleIterator> More... | |
class | AttributeMeshIOBase |
class | AzimuthalProjection |
class | BaseBuffer |
ChannelManager class Store and access AttributeChannels. It expands the MultiChannelMap with downwoards compitibility functions of the old ChannelManager. More... | |
class | BaseHandle |
Interface for all kinds of handles. Handles are basically a key to refer to something. More... | |
class | BaseIO |
Interface specification for low-level io. All read elements are stored in linear arrays. More... | |
class | BaseMesh |
Interface for triangle-meshes with adjacency information. More... | |
class | BaseOption |
class | BaseOptionalHandle |
Base class for optional handles (handles that can be "null" or "None"). More... | |
struct | BaseVector |
A generic, weakly-typed vector. More... | |
class | BigGrid |
class | BigGridKdTree |
class | BigVolumen |
class | BilinearFastBox |
struct | BitField |
struct | BOct |
class | BoctreeIO |
IO-Class to import compressed octrees from slam6d. More... | |
class | BoundingBox |
A dynamic bounding box class. More... | |
struct | BoundingRectangle |
A representation of a bounding rectangle. More... | |
struct | BoxTraits |
struct | BoxTraits< BilinearFastBox< BaseVecT > > |
struct | BoxTraits< SharpBox< BaseVecT > > |
struct | BrailleChar |
class | BVHRaycaster |
BVHRaycaster: CPU version of BVH Raycasting: WIP. More... | |
class | BVHTree |
Implementation of an Bounding Volume Hierarchy Tree used for ray casting. More... | |
class | C_Octree |
struct | Cell |
class | CellHandle |
struct | CellInfo |
class | Channel |
class | ChannelIO |
class | ChunkBuilder |
class | ChunkedMeshCuller |
class | ChunkGeomtryChannelVisitor |
visitor that returns the channel that holds geometic information (like vertices-channel for meshes) More... | |
class | ChunkHashGrid |
class | ChunkingPipeline |
class | ChunkIO |
struct | ChunkLeaf |
class | ChunkManager |
class | CLRaycaster |
CLRaycaster: GPU OpenCL version of BVH Raycasting. More... | |
class | ClSOR |
class | ClSurface |
struct | Cluster |
Represents a group of handles, which are somehow connected. More... | |
class | ClusterBiMap |
A map of clusters, which also saves a back-reference from handle to cluster. More... | |
class | ClusterBiMapIterator |
Iterator over cluster handles in this cluster map. More... | |
class | ClusterHandle |
Handle to access Cluster of the ClusterBiMap. More... | |
class | ClusterPainter |
Algorithm which generates the same color for all vertices, which are in the same cluster. More... | |
class | ClusterTexCoordMapping |
Mapping of clusters to texture coordinates for a single vertex. More... | |
class | CLUtil |
Util class for CL that maps error codes to human readable strings. More... | |
struct | color |
class | ColorMap |
class | Colors |
class | ColorVertex |
A color vertex. More... | |
class | CompareDistancePair |
class | ConicProjection |
struct | ConstructType |
struct | coord |
class | CoordinateAxes |
struct | CoordinateTransform |
Stores information to transform a 3D point into a different coordinate system. It is assumed, that the coordinate called x is refered to as coordinate 0, y is 1 and z is 2. More... | |
class | CudaSurface |
class | CylindricalProjection |
class | DatIO |
IO class for binary laser scans. More... | |
struct | Description |
class | DirectoryIO |
class | DirectoryKernel |
class | DirectorySchema |
Marker interface for directory schemas. More... | |
class | DMCPointHandle |
class | DMCReconstruction |
A surface reconstruction object that implements the standard marching cubes algorithm using a octree and a thread pool for parallel computation. More... | |
class | DMCVecPointHandle |
class | DrcIO |
class | DualLeaf |
class | DynamicKDTree |
struct | EdgeCollapseRemovedFace |
struct | EdgeCollapseResult |
class | EdgeHandle |
Handle to access edges of the mesh. More... | |
class | EdgeIteratorProxy |
struct | EdgeSplitResult |
class | EigenSVDPointAlign |
class | ElementProxy |
class | ElementProxyPtr |
This class emulates a Pointer behaviour for an ElementProxy if its & operator is used. The arithmetic is based on the width of an ElementProxy. It was necessary for the Octree. USE WITH CARE. More... | |
class | EmbreeRaycaster |
class | EquirectangularProjection |
class | FaceHandle |
Handle to access faces of the mesh. More... | |
class | FaceIteratorProxy |
class | FastBox |
A volume representation used by the standard Marching Cubes implementation. More... | |
class | FastReconstruction |
A surface reconstruction object that implements the standard marching cubes algorithm using a hashed grid structure for parallel computation. More... | |
class | FastReconstructionBase |
class | FeatureBase |
Manager Class for all FeatureBase components located in hdf5 directory. More... | |
class | FeatureConstruct |
Helper class how to construct a IO feature with its dependencies. More... | |
struct | FeatureConstruct< ChunkIO, FeatureBase > |
struct | FeatureConstruct< HyperspectralCameraIO, FeatureBase > |
FeatureConstruct Specialization for ScanCameraIO. More... | |
struct | FeatureConstruct< PointCloudIO, FeatureBase > |
struct | FeatureConstruct< ScanCameraIO, FeatureBase > |
FeatureConstruct Specialization for hdf5features::ScanCameraIO. More... | |
struct | FeatureConstruct< ScanImageIO, FeatureBase > |
FeatureConstruct Specialization for hdf5features::ScanImageIO. More... | |
struct | FeatureConstruct< ScanIO, FeatureBase > |
FeatureConstruct Specialization for ScanIO. More... | |
struct | FeatureConstruct< ScanPositionIO, FeatureBase > |
struct | FeatureConstruct< ScanProjectIO, FeatureBase > |
struct | fileAttribut |
class | FileKernel |
class | GeoTIFFIO |
class providing and encapsulating GDAL GeoTIFF I/O functions More... | |
class | GlTexture |
class | GraphSLAM |
Wrapper class for running GraphSLAM on Scans. More... | |
class | Grid |
class | GridBase |
class | GridIO |
class | GroundPlane |
class | GroupedChannelIO |
Interface class for io classes that support annotation channels organized in different groups. More... | |
class | GrowingCellStructure |
struct | HalfEdge |
struct | HalfEdgeFace |
Represents a face in the HEM data structure. More... | |
class | HalfEdgeHandle |
Handle to access half edges of the HEM. More... | |
class | HalfEdgeMesh |
Half-edge data structure implementing the BaseMesh interface. More... | |
struct | HalfEdgeVertex |
Represents a vertex in the HEM data structure. More... | |
class | HashGrid |
class | HashMap |
class | HashMapIterator |
class | Hdf5Construct |
Helper class how to construct a IO feature with its dependencies. More... | |
struct | Hdf5Construct< hdf5features::ChunkIO, Derived > |
struct | Hdf5Construct< hdf5features::HyperspectralCameraIO, Derived > |
Hdf5Construct Specialization for hdf5features::ScanCameraIO. More... | |
struct | Hdf5Construct< hdf5features::MeshIO, Derived > |
Hdf5Construct Specialization for hdf5features::MeshIO. More... | |
struct | Hdf5Construct< hdf5features::PointCloudIO, Derived > |
struct | Hdf5Construct< hdf5features::ScanCameraIO, Derived > |
Hdf5Construct Specialization for hdf5features::ScanCameraIO. More... | |
struct | Hdf5Construct< hdf5features::ScanImageIO, Derived > |
Hdf5Construct Specialization for hdf5features::ScanImageIO. More... | |
struct | Hdf5Construct< hdf5features::ScanIO, Derived > |
Hdf5Construct Specialization for hdf5features::ScanIO. More... | |
struct | Hdf5Construct< hdf5features::ScanPositionIO, Derived > |
struct | Hdf5Construct< hdf5features::ScanProjectIO, Derived > |
struct | Hdf5Construct< hdf5features::VariantChannelIO, BaseIO > |
struct | Hdf5Construct< VariantChannelIO, BaseIO > |
class | Hdf5IO |
Manager Class for all Hdf5IO components located in hdf5 directory. More... | |
class | HDF5IO |
class | HDF5Kernel |
class | HDF5MetaDescriptionBase |
class | HDF5MetaDescriptionV2 |
class | HDF5Schema |
Marker interface for HDF5 schemas. More... | |
class | HemEdgeIterator |
class | HemFevIterator |
Implementation of the MeshHandleIterator for the HalfEdgeMesh. More... | |
struct | HyperspectralCalibration_ |
struct | HyperspectralCamera |
class | HyperspectralCameraIO |
struct | HyperspectralCameraModel |
struct | HyperspectralPanorama |
struct | HyperspectralPanoramaChannel |
class | ICPPointAlign |
A class to align two Scans with ICP. More... | |
struct | idxVal |
class | ImageIO |
class | ImageTexturizer |
A texturizer that uses images instead of pointcloud colors for creating the textures for meshes. More... | |
class | InteractivePointCloud |
struct | Intersection |
CRTP Container for User defined intersection elements. More... | |
struct | IOType |
struct | IOType< FeatureBase, MeshBufferPtr > |
struct | IOType< FeatureBase, PointBufferPtr > |
class | KDLeaf |
class | KDNode |
class | KDTree |
a kd-Tree Implementation for nearest Neighbor searches More... | |
class | KinectGrabber |
class | KinectIO |
class | LargeScaleReconstruction |
class | LasIO |
Interface class to read laser scan data in .las-Format. More... | |
class | LBKdTree |
The LBKdTree class implements a left-balanced array-based index kd-tree. Left-Balanced: minimum memory Array-Based: Good for GPU - Usage. More... | |
struct | LBPointArray |
struct | Leaf |
struct | Line |
A Line. More... | |
struct | LineReader |
class | ListMap |
A simple implementation of AttributeMap for a small number of values. More... | |
class | ListMapIterator |
class | LocalApproximation |
An interface class for local approximation operations (e.g. in a Marching Cubes box) More... | |
class | Location |
struct | LSROptions |
class | LVRAnimationDialog |
class | LVRBackgroundDialog |
class | LVRBoundingBoxBridge |
class | LVRBoundingBoxItem |
class | LVRCamDataItem |
class | LVRChunkedMeshBridge |
class | LVRCorrespondanceDialog |
class | LVRCvImageItem |
class | LVREstimateNormalsDialog |
class | LVRGraphicsView |
class | LVRHistogram |
class | LVRLabelDialog |
class | LVRMainWindow |
class | LVRMeshBufferBridge |
class | LVRMeshItem |
class | LVRMLSProjectionDialog |
class | LVRModelBridge |
Main class for conversion of LVR model instances to vtk actors. This class parses the internal model structures to vtk representations that can be added to a vtkRenderer instance. More... | |
class | LVRModelItem |
class | LVRPickingInteractor |
class | LVRPickItem |
class | LVRPlanarOptimizationDialog |
class | LVRPlotter |
class | LVRPointBufferBridge |
class | LVRPointCloudItem |
class | LVRPointInfo |
class | LVRPoseItem |
class | LVRReconstructViaExtendedMarchingCubesDialog |
class | LVRReconstructViaMarchingCubesDialog |
class | LVRRecordedFrameItem |
class | LVRRemoveArtifactsDialog |
class | LVRRemoveOutliersDialog |
class | LVRRenameDialog |
class | LVRScanDataItem |
class | LVRTextureMeshItem |
class | LVRTransformationDialog |
class | LVRTreeWidgetHelper |
class | LVRVtkArrow |
A wrapper class to generate arrow actors for vtk based on VTK's oriented arrow example. More... | |
struct | Material |
A material that stores information about color and texture of a cluster. More... | |
struct | MaterialGroup |
class | Materializer |
Class for calculating materials for each cluster of a given mesh. More... | |
struct | MaterializerResult |
Result struct for the materializer. More... | |
class | Matrix4 |
A 4x4 matrix class implementation for use with the provided vertex types. More... | |
class | MatrixIO |
class | Meap |
A map combined with a binary heap. More... | |
class | MeapPair |
Element in a meap, consisting of a key and a value. More... | |
class | MercatorProjection |
class | MeshBuffer |
The MeshBuffer Mesh representation for I/O modules. More... | |
class | MeshCluster |
class | MeshGenerator |
Interface class for mesh based reconstruction algorithms. More... | |
class | MeshGeometryIO |
class | MeshHandleIterator |
An iterator for handles in the BaseMesh. More... | |
class | MeshHandleIteratorPtr |
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <3. More... | |
class | MeshOctree |
class | Metascan |
Represents several Scans as part of a single Scan. More... | |
class | Model |
class | ModelFactory |
Factory class extract point cloud and mesh information from supported file formats. The instantiated MeshLoader and PointLoader instances are persistent, i.e. they will not be freed in the destructor of this class to prevent side effects. More... | |
class | ModelToImage |
The ModelToImage class provides methods to re-project 3D laser scans to image planes. More... | |
class | MultiPointCloud |
struct | my_dummy |
struct | Node |
class | NodeData |
struct | Normal |
A vector guaranteed to be normalized (length = 1). More... | |
class | ObjIO |
A basic implementation of the obj file format. More... | |
class | OctreeReduction |
class | OpenMPConfig |
class | OptionalClusterHandle |
Semantically equivalent to boost::optional<ClusterHandle> More... | |
class | OptionalEdgeHandle |
Semantically equivalent to boost::optional<EdgeHandle> More... | |
class | OptionalFaceHandle |
Semantically equivalent to boost::optional<FaceHandle> More... | |
class | OptionalHalfEdgeHandle |
Semantically equivalent to boost::optional<HalfEdgeHandle> More... | |
class | OptionalVertexHandle |
Semantically equivalent to boost::optional<VertexHandle> More... | |
class | PacmanProgressBar |
struct | PanicException |
An exception denoting an internal bug. More... | |
class | PanniniProjection |
class | PanoramaNormals |
The PanoramaNormals class computes normals for a given panorama. More... | |
class | PCDIO |
A import / export class for point cloud data in the PointCloudLibrary file format. More... | |
struct | PinholeModel |
struct | Plane |
A plane. More... | |
struct | PlutoMapImage |
class | PlutoMapIO |
struct | PlutoMapMaterial |
class | PLYIO |
A class for input and output to ply files. More... | |
class | PointBuffer |
A class to handle point information with an arbitrarily large number of attribute channels. The added channels should always have the same length as the point array to keep the mapping between geometry (channel 'points') and the associated layers like RGB colors or point normals consistent. More... | |
class | PointCloud |
struct | PointCloudAttribute |
class | PointCloudIO |
Hdf5IO Feature for handling PointBuffer related IO. More... | |
class | PointCorrespondences |
class | PointOctree |
class | PointsetGrid |
class | PointsetMeshGenerator |
Interface class for surface reconstruction algorithms that generate triangle meshes from point set surfaces. More... | |
class | PointsetSurface |
An interface class to wrap all functionality that is needed to generate a surface approximation from point cloud data. More... | |
struct | Pose |
class | PPMIO |
An implementation of the PPM file format. More... | |
class | ProgressBar |
class | ProgressCounter |
A progress counter class. More... | |
class | Projection |
class | Quaternion |
class | QueryPoint |
A query Vector for marching cubes reconstructions. It represents a Vector in space together with a 'distance' value that is used by the marching cubes algorithm. More... | |
class | RaycasterBase |
RaycasterBase interface. More... | |
class | RectilinearProjection |
class | Renderable |
struct | RGBMaterial |
class | RieglProject |
class | RxpIO |
Reads .rxp files. More... | |
struct | Scan |
struct | ScanCamera |
class | ScanCameraIO |
class | ScanDataManager |
class | ScanDirectoryParser |
struct | ScanImage |
class | ScanImageIO |
struct | ScanInfo |
class | ScanIO |
struct | ScanPosition |
class | ScanPositionIO |
struct | ScanProject |
struct | ScanProjectEditMark |
class | ScanProjectIO |
Hdf5IO Feature for handling ScanProject related IO. More... | |
class | ScanProjectSchema |
class | ScanProjectSchemaHyperlib |
class | ScanProjectSchemaSLAM |
class | SearchTree |
Abstract interface for storing and searching through a set of points. Query functions for nearest neighbour searches are defined. More... | |
class | SearchTreeFlann |
SearchClass for point data. More... | |
class | SharpBox |
Used for extended marching cubes Reconstruction. More... | |
class | SimpleFinalizer |
class | SLAMAlign |
A class to run SLAM on Scans. More... | |
struct | SLAMOptions |
A struct to configure SLAMAlign. More... | |
class | SLAMScanWrapper |
A Wrapper around Scan to allow for SLAM usage. More... | |
class | sort_indices |
class | StableVector |
A vector which guarantees stable indices and features O(1) deletion. More... | |
class | StableVectorIterator |
Iterator over handles in this vector, which skips deleted elements. More... | |
class | StaticMesh |
class | StereographicProjection |
class | STLIO |
class | Tesselator |
class | TetraederBox |
Used for Marching Tetreader Reconstruction. Dives a regular box into 5 Tetraeders for mesh generation. More... | |
struct | TexCoords |
Texture coordinates. More... | |
class | Texture |
This class represents a texture. More... | |
class | TexturedMesh |
class | TextureFactory |
class | TextureFinalizer |
class | TextureHandle |
Handle to access textures of the mesh. More... | |
class | Texturizer |
Class that performs texture-related tasks. More... | |
class | Timestamp |
A helper class for automated time stamping. Timing is started as soon as an object of this class is created. To time some parts of a program, just create a new object and use the provided output operator to display the elapsed time. More... | |
class | TransformableBase |
Interface for transformable objects. More... | |
class | TumbleTree |
class | UosIO |
An input class for laser scans in UOS 3d format. More... | |
class | Util |
A class that contains utility functions/types. More... | |
class | VariantChannel |
class | VariantChannelIO |
Hdf5IO Feature for handling VariantChannel related IO. More... | |
class | VariantChannelMap |
class | VectorMap |
A map with constant lookup overhead using small-ish integer-keys. More... | |
class | VectorMapIterator |
class | VertexHandle |
Handle to access vertices of the mesh. More... | |
class | VertexIteratorProxy |
struct | VertexLoopException |
struct | VertexSplitResult |
class | VirtualGrid |
Typedefs | |
using | AllInt = Intersection< intelem::Point, intelem::Distance, intelem::Normal, intelem::Face, intelem::Barycentrics, intelem::Mesh > |
using | AsciiRendererPtr = std::shared_ptr< AsciiRenderer > |
template<typename T > | |
using | AttributeChannel = Channel< T > |
using | BaseVec = BaseVector< float > |
using | BoundingBoxBridgePtr = boost::shared_ptr< LVRBoundingBoxBridge > |
typedef struct lvr2::Cell | Cell |
template<typename T > | |
using | ChannelOptional = typename Channel< T >::Optional |
template<typename T > | |
using | ChannelPtr = typename Channel< T >::Ptr |
using | ChunkBuilderPtr = std::shared_ptr< ChunkBuilder > |
typedef boost::shared_ptr< LVRChunkedMeshBridge > | ChunkedMeshBridgePtr |
using | ChunkHDF5IO = lvr2::Hdf5IO< lvr2::hdf5features::ArrayIO, lvr2::hdf5features::ChannelIO, lvr2::hdf5features::VariantChannelIO, lvr2::hdf5features::MeshIO > |
template<typename ValueT > | |
using | ClusterMap = AttributeMap< ClusterHandle, ValueT > |
typedef boost::shared_array< color< unsigned char > > | color3bArr |
typedef boost::shared_array< coord< float > > | coord3fArr |
typedef ColorVertex< float, unsigned char > | cVertex |
template<typename HandleT , typename ValueT > | |
using | DenseAttrMap = VectorMap< HandleT, ValueT > |
template<typename ValueT > | |
using | DenseClusterMap = DenseAttrMap< ClusterHandle, ValueT > |
template<typename ValueT > | |
using | DenseEdgeMap = DenseAttrMap< EdgeHandle, ValueT > |
template<typename ValueT > | |
using | DenseFaceMap = DenseAttrMap< FaceHandle, ValueT > |
template<typename ValueT > | |
using | DenseVertexMap = DenseAttrMap< VertexHandle, ValueT > |
template<typename ValueT > | |
using | DenseVertexMapOptional = boost::optional< DenseVertexMap< ValueT > > |
using | DirectoryIOPtr = std::shared_ptr< DirectoryIO > |
using | DirectoryKernelPtr = std::shared_ptr< DirectoryKernel > |
using | DirectorySchemaPtr = std::shared_ptr< DirectorySchema > |
using | DistInt = Intersection< intelem::Distance > |
template<typename T > | |
using | Distortion = Eigen::Matrix< T, 6, 1 > |
Distortion Parameters. More... | |
using | Distortiond = Distortion< double > |
Distortion Parameters (double precision) More... | |
using | Distortionf = Distortion< float > |
Distortion Parameters (single precision) More... | |
typedef boost::shared_array< double > | doubleArr |
using | DoubleChannel = Channel< double > |
using | DoubleChannelOptional = DoubleChannel::Optional |
using | DoubleChannelPtr = DoubleChannel::Ptr |
template<typename ValueT > | |
using | EdgeMap = AttributeMap< EdgeHandle, ValueT > |
template<typename T > | |
using | Extrinsics = Eigen::Matrix< T, 4, 4 > |
4x4 extrinsic calibration More... | |
using | Extrinsicsd = Extrinsics< double > |
4x4 extrinsic calibration (double precision) More... | |
using | Extrinsicsf = Extrinsics< float > |
4x4 extrinsic calibration (single precision) More... | |
using | FaceInt = Intersection< intelem::Face, intelem::Barycentrics > |
template<typename ValueT > | |
using | FaceMap = AttributeMap< FaceHandle, ValueT > |
template<template< typename > typename Feature> | |
using | FeatureBuild = typename FeatureConstruct< Feature >::type |
using | FileKernelPtr = std::shared_ptr< FileKernel > |
typedef boost::shared_array< float > | floatArr |
using | FloatChannel = Channel< float > |
using | FloatChannelOptional = FloatChannel::Optional |
using | FloatChannelPtr = FloatChannel::Ptr |
using | floatOptional = boost::optional< float > |
using | FloatProxy = ElementProxy< float > |
template<template< typename > typename Feature> | |
using | Hdf5Build = typename Hdf5Construct< Feature >::type |
using | HDF5KernelPtr = std::shared_ptr< HDF5Kernel > |
using | HDF5SchemaPtr = std::shared_ptr< HDF5Schema > |
typedef struct lvr2::HyperspectralCalibration_ | HyperspectralCalibration |
using | HyperspectralCameraModelPtr = std::shared_ptr< HyperspectralCameraModel > |
using | HyperspectralCameraPtr = std::shared_ptr< HyperspectralCamera > |
using | HyperspectralPanoramaChannelOptional = boost::optional< HyperspectralPanoramaChannel > |
using | HyperspectralPanoramaChannelPtr = std::shared_ptr< HyperspectralPanoramaChannel > |
using | HyperspectralPanoramaOptional = boost::optional< HyperspectralPanorama > |
using | HyperspectralPanoramaPtr = std::shared_ptr< HyperspectralPanorama > |
typedef boost::shared_array< idxVal< float > > | idx1fArr |
typedef boost::shared_array< idxVal< unsigned int > > | idx1uArr |
typedef boost::shared_array< coord< unsigned int > > | idx3uArr |
using | Index = uint32_t |
Datatype used as index for each vertex, face and edge. More... | |
typedef boost::shared_array< unsigned int > | indexArray |
using | IndexChannel = Channel< unsigned int > |
using | IndexChannelOptional = IndexChannel::Optional |
using | IndexChannelPtr = IndexChannel::Ptr |
typedef std::pair< size_t, size_t > | indexPair |
using | IndexProxy = ElementProxy< unsigned int > |
typedef boost::shared_array< int > | intArray |
using | intOptional = boost::optional< int > |
template<typename T > | |
using | Intrinsics = Eigen::Matrix< T, 3, 3 > |
4x4 extrinsic calibration More... | |
using | Intrinsicsd = Intrinsics< double > |
4x4 extrinsic calibration (double precision) More... | |
using | Intrinsicsf = Intrinsics< float > |
4x4 intrinsic calibration (single precision) More... | |
using | KDTreePtr = std::shared_ptr< KDTree > |
typedef std::map< std::string, std::vector< unsigned int > > | labeledFacesMap |
typedef boost::shared_array< RGBMaterial * > | materialArr |
using | Matrix3dRM = Matrix3RM< double > |
3x3 row major matrix with double scalars More... | |
using | Matrix3fRM = Matrix3RM< float > |
3x3 row major matrix with float scalars More... | |
template<typename T > | |
using | Matrix3RM = Eigen::Matrix< T, 3, 3, Eigen::RowMajor > |
General alias for row major 3x3 matrices. More... | |
using | Matrix4d = Eigen::Matrix4d |
Eigen 4x4 matrix, double precision. More... | |
using | Matrix4dRM = Matrix4RM< double > |
4x4 row major matrix with double scalars More... | |
using | Matrix4f = Eigen::Matrix4f |
Eigen 4x4 matrix, single precision. More... | |
using | Matrix4fRM = Matrix4RM< float > |
4x4 row major matrix with float scalars More... | |
template<typename T > | |
using | Matrix4RM = Eigen::Matrix< T, 4, 4, Eigen::RowMajor > |
General alias for row major 4x4 matrices. More... | |
using | Matrix6d = Eigen::Matrix< double, 6, 6 > |
6D matrix double precision More... | |
using | Matrix6f = Eigen::Matrix< float, 6, 6 > |
6D Matrix, single precision More... | |
typedef boost::shared_ptr< LVRMeshBufferBridge > | MeshBufferBridgePtr |
using | MeshBufferPtr = std::shared_ptr< MeshBuffer > |
typedef boost::shared_ptr< LVRModelBridge > | ModelBridgePtr |
typedef boost::shared_ptr< ModelFactory > | ModelFactoryPtr |
using | ModelPtr = std::shared_ptr< Model > |
using | MultiChannelMap = VariantChannelMap< char, unsigned char, short, unsigned short, int, unsigned int, float, double > |
using | NodeOptional = boost::optional< YAML::Node > |
using | NormalInt = Intersection< intelem::Normal > |
typedef void(* | PacmanProgressCallbackPtr) (int) |
A class to manage progress information output for process where the number of performed operations is known in advance, e.g. number of loop iterations. More... | |
typedef void(* | PacmanProgressTitleCallbackPtr) (string) |
typedef map< PointCloud *, PointCloudAttribute * >::iterator | pc_attr_it |
typedef map< PointCloud *, PointCloudAttribute * > | pc_attr_map |
using | PinholeModeld = PinholeModel< double > |
using | PinholeModelf = PinholeModel< float > |
template<typename T > | |
using | PinholeModelPtr = std::shared_ptr< PinholeModel< T > > |
typedef boost::shared_ptr< LVRPointBufferBridge > | PointBufferBridgePtr |
using | PointBufferPtr = std::shared_ptr< PointBuffer > |
using | PointInt = Intersection< intelem::Point > |
template<typename BaseVecT > | |
using | PointsetSurfacePtr = std::shared_ptr< PointsetSurface< BaseVecT > > |
typedef void(* | ProgressCallbackPtr) (int) |
A class to manage progress information output for process where the number of performed operations is known in advance, e.g. number of loop iterations. More... | |
typedef void(* | ProgressTitleCallbackPtr) (string) |
typedef QueryPoint< Vec > | QueryPointC |
template<typename IntT > | |
using | RaycasterBasePtr = std::shared_ptr< RaycasterBase< IntT > > |
using | Rgb8Color = std::array< uint8_t, 3 > |
template<typename T > | |
using | Rotation = Eigen::Matrix< T, 3, 3 > |
General 3x3 rotation matrix. More... | |
using | Rotationd = Rotation< double > |
Double precision 3x3 rotation matrix. More... | |
using | Rotationf = Rotation< float > |
Single precision 3x3 rotation matrix. More... | |
using | ScanCameraPtr = std::shared_ptr< ScanCamera > |
using | ScanImageOptional = boost::optional< ScanImage > |
using | ScanImagePtr = std::shared_ptr< ScanImage > |
using | ScanOptional = boost::optional< Scan > |
using | ScanPositionPtr = std::shared_ptr< ScanPosition > |
using | ScanProjectEditMarkPtr = std::shared_ptr< ScanProjectEditMark > |
using | ScanProjectPtr = std::shared_ptr< ScanProject > |
using | ScanProjectSchemaPtr = std::shared_ptr< ScanProjectSchema > |
using | ScanPtr = std::shared_ptr< Scan > |
Shared pointer to scans. More... | |
template<typename BaseVecT > | |
using | SearchTreePtr = std::shared_ptr< SearchTree< BaseVecT > > |
typedef boost::shared_array< short > | shortArr |
using | SLAMScanPtr = std::shared_ptr< SLAMScanWrapper > |
template<typename HandleT , typename ValueT > | |
using | SparseAttrMap = HashMap< HandleT, ValueT > |
template<typename ValueT > | |
using | SparseClusterMap = SparseAttrMap< ClusterHandle, ValueT > |
template<typename ValueT > | |
using | SparseEdgeMap = SparseAttrMap< EdgeHandle, ValueT > |
template<typename ValueT > | |
using | SparseFaceMap = SparseAttrMap< FaceHandle, ValueT > |
template<typename ValueT > | |
using | SparseVertexMap = SparseAttrMap< VertexHandle, ValueT > |
using | StringOptional = boost::optional< std::string > |
typedef boost::shared_array< GlTexture * > | textureArr |
template<typename HandleT , typename ValueT > | |
using | TinyAttrMap = ListMap< HandleT, ValueT > |
template<typename ValueT > | |
using | TinyClusterMap = TinyAttrMap< ClusterHandle, ValueT > |
template<typename ValueT > | |
using | TinyEdgeMap = TinyAttrMap< EdgeHandle, ValueT > |
template<typename ValueT > | |
using | TinyFaceMap = TinyAttrMap< FaceHandle, ValueT > |
template<typename ValueT > | |
using | TinyVertexMap = TinyAttrMap< VertexHandle, ValueT > |
template<typename T > | |
using | Transform = Eigen::Matrix< T, 4, 4 > |
General 4x4 transformation matrix (4x4) More... | |
typedef TransformableBase< double > | Transformable |
using | Transformd = Transform< double > |
4x4 double precision transformation matrix More... | |
using | Transformf = Transform< float > |
4x4 single precision transformation matrix More... | |
typedef boost::shared_array< unsigned char > | ucharArr |
using | UCharChannel = Channel< unsigned char > |
using | UCharChannelOptional = UCharChannel::Optional |
using | UCharChannelPtr = UCharChannel::Ptr |
using | ucharOptional = boost::optional< unsigned char > |
using | UCharProxy = ElementProxy< unsigned char > |
using | uColorVertex = ColorVertex< float, unsigned char > |
typedef boost::shared_array< unsigned int > | uintArr |
template<typename ... Tp> | |
using | VariantChannelOptional = boost::optional< VariantChannel< Tp... > > |
using | Vec = BaseVector< float > |
template<typename T > | |
using | Vector2 = Eigen::Matrix< T, 2, 1 > |
Eigen 2D vector. More... | |
using | Vector2d = Eigen::Vector2d |
Eigen 2D vector, double precision. More... | |
using | Vector2f = Eigen::Vector2f |
Eigen 2D vector, single precision. More... | |
template<typename T > | |
using | Vector3 = Eigen::Matrix< T, 3, 1 > |
Eigen 3D vector. More... | |
using | Vector3d = Eigen::Vector3d |
Eigen 3D vector, double precision. More... | |
using | Vector3f = Eigen::Vector3f |
Eigen 3D vector, single precision. More... | |
using | Vector3i = Eigen::Vector3i |
Eigen 3D vector, integer. More... | |
template<typename T > | |
using | Vector4 = Eigen::Matrix< T, 4, 1 > |
Eigen 4D vector. More... | |
using | Vector4d = Eigen::Vector4d |
Eigen 4D vector, double precision. More... | |
using | Vector4f = Eigen::Vector4f |
Eigen 4D vector, single precision. More... | |
using | Vector6d = Eigen::Matrix< double, 6, 1 > |
6D vector double precision More... | |
using | Vector6f = Eigen::Matrix< float, 6, 1 > |
6D vector, single precision More... | |
using | VecUChar = BaseVector< unsigned char > |
template<typename ValueT > | |
using | VertexMap = AttributeMap< VertexHandle, ValueT > |
Functions | |
struct | __attribute__ ((packed)) xyz |
static void | __checkOclErrors (const cl_int err, const char *const func, const char *const file, const int line) |
void | AsciiRendererErrorFunc (void *userPtr, enum RTCError error, const char *str) |
template<template< typename, typename > typename OutMapT, typename IterProxyT , typename GenF > | |
OutMapT< typename decltype(std::declval< IterProxyT >).begin())::HandleType, typename std::result_of< GenF(typename decltype(std::declval< IterProxyT >).begin())::HandleType)>::type > | attrMapFromFunc (IterProxyT iterProxy, GenF func) |
Creates an attribute map by calling the given function for each element in the given iterator. The iterator yields the keys, the function gives us the corresponding value. More... | |
template<typename T > | |
Transform< T > | buildTransformation (T *alignxf) |
Transforms an slam6d transformation matrix into an Eigen 4x4 matrix. More... | |
template<typename BaseVecT > | |
DenseVertexMap< float > | calcAverageVertexAngles (const BaseMesh< BaseVecT > &mesh, const VertexMap< Normal< typename BaseVecT::CoordType >> &normals) |
Calculates the average angle for each vertex. More... | |
template<typename BaseVecT > | |
Rgb8Color | calcColorForFaceCentroid (const BaseMesh< BaseVecT > &mesh, const PointsetSurface< BaseVecT > &surface, FaceHandle faceH) |
Calculate the color for the centroid of a given face. More... | |
template<typename BaseVecT > | |
boost::optional< DenseVertexMap< Rgb8Color > > | calcColorFromPointCloud (const BaseMesh< BaseVecT > &mesh, const PointsetSurfacePtr< BaseVecT > surface) |
Calculates the color of each vertex from the point cloud. More... | |
template<typename BaseVecT > | |
void | calcContourEdges (const BaseMesh< BaseVecT > &mesh, EdgeHandle startH, std::vector< EdgeHandle > &contourOut) |
Walks on a boundary contour starting at startH and adds all visited edges to the given out vector. More... | |
template<typename BaseVecT , typename PredF > | |
void | calcContourEdges (const BaseMesh< BaseVecT > &mesh, EdgeHandle startH, std::vector< EdgeHandle > &contourOut, PredF exists) |
Walks on a boundary contour starting at startH and adds all visited edges to the given out vector. More... | |
template<typename BaseVecT > | |
void | calcContourVertices (const BaseMesh< BaseVecT > &mesh, EdgeHandle startH, std::vector< VertexHandle > &contourOut) |
Walks on a boundary contour starting at startH and adds all visited vertices to the given out vector. More... | |
template<typename BaseVecT , typename PredF > | |
void | calcContourVertices (const BaseMesh< BaseVecT > &mesh, EdgeHandle startH, std::vector< VertexHandle > &contourOut, PredF exists) |
Walks on a boundary contour starting at startH and adds all visited vertices to the given out vector. More... | |
template<typename BaseVecT > | |
DenseFaceMap< Normal< typename BaseVecT::CoordType > > | calcFaceNormals (const BaseMesh< BaseVecT > &mesh) |
Calculates a normal for each face in the mesh. More... | |
template<typename BaseVecT > | |
void | calcLocalVertexNeighborhood (const BaseMesh< BaseVecT > &mesh, VertexHandle vH, double radius, vector< VertexHandle > &neighborsOut) |
Calculates the local neighborhood of a given vertex (defined by it's handle). More... | |
template<typename BaseVecT > | |
Plane< BaseVecT > | calcRegressionPlane (const BaseMesh< BaseVecT > &mesh, const Cluster< FaceHandle > &cluster, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals) |
Calcs a regression plane for the given cluster. More... | |
template<typename BaseVecT > | |
Plane< BaseVecT > | calcRegressionPlanePCA (const BaseMesh< BaseVecT > &mesh, const Cluster< FaceHandle > &cluster, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, const int num_iterations=100, const int num_samples=10) |
Calcs a regression plane for the given cluster. More... | |
template<typename BaseVecT > | |
Plane< BaseVecT > | calcRegressionPlaneRANSAC (const BaseMesh< BaseVecT > &mesh, const Cluster< FaceHandle > &cluster, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, const int num_iterations=100, const int num_samples=10) |
Calcs a regression plane for the given cluster. More... | |
template<typename BaseVecT > | |
DenseClusterMap< Plane< BaseVecT > > | calcRegressionPlanes (const BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, int minClusterSize) |
Calcs regression planes for all cluster in clusters. More... | |
template<typename BaseVecT > | |
DenseClusterMap< Plane< BaseVecT > > | calcRegressionPlanesRANSAC (const BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, int minClusterSize, int iterations=100, int samples=10) |
Calcs regression planes for all cluster in clusters. More... | |
template<typename BaseVecT > | |
BoundingRectangle< typename BaseVecT::CoordType > | calculateBoundingRectangle (const vector< VertexHandle > &contour, const BaseMesh< BaseVecT > &mesh, const Cluster< FaceHandle > &cluster, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, float texelSize, ClusterHandle clusterH) |
Calculates bounding rectangle for a given cluster. More... | |
template<typename BaseVecT > | |
vector< VertexHandle > | calculateClusterContourVertices (ClusterHandle clusterH, const BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusterBiMap) |
Calculates contour vertices for a given cluster. More... | |
template<typename BaseVecT > | |
DenseEdgeMap< float > | calcVertexAngleEdges (const BaseMesh< BaseVecT > &mesh, const VertexMap< Normal< typename BaseVecT::CoordType >> &normals) |
Calculates the angle between two vertex normals for each edge. More... | |
template<typename BaseVecT > | |
DenseEdgeMap< float > | calcVertexDistances (const BaseMesh< BaseVecT > &mesh) |
Computes the distances between the vertices and stores them in the given dense edge map. More... | |
template<typename BaseVecT > | |
DenseVertexMap< float > | calcVertexHeightDifferences (const BaseMesh< BaseVecT > &mesh, double radius) |
Calculate the height difference value for each vertex of the given BaseMesh. More... | |
template<typename BaseVecT > | |
DenseVertexMap< Normal< typename BaseVecT::CoordType > > | calcVertexNormals (const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals) |
Calculates a normal for each vertex in the mesh. More... | |
template<typename BaseVecT > | |
DenseVertexMap< Normal< typename BaseVecT::CoordType > > | calcVertexNormals (const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, const PointsetSurface< BaseVecT > &surface) |
Calculates a normal for each vertex in the mesh. More... | |
template<typename BaseVecT > | |
DenseVertexMap< float > | calcVertexRoughness (const BaseMesh< BaseVecT > &mesh, double radius, const VertexMap< Normal< typename BaseVecT::CoordType >> &normals) |
Calculates the roughness for each vertex. More... | |
template<typename BaseVecT > | |
void | calcVertexRoughnessAndHeightDifferences (const BaseMesh< BaseVecT > &mesh, double radius, const VertexMap< Normal< typename BaseVecT::CoordType >> &normals, DenseVertexMap< float > &roughness, DenseVertexMap< float > &heightDiff) |
Calculates the roughness and the height difference for each vertex. More... | |
template<typename T > | |
static unsigned int | checkNumberOfBiggerValues (LBPointArray< T > &V, unsigned int dim, T split) |
static unsigned int | checkNumberOfSmallerEqualValues (LBPointArray< float > &V, unsigned int dim, float split) |
template<typename T , typename U > | |
static bool | checkSortedIndices (const LBPointArray< T > &V, const LBPointArray< U > &sorted_indices, unsigned int dim, int n=0) |
template<typename BaseVecT > | |
void | cleanContours (BaseMesh< BaseVecT > &mesh, int iterations, float areaThreshold) |
Removes faces with a high number of boundary edges. More... | |
template<typename BaseVecT , typename Pred > | |
ClusterBiMap< FaceHandle > | clusterGrowing (const BaseMesh< BaseVecT > &mesh, Pred pred) |
Algorithm which generates clusters from the given mesh. The given predicate decides which faces will be in the same clusters. More... | |
template<typename T > | |
bool | color_equal (const color< T > &col1, const color< T > &col2) |
void | convert (COORD_SYSTEM from, COORD_SYSTEM to, float *point) |
void | convert (COORD_SYSTEM from, COORD_SYSTEM to, PointBufferPtr &buffer) |
template<typename T > | |
static void | copyDimensionToPointArray (LBPointArray< T > &in, int dim, LBPointArray< T > &out) |
template<typename T > | |
static void | copyVectorInterval (LBPointArray< T > &in, int start, int end, LBPointArray< T > &out) |
size_t | countPointsInFile (const boost::filesystem::path &inFile) |
Counts the number of points (i.e. number of lines) in the given file. More... | |
KDTreePtr | create_recursive (KDTree::Point *points, int n, int maxLeafSize) |
void | createOctree (Vector3f *points, int n, bool *flagged, const Vector3f &min, const Vector3f &max, int level, double voxelSize, int maxLeafSize) |
void | createTextures (std::vector< int32_t > &drcTextures, std::vector< GlTexture * > &lvrTextures) |
transforms the int32_t vector with texture data into actual GlTextures More... | |
void | createTextures (std::vector< int32_t > &drcTextures, std::vector< Texture > &lvrTextures) |
transforms the int32_t vector with texture data into actual GlTextures More... | |
template<typename BaseVecT > | |
void | debugPlanes (const BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, const ClusterMap< Plane< BaseVecT >> &planes, string filename, size_t minClusterSize) |
Creates a mesh containing the given regression planes (which match the given minimum cluster size) as planes and saves it to a file with the given filename. More... | |
ModelPtr | decodeDraco (draco::DecoderBuffer &buffer, draco::EncodedGeometryType type) |
delivers ModelPtr from draco DecoderBuffer More... | |
template<typename BaseVecT > | |
void | deleteSmallPlanarCluster (BaseMesh< BaseVecT > &mesh, ClusterBiMap< FaceHandle > &clusters, size_t smallClusterThreshold) |
Removes all clusters and their cotained faces from the given mesh which are smaller than the given smallClusterThreshold. More... | |
template<typename BaseVecT > | |
bool | Dijkstra (const BaseMesh< BaseVecT > &mesh, const VertexHandle &start, const VertexHandle &goal, const DenseEdgeMap< float > &edgeCosts, std::list< VertexHandle > &path, DenseVertexMap< float > &distances, DenseVertexMap< VertexHandle > &predecessors, DenseVertexMap< bool > &seen, DenseVertexMap< float > &vertex_costs) |
Dijkstra's algorithm. More... | |
std::ostream & | dout () |
template<typename BaseVecT > | |
void | dragOntoIntersection (BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, const ClusterHandle &clusterH, const ClusterHandle &neighbourClusterH, const Line< BaseVecT > &intersection) |
Drags all points between two clusters (planes) into their intersection. More... | |
template<typename BaseVecT > | |
void | dragToRegressionPlane (BaseMesh< BaseVecT > &mesh, const Cluster< FaceHandle > &cluster, const Plane< BaseVecT > &plane, FaceMap< Normal< typename BaseVecT::CoordType >> &normals) |
Drags all points from the given cluster into the given plane. More... | |
template<typename BaseVecT > | |
void | dragToRegressionPlanes (BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, const ClusterMap< Plane< BaseVecT >> &planes, FaceMap< Normal< typename BaseVecT::CoordType >> &normals) |
Drags all points from the given clusters into their regression planes. More... | |
template<typename T > | |
void | eigenToEuler (Transform< T > &mat, T *pose) |
void | EmbreeErrorFunction (void *userPtr, enum RTCError error, const char *str) |
std::unique_ptr< draco::EncoderBuffer > | encodeDraco (ModelPtr modelPtr, draco::EncodedGeometryType type) |
encodes Model to draco EncodeBuffer which contents can be written into a file More... | |
std::unique_ptr< draco::EncoderBuffer > | encodeMesh (ModelPtr modelPtr, draco::Encoder &encoder) |
transfers a mesh of a modelPtr to a draco EncoderBuffer that can be written into a file More... | |
std::unique_ptr< draco::EncoderBuffer > | encodePointCloud (ModelPtr modelPtr, draco::Encoder &encoder) |
transfers a pointcloud of a modelPtr to a draco EncoderBuffer that can be written into a file More... | |
void | EulerToMatrix (const double *rPos, const double *rPosTheta, float *alignxf) |
void | EulerToMatrix4 (const Vector3d &pos, const Vector3d &theta, Matrix4d &mat) |
Conversion from Pose to Matrix representation. More... | |
template<typename T > | |
void | extrinsicsToEuler (Extrinsics< T > mat, T *pose) |
template<typename T > | |
static void | fillPointArrayWithSequence (int id, LBPointArray< T > &m) |
template<typename T > | |
static void | fillPointArrayWithSequence (LBPointArray< T > &m) |
bool | findCloseScans (const std::vector< SLAMScanPtr > &scans, size_t scan, const SLAMOptions &options, std::vector< size_t > &output) |
finds Scans that are "close" to a Scan as determined by a Loopclosing strategy More... | |
bool | findCloseScans (const vector< SLAMScanPtr > &scans, size_t scan, const SLAMOptions &options, vector< size_t > &output) |
Lists all numbers of scans near to the scan. More... | |
template<typename BaseVecT > | |
vector< vector< VertexHandle > > | findContours (BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, ClusterHandle clusterH) |
static Rgb8Color | floatToGrayScaleColor (float value) |
Convert a given float to an 8-bit Grayscale-Color. More... | |
static Rgb8Color | floatToRainbowColor (float value) |
Convert a given float to an 8-bit RGB-Color, using the rainbowcolor scale. More... | |
template<typename T , typename U > | |
static void | generateAndSort (int id, LBPointArray< T > &vertices, LBPointArray< U > *indices_sorted, LBPointArray< T > *values_sorted, int dim) |
template<typename T > | |
static void | generatePointArray (int id, LBPointArray< T > &m, int width, int dim) |
template<typename T > | |
static void | generatePointArray (LBPointArray< T > &m, int width, int dim) |
std::string | get_first_group_regex (std::regex regex_string, std::string data) |
const draco::PointAttribute * | getDracoAttributeByAttributeMetadata (draco::PointCloud *geometry, std::string key, std::string value) |
delivers PointAttribute by searching for given Attribute Metadata Entries More... | |
template<typename BaseVecT > | |
vector< vector< VertexHandle > > | getDuplicateVertices (const BaseMesh< BaseVecT > &mesh) |
Returns all handles of duplicate vertices from the given mesh. More... | |
template<typename BaseVecT > | |
boost::optional< Normal< typename BaseVecT::CoordType > > | getFaceNormal (array< BaseVecT, 3 > vertices) |
Returns the normal of a face with the given three vertices. More... | |
boost::filesystem::path | getHyperspectralCameraDirectory (boost::filesystem::path root, const std::string positionDirectory, const std::string cameraDirectory) |
HYPERSPECTRAL_CAMERA. More... | |
std::pair< std::string, std::string > | getNames (const std::string &defaultGroup, const std::string &defaultContainer, const Description &d) |
size_t | getNumberOfPointsInPLY (const std::string &filename) |
Get the Number Of Points (element points if present, vertex count otherwise) in a PLY file. More... | |
boost::filesystem::path | getPanoramaChannelDirectory (boost::filesystem::path root, const std::string positionDirectory, const std::string panoramaDirectory) |
HYPERSPECTRAL_PANORAMA_CHANNEL. More... | |
void | getPoseFromFile (BaseVector< float > &position, BaseVector< float > &angles, const boost::filesystem::path file) |
Loads an Euler representation of from a pose file. More... | |
template<typename T > | |
void | getPoseFromMatrix (BaseVector< T > &position, BaseVector< T > &angles, const Transform< T > &mat) |
Computes a Euler representation from the given transformation matrix. More... | |
size_t | getReductionFactor (boost::filesystem::path &inFile, size_t targetSize) |
Computes the reduction factor for a given target size (number of points) when reducing a point cloud loaded from an ASCII file using a modulo filter. More... | |
size_t | getReductionFactor (ModelPtr model, size_t targetSize) |
Computes the reduction factor for a given target size (number of points) when reducing a point cloud using a modulo filter. More... | |
boost::filesystem::path | getScanCameraDirectory (boost::filesystem::path root, const std::string positionDirectory, const std::string cameraDirectory) |
SCANCAMERA. More... | |
boost::filesystem::path | getScanImageDirectory (boost::filesystem::path root, const std::string positionDirectory, const std::string cameraDirectory) |
template<typename BaseVecT > | |
SearchTreePtr< BaseVecT > | getSearchTree (string name, PointBufferPtr buffer) |
Returns the search tree implementation specified by name . More... | |
std::string | getSensorType (const boost::filesystem::path &dir) |
Gets the sensor type for a given directory. Return an empty string if the directory does not contain a meta.yaml file with 'sensor_type' element. More... | |
template<typename T > | |
Transform< T > | getTransformationFromDat (const boost::filesystem::path &frames) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given dat file. More... | |
template<typename T > | |
Transform< T > | getTransformationFromFile (const boost::filesystem::path &file) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given file. More... | |
template<typename T > | |
Transform< T > | getTransformationFromFrames (const boost::filesystem::path &frames) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given frame file. More... | |
template<typename T > | |
Transform< T > | getTransformationFromPose (const boost::filesystem::path &pose) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given pose file. More... | |
static void | HandleError (cudaError_t err, const char *file, int line) |
template<typename BaseVecT > | |
boost::optional< Normal< typename BaseVecT::CoordType > > | interpolatedVertexNormal (const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, VertexHandle handle) |
Returns a vertex normal for the given vertex interpolated from the normals of its adjacent faces. More... | |
template<typename T > | |
Transform< T > | inverseTransform (const Transform< T > &transform) |
Computes the inverse transformation from the given transformation matrix, which means if transform encodes the transformation A->B, the return will transform from B to A. More... | |
bool | isSelfOrChildSelected (QTreeWidgetItem *item) |
template<typename BaseVecT , typename CostF > | |
size_t | iterativeEdgeCollapse (BaseMesh< BaseVecT > &mesh, const size_t count, FaceMap< Normal< typename BaseVecT::CoordType >> &faceNormals, CostF collapseCost) |
Collapses count many edges of mesh for which collapseCost returns the smallest values. More... | |
template<typename BaseVecT > | |
ClusterBiMap< FaceHandle > | iterativePlanarClusterGrowing (BaseMesh< BaseVecT > &mesh, FaceMap< Normal< typename BaseVecT::CoordType >> &normals, float minSinAngle, int numIterations, int minClusterSize) |
Algorithm which generates planar clusters from the given mesh, drags points in clusters into regression planes and improves clusters iteratively. More... | |
template<typename BaseVecT > | |
ClusterBiMap< FaceHandle > | iterativePlanarClusterGrowingRANSAC (BaseMesh< BaseVecT > &mesh, FaceMap< Normal< typename BaseVecT::CoordType >> &normals, float minSinAngle, int numIterations, int minClusterSize, int ransacIterations=100, int ransacSamples=10) |
Algorithm which generates planar clusters from the given mesh, drags points in clusters into regression planes and improves clusters iteratively. More... | |
template<typename LvrArrType , typename DataType , int numComponents> | |
LvrArrType | loadAttributeFromDraco (const draco::PointAttribute *attribute) |
loads any GeometryAttribute from draco pointcloud and returns its values More... | |
template<typename T > | |
Transform< T > | loadFromFile (const boost::filesystem::path &file) |
Reads an Eigen 4x4 matrix from the given file (16 coefficients, row major) More... | |
bool | loadHyperspectralCamera (const boost::filesystem::path &root, HyperspectralCamera &camera, const size_t &positionNumber) |
bool | loadHyperspectralCamera (const boost::filesystem::path &root, HyperspectralCamera &camera, const std::string &positionDirectory) |
bool | loadHyperspectralCamera (const boost::filesystem::path &root, HyperspectralCamera &camera, const std::string &positionDirectory, const std::string &cameraDirectory) |
void | loadHyperspectralPanoramaChannels (std::vector< HyperspectralPanoramaChannelPtr > &channels, boost::filesystem::path dataPath) |
YAML::Node | loadMetaInformation (const std::string &in) |
bool | loadScan (const boost::filesystem::path &root, Scan &scan, const size_t &positionNumber, const size_t &scanNumber) |
bool | loadScan (const boost::filesystem::path &root, Scan &scan, const std::string &positionDirectory, const size_t &scanNumber) |
bool | loadScan (const boost::filesystem::path &root, Scan &scan, const std::string &positionDirectory, const std::string &scanDirectory, const size_t &scanNumber) |
bool | loadScan (const boost::filesystem::path &root, Scan &scan, const std::string &positionDirectory, const std::string &scanDirectory, const std::string &scanName) |
bool | loadScanCamera (const boost::filesystem::path &root, ScanCamera &image, const size_t &positionNumber, const size_t &cameraNumber) |
bool | loadScanCamera (const boost::filesystem::path &root, ScanCamera &image, const std::string &positionDirectory, const size_t &cameraNumber) |
bool | loadScanCamera (const boost::filesystem::path &root, ScanCamera &image, const std::string &positionDirectory, const std::string &cameraDirectory) |
bool | loadScanImage (const boost::filesystem::path &root, ScanImage &image, const size_t &positionNumber, const size_t &cameraNumber, const size_t &imageNumber) |
bool | loadScanImage (const boost::filesystem::path &root, ScanImage &image, const std::string &positionDirectory, const size_t &cameraNumber, const size_t &imageNumber) |
bool | loadScanImage (const boost::filesystem::path &root, ScanImage &image, const std::string &positionDirectory, const std::string &cameraDirectory, const size_t &imageNumber) |
void | loadScanImages (std::vector< ScanImagePtr > &images, boost::filesystem::path dataPath) |
void | loadScanImages (vector< ScanImagePtr > &images, boost::filesystem::path dataPath) |
bool | loadScanPosition (const boost::filesystem::path &root, ScanPosition &scanPos, const size_t &positionNumber) |
bool | loadScanPosition (const boost::filesystem::path &root, ScanPosition &scanPos, const std::string &positionDirectory) |
bool | loadScanProject (const boost::filesystem::path &root, ScanProject &scanProj) |
template<typename T > | |
static Rotation< T > | lvrToOpenCv (const Rotation< T > &in) |
template<typename T > | |
static Transform< T > | lvrToOpenCv (const Transform< T > &in) |
template<typename T > | |
static Vector3< T > | lvrToOpenCv (const Vector3< T > &in) |
Lvr to OpenCV coordinate change: Point. More... | |
template<typename T > | |
static Rotation< T > | lvrToSlam6d (const Rotation< T > &in) |
template<typename T > | |
static Transform< T > | lvrToSlam6d (const Transform< T > &in) |
template<typename T > | |
static Vector3< T > | lvrToSlam6d (const Vector3< T > &in) |
Lvr to Slam6D coordinate change: Point. More... | |
template<typename T > | |
static void | mallocPointArray (LBPointArray< T > &m) |
template<template< typename, typename > typename OutMapT, typename InMapT , typename MapF > | |
OutMapT< typename InMapT::HandleType, std::result_of_t< MapF(typename InMapT::ValueType)> > | map (const InMapT &mapIn, MapF func) |
Calls func for each value of the given map and save the result in the output map. More... | |
void | Matrix4ToEuler (const Matrix4d mat, Vector3d &rPosTheta, Vector3d &rPos) |
Conversion from Matrix to Pose representation. More... | |
template<typename T > | |
void | matrixToPose (const Transform< T > &mat, Vector3< T > &position, Vector3< T > &rotation) |
Extracts the Pose from a Matrix. More... | |
template<typename T , typename U > | |
static void | mergeHostWithIndices (T *a, U *b, unsigned int i1, unsigned int j1, unsigned int i2, unsigned int j2, int limit) |
template<typename HandleT , typename ValueT > | |
pair< ValueT, ValueT > | minMaxOfMap (const AttributeMap< HandleT, ValueT > &map) |
Returns the minimum and maximum element from the given map. More... | |
template<typename T > | |
Vector3< T > | multiply (const Transform< T > &transform, const Vector3< T > &p) |
template<typename BaseVecT > | |
size_t | naiveFillSmallHoles (BaseMesh< BaseVecT > &mesh, size_t maxSize, bool collapseOnly) |
Fills holes consisting of less than or equal to maxSize edges. More... | |
template<typename T , typename U > | |
static void | naturalMergeSort (LBPointArray< T > &in, int dim, LBPointArray< U > &indices, LBPointArray< T > &m, int limit=-1) |
int | octreeReduce (Vector3f *points, int n, double voxelSize, int maxLeafSize) |
Reduces a Point Cloud using an Octree with a minimum Voxel size. More... | |
template<typename T > | |
static Rotation< T > | openCvToLvr (const Rotation< T > &in) |
template<typename T > | |
static Transform< T > | openCvToLvr (const Transform< T > &in) |
template<typename T > | |
static Vector3< T > | openCvToLvr (const Vector3< T > &in) |
OpenCV to Lvr coordinate change: Point. More... | |
template<typename CoordType , typename Scalar = CoordType> | |
BaseVector< CoordType > | operator* (const Eigen::Matrix< Scalar, 4, 4 > &mat, const BaseVector< CoordType > &normal) |
Multiplication operator to support transformation with Eigen matrices. Rotates the normal, ignores translation. Implementation for RowMajor matrices. More... | |
template<typename CoordType , typename Scalar = CoordType> | |
Normal< CoordType > | operator* (const Eigen::Matrix< Scalar, 4, 4 > &mat, const Normal< CoordType > &normal) |
Multiplication operator to support transformation with Eigen matrices. Rotates the normal, ignores translation. Implementation for RowMajor matrices. More... | |
template<typename T > | |
ostream & | operator<< (ostream &os, const Matrix4< T > matrix) |
Output operator for matrices. More... | |
ostream & | operator<< (ostream &os, Timestamp &ts) |
The output operator for Timestamp objects. More... | |
std::ostream & | operator<< (std::ostream &lhs, const RieglProject &rhs) |
std::ostream & | operator<< (std::ostream &lhs, const ScanPosition &rhs) |
template<typename T > | |
std::ostream & | operator<< (std::ostream &os, const BaseVector< T > &v) |
template<typename BaseVecT > | |
std::ostream & | operator<< (std::ostream &os, const BoundingBox< BaseVecT > &bb) |
std::ostream & | operator<< (std::ostream &os, const ClusterHandle &h) |
template<typename CoordType , typename ColorT > | |
std::ostream & | operator<< (std::ostream &os, const ColorVertex< CoordType, ColorT > v) |
Output operator for color vertex types. More... | |
std::ostream & | operator<< (std::ostream &os, const EdgeHandle &h) |
std::ostream & | operator<< (std::ostream &os, const FaceHandle &h) |
std::ostream & | operator<< (std::ostream &os, const HalfEdgeHandle &h) |
template<typename BaseVecT > | |
std::ostream & | operator<< (std::ostream &os, const Line< BaseVecT > &l) |
template<typename CoordType > | |
std::ostream & | operator<< (std::ostream &os, const Normal< CoordType > &n) |
std::ostream & | operator<< (std::ostream &os, const OptionalClusterHandle &h) |
std::ostream & | operator<< (std::ostream &os, const OptionalEdgeHandle &h) |
std::ostream & | operator<< (std::ostream &os, const OptionalFaceHandle &h) |
std::ostream & | operator<< (std::ostream &os, const OptionalHalfEdgeHandle &h) |
std::ostream & | operator<< (std::ostream &os, const OptionalVertexHandle &h) |
template<typename BaseVecT > | |
std::ostream & | operator<< (std::ostream &os, const Plane< BaseVecT > &p) |
std::ostream & | operator<< (std::ostream &os, const VertexHandle &h) |
template<typename BaseVecT > | |
void | optimizePlaneIntersections (BaseMesh< BaseVecT > &mesh, const ClusterBiMap< FaceHandle > &clusters, const ClusterMap< Plane< BaseVecT >> &planes) |
void | panic (std::string msg) |
Throws a panic exception with the given error message. More... | |
void | panic_unimplemented (std::string msg) |
Throws a panic exception with the given error message and denotes that the exception was thrown due to a missing implementation. More... | |
void | parseSLAMDirectory (std::string dir, vector< ScanPtr > &scans) |
Reads a directory containing data from slam6d. Represents. More... | |
template<typename BaseVecT > | |
ClusterBiMap< FaceHandle > | planarClusterGrowing (const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, float minSinAngle) |
Algorithm which generates plane clusters from the given mesh. More... | |
template<typename T > | |
Transform< T > | poseToMatrix (const Vector3< T > &position, const Vector3< T > &rotation) |
Converts a Pose to a Matrix. More... | |
ModelPtr | readMesh (draco::DecoderBuffer &buffer, draco::Decoder &decoder) |
loads a mesh from the decoderBuffer and converts it into the lvr structure More... | |
ModelPtr | readPointCloud (draco::DecoderBuffer &buffer, draco::Decoder &decoder) |
loads a pointcloud from the decoderBuffer and converts it into the lvr structure More... | |
template<typename BaseVecT > | |
void | removeDanglingCluster (BaseMesh< BaseVecT > &mesh, size_t sizeThreshold) |
template<typename T > | |
static Transform< T > | rieglToSLAM6DTransform (const Transform< T > &in) |
Converts a transformation matrix that is used in riegl coordinate system into a transformation matrix that is used in slam6d coordinate system. More... | |
template<typename ArrayType , typename DataType , int size> | |
int | saveAttributeToDraco (ArrayType array, draco::PointCloud *drcPointcloud, draco::GeometryAttribute::Type geometryType, draco::DataType dracoDataType, size_t numPoints, bool normalized) |
adds the given data to a new attribute and attaches the attribute to the pointcloud More... | |
void | saveHyperspectralCamera (const boost::filesystem::path &root, const HyperspectralCamera &camera, const size_t &positionNumber) |
void | saveHyperspectralCamera (const boost::filesystem::path &root, const HyperspectralCamera &camera, const std::string &positionDirectory) |
void | saveHyperspectralCamera (const boost::filesystem::path &root, const HyperspectralCamera &camera, const std::string positionDirectory, const std::string &cameraDirectory) |
void | saveHyperspectralPanoramaChannel (const boost::filesystem::path &root, const HyperspectralPanoramaChannel &channel, const std::string positionDirectory, const std::string panoramaDirectory, const size_t &channelNumber) |
void | saveMetaInformation (const std::string &outfile, const YAML::Node &node) |
void | saveScan (const boost::filesystem::path &root, const Scan &scan, const size_t &positionNumber, const size_t &scanNumber) |
void | saveScan (const boost::filesystem::path &root, const Scan &scan, const std::string positionDirectory, const std::string scanDirectory, const size_t &scanNumber) |
void | saveScan (const boost::filesystem::path &root, const Scan &scan, const std::string positionName, const std::string scanDirectoryName, const std::string scanName) |
SCAN. More... | |
void | saveScanCamera (const boost::filesystem::path &root, const ScanCamera &image, const size_t &positionNumber, const size_t &cameraNumber) |
void | saveScanCamera (const boost::filesystem::path &root, const ScanCamera &image, const std::string &positionDirectory, const size_t &cameraNumber) |
void | saveScanCamera (const boost::filesystem::path &root, const ScanCamera &image, const std::string positionDirectory, const std::string cameraDirectory) |
SCANCAMERA. More... | |
void | saveScanImage (const boost::filesystem::path &root, const ScanImage &image, const size_t &positionNumber, const size_t &cameraNumber, const size_t &imageNumber) |
SCANIMAGE. More... | |
void | saveScanImage (const boost::filesystem::path &root, const ScanImage &image, const std::string positionDirectory, const size_t &cameraNumber, const size_t &imageNumber) |
void | saveScanImage (const boost::filesystem::path &root, const ScanImage &image, const std::string positionDirectory, const std::string cameraDirectory, const size_t &imageNr) |
void | saveScanPosition (const boost::filesystem::path &root, const ScanPosition &scanPos, const size_t &positionNumber) |
void | saveScanPosition (const boost::filesystem::path &root, const ScanPosition &scanPos, const std::string positionDirectory) |
SCAN_POSITION. More... | |
void | saveScanProject (const boost::filesystem::path &root, const ScanProject &scanProj) |
SCAN_PROJECT. More... | |
void | saveTextures (std::vector< int32_t > *textureValue, textureArr textures, size_t numTextures) |
pushes the given textures in a int32_t vector to store it in the draco structure More... | |
void | saveTextures (std::vector< int32_t > *textureValue, vector< Texture > &textures) |
pushes the given textures in a int32_t vector to store it in the draco structure More... | |
template<typename Iter > | |
Iter | select_randomly (Iter start, Iter end) |
template<typename Iter , typename RandomGenerator > | |
Iter | select_randomly (Iter start, Iter end, RandomGenerator &g) |
template<typename BaseVecT > | |
size_t | simpleMeshReduction (BaseMesh< BaseVecT > &mesh, const size_t count, FaceMap< Normal< typename BaseVecT::CoordType >> &faceNormals) |
Like iterativeEdgeCollapse but with a fixed cost function. More... | |
template<typename BaseVecT > | |
vector< VertexHandle > | simplifyContour (const BaseMesh< BaseVecT > &mesh, const vector< VertexHandle > &contour, float threshold) |
template<typename T > | |
static Rotation< T > | slam6dToLvr (const Rotation< T > &in) |
template<typename T > | |
static Transform< T > | slam6dToLvr (const Transform< T > &in) |
template<typename T > | |
static Vector3< T > | slam6dToLvr (const Vector3< T > &in) |
Slam6D to LVR coordinate change: Point. More... | |
template<typename T > | |
static Vector3< T > | slam6DToRieglPoint (const Vector3< T > &in) |
template<typename T > | |
static Transform< T > | slam6dToRieglTransform (const Transform< T > &in) |
Converts a transformation matrix that is used in slam6d coordinate system into a transformation matrix that is used in riegl coordinate system. More... | |
void | slamToLVRInPlace (PointBufferPtr src) |
Transforms src, which is assumed to be in slam6Ds left-handed coordinate system into our right-handed default coordinate system. The transformation is done in-place, so the original data will be modified. More... | |
template<typename T , typename U > | |
static void | sortByDim (LBPointArray< T > &V, int dim, LBPointArray< U > &indices, LBPointArray< T > &values) |
template<typename T > | |
static void | splitPointArray (LBPointArray< T > &I, LBPointArray< T > &I_L, LBPointArray< T > &I_R) |
template<typename T , typename U > | |
static void | splitPointArrayWithValue (const LBPointArray< T > &V, const LBPointArray< U > &I, LBPointArray< U > &I_L, LBPointArray< U > &I_R, int current_dim, T value, T &deviation_left, T &deviation_right, const unsigned int &orig_dim, const std::list< U > &critical_indices_left, const std::list< U > &critical_indices_right) |
template<typename T , typename U > | |
static void | splitPointArrayWithValueSet (const LBPointArray< T > &V, const LBPointArray< U > &I, LBPointArray< U > &I_L, LBPointArray< U > &I_R, int current_dim, T value, T &deviation_left, T &deviation_right, const unsigned int &orig_dim, const std::unordered_set< U > &critical_indices_left, const std::unordered_set< U > &critical_indices_right) |
int | splitPoints (Vector3f *points, int n, int axis, double splitValue) |
Sorts a Point array so that all Points smaller than splitValue are on the left. More... | |
Transformd | string2mat4f (const std::string data) |
template<typename T > | |
void | subsample (PointBufferPtr src, PointBufferPtr dst, const vector< size_t > &indices) |
template<typename T > | |
Channel< T >::Ptr | subSampleChannel (Channel< T > &src, std::vector< size_t > ids) |
PointBufferPtr | subSamplePointBuffer (PointBufferPtr src, const size_t &n) |
Computes a random sub-sampling of a point buffer by creating a uniform distribution over all point indices with given target size. The sub-sampling is applied to all channels in the source buffer. More... | |
PointBufferPtr | subSamplePointBuffer (PointBufferPtr src, const std::vector< size_t > &indices) |
Computes a reduced version of the source buffer by sampling all channels using the given set of point indices. More... | |
template<typename T > | |
void | swap (T *&arr, size_t i1, size_t i2, size_t n) |
template<class T > | |
boost::shared_ptr< T > | to_boost_ptr (const std::shared_ptr< T > &p) |
template<class T > | |
std::shared_ptr< T > | to_std_ptr (const boost::shared_ptr< T > &p) |
void | tokenize (const string &str, vector< string > &tokens, const string &delimiters=" ") |
template<typename T > | |
void | transformAndReducePointCloud (ModelPtr &model, int modulo, const CoordinateTransform< T > &c) |
Transforms (scale and switch coordinates) and reduces a model containing point cloud data using a modulo filter. Use this function the convert between different coordinate systems. More... | |
template<typename T > | |
void | transformAndReducePointCloud (ModelPtr model, int modulo, const T &sx, const T &sy, const T &sz, const unsigned char &xPos, const unsigned char &yPos, const unsigned char &zPos) |
Transforms (scale and switch coordinates) and reduces a model containing point cloud data using a modulo filter. Use this function the convert between different coordinate systems. More... | |
template<typename T > | |
Transform< T > | transformFrame (const Transform< T > &frame, const CoordinateTransform< T > &ct) |
Transforms the given source frame according to the given coordinate transform struct. More... | |
template<typename T > | |
void | transformPointCloud (ModelPtr model, const Transform< T > &transformation) |
Transforms a model containing a point cloud according to the given transformation (usually from a .frames file) More... | |
void | transformPointCloudAndAppend (PointBufferPtr &buffer, boost::filesystem::path &transfromFile, std::vector< float > &pts, std::vector< float > &nrm) |
Transforms the given point buffer according to the transformation stored in transformFile and appends the transformed points and normals to pts and nrm. More... | |
template<typename T > | |
Transform< T > | transformRegistration (const Transform< T > &transform, const Transform< T > ®istration) |
Transforms a registration matrix according to the given transformation matrix, i.e., applies transform to registration. More... | |
template<typename BaseVecT , typename VisitorF > | |
void | visitLocalVertexNeighborhood (const BaseMesh< BaseVecT > &mesh, VertexHandle vH, double radius, VisitorF visitor) |
Visits every vertex in the local neighborhood of vH . More... | |
vtkStandardNewMacro (LVRPickingInteractor) | |
template<typename BaseVecT , typename VisitorF > | |
void | walkContour (const BaseMesh< BaseVecT > &mesh, EdgeHandle startH, VisitorF visitor) |
Like the other overload, but without ignoring any faces. More... | |
template<typename BaseVecT , typename VisitorF , typename PredF > | |
void | walkContour (const BaseMesh< BaseVecT > &mesh, EdgeHandle startH, VisitorF visitor, PredF exists) |
Walks on a boundary contour starting at startH . More... | |
template<typename BaseVecT > | |
void | writeDebugContourMesh (const BaseMesh< BaseVecT > &mesh, string filename="debug-contours.ply", Rgb8Color connectedColor={0, 255, 0}, Rgb8Color contourColor={0, 0, 255}, Rgb8Color bugColor={255, 0, 0}) |
Writes a mesh to the given filename and colors it with the following meaning: More... | |
template<typename BaseVecT > | |
void | writeDebugMesh (const BaseMesh< BaseVecT > &mesh, string filename="debug.ply", Rgb8Color color={255, 0, 0}) |
Write a mesh to the given filename and color it with the given color. More... | |
template<typename T > | |
void | writeFrame (const Transform< T > &transform, const boost::filesystem::path &framesOut) |
Writes a Eigen transformation into a .frames file. More... | |
size_t | writeModel (ModelPtr model, const boost::filesystem::path &outfile) |
Writes the given model to the given file. More... | |
void | writePointsAndNormals (std::vector< float > &p, std::vector< float > &n, std::string outfile) |
Writes the points and normals (float triples) stored in p and n to the given output file. Attention: The data is converted to a PointBuffer structure to be able to use the IO library, which results in a considerable memory overhead. More... | |
size_t | writePointsToStream (ModelPtr model, std::ofstream &out, bool nocolor=false) |
Writes the points stored in the given model to the fiven output stream. This function is used to apend point cloud data to an already existing ASCII file.. More... | |
void | writePose (const BaseVector< float > &position, const BaseVector< float > &angles, const boost::filesystem::path &out) |
Writes pose information in Euler representation to the given file. More... | |
Variables | |
const static int | box_creation_table [8][3] |
This table states where each coordinate of a box vertex is relative to the box center. More... | |
const static int | box_neighbour_table [8][3] |
const static wchar_t | BrailleTable [] |
const static int | edge_neighbour_table [8][12] |
const static int | edge_vertex_table [8][3] |
const static int | edgeDistanceTable [12][2] |
static const char * | errorString [] |
const static int | ExtendedMCTable [256][13] |
const static int | HGCreateTable [8][3] |
const static int | MCTable [256][13] |
const static int | neighbor_table [12][3] |
const static int | neighbor_vertex_table [12][3] |
const static int | octreeCenterTable [8][3] |
const static int | octreeCornerNeighborTable [64][3] |
const static int | octreeNeighborTable [12][3] |
const static int | octreeNeighborVertexTable [12][3] |
const static int | octreeVertexTable [8][3] |
const static int | shared_vertex_table [8][28] |
A table coding the relations between shared vertices of adjacent positions in the grid created during the marching cubes reconstruction process. More... | |
const static int | TetraederDefinitionTable [6][4] |
const static int | TetraederIntersectionTable [6][6] |
const static int | TetraederNeighborTable [19][3] |
const static int | TetraederTable [16][7] |
const static int | TetraederVertexNBTable [19][3] |
static Timestamp | timestamp |
A global time stamp object for program runtime measurement. More... | |
const static int | TSDFCreateTable [8][3] |
This tables stors adjacency information for the grid creation algorithm. More... | |
const static int | vertex_edge_table [12][2] |
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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.
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkBuilder.hpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkHashGrid.hpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkingPipeline.hpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkManager.hpp
Copyright (c) 2020, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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.
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ColorMap.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. Grid.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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.
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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.
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. BoctreeIO.hpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkIO.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. GridIO.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LasIO.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. IOFactory.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. BilinearFastBox.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. CudaSurface.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. MeshGenerator.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. SharpBox.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. TetraederBox.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. TetraederTable.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. EigenSVDPointAlign.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. EigenSVDPointAlign.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. GraphSLAM.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ICPPointAlign.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. KDTree.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. Metascan.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. Metascan.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. SLAMAlign.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. SLAMOptions.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. SLAMScanWrapper.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. TransformUtils.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. TreeUtils.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. TextureFactory.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. Panic.hpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkBuilder.cpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkHashGrid.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ColorMap.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. Grid.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. MultiPointCloud.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. BoctreeIO.cpp
Copyright (c) 2019, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. ChunkIO.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. IOFactory.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. Metascan.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. MainWindow.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRTreeWidgetHelper.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRTreeWidgetHelper.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRMeshBufferBridge.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRMeshBufferBridge.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRModel.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRModel.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPickingInteractor.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPickingInteractor.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPointBufferBridge.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPointBufferBridge.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRVtkArrow.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRVtkArrow.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRBackgroundDialog.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRItemTypes.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRMeshItem.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRMeshItem.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRModelItem.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRModelItem.h
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPickItem.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPickItem.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPointCloudItem.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPointCloudItem.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPoseItem.cpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRPoseItem.hpp
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 University Osnabrück 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. LVRTransformationDialog.cpp
using lvr2::AllInt = typedef Intersection< intelem::Point, intelem::Distance, intelem::Normal, intelem::Face, intelem::Barycentrics, intelem::Mesh> |
Definition at line 153 of file Intersection.hpp.
using lvr2::AsciiRendererPtr = typedef std::shared_ptr<AsciiRenderer> |
Definition at line 103 of file AsciiRenderer.hpp.
using lvr2::AttributeChannel = typedef Channel<T> |
Definition at line 79 of file Channel.hpp.
using lvr2::BaseVec = typedef BaseVector<float> |
Definition at line 45 of file AttributeMeshIOBase.hpp.
using lvr2::BoundingBoxBridgePtr = typedef boost::shared_ptr<LVRBoundingBoxBridge> |
Definition at line 35 of file LVRBoundingBoxBridge.hpp.
typedef struct lvr2::Cell lvr2::Cell |
using lvr2::ChannelOptional = typedef typename Channel<T>::Optional |
Definition at line 85 of file Channel.hpp.
using lvr2::ChannelPtr = typedef typename Channel<T>::Ptr |
Definition at line 82 of file Channel.hpp.
using lvr2::ChunkBuilderPtr = typedef std::shared_ptr<ChunkBuilder> |
Definition at line 48 of file ChunkBuilder.hpp.
typedef boost::shared_ptr<LVRChunkedMeshBridge> lvr2::ChunkedMeshBridgePtr |
Definition at line 127 of file LVRChunkedMeshBridge.hpp.
using lvr2::ChunkHDF5IO = typedef lvr2::Hdf5IO< lvr2::hdf5features::ArrayIO, lvr2::hdf5features::ChannelIO, lvr2::hdf5features::VariantChannelIO, lvr2::hdf5features::MeshIO> |
Definition at line 52 of file ChunkIO.hpp.
using lvr2::ClusterMap = typedef AttributeMap<ClusterHandle, ValueT> |
Definition at line 91 of file AttrMaps.hpp.
typedef boost::shared_array< color<unsigned char> > lvr2::color3bArr |
Definition at line 141 of file DataStruct.hpp.
typedef boost::shared_array< coord<float> > lvr2::coord3fArr |
Definition at line 144 of file DataStruct.hpp.
typedef ColorVertex<float, unsigned char> lvr2::cVertex |
Definition at line 74 of file CudaSurface.hpp.
using lvr2::DenseAttrMap = typedef VectorMap<HandleT, ValueT> |
Definition at line 85 of file AttrMaps.hpp.
using lvr2::DenseClusterMap = typedef DenseAttrMap<ClusterHandle, ValueT> |
Definition at line 98 of file AttrMaps.hpp.
using lvr2::DenseEdgeMap = typedef DenseAttrMap<EdgeHandle, ValueT> |
Definition at line 99 of file AttrMaps.hpp.
using lvr2::DenseFaceMap = typedef DenseAttrMap<FaceHandle, ValueT> |
Definition at line 100 of file AttrMaps.hpp.
using lvr2::DenseVertexMap = typedef DenseAttrMap<VertexHandle, ValueT> |
Definition at line 101 of file AttrMaps.hpp.
using lvr2::DenseVertexMapOptional = typedef boost::optional<DenseVertexMap<ValueT> > |
Definition at line 113 of file AttrMaps.hpp.
using lvr2::DirectoryIOPtr = typedef std::shared_ptr<DirectoryIO> |
Definition at line 27 of file DirectoryIO.hpp.
using lvr2::DirectoryKernelPtr = typedef std::shared_ptr<DirectoryKernel> |
Definition at line 156 of file DirectoryKernel.hpp.
using lvr2::DirectorySchemaPtr = typedef std::shared_ptr<DirectorySchema> |
Definition at line 93 of file ScanProjectSchema.hpp.
using lvr2::DistInt = typedef Intersection<intelem::Distance> |
Definition at line 145 of file Intersection.hpp.
using lvr2::Distortion = typedef Eigen::Matrix<T, 6, 1> |
Distortion Parameters.
Definition at line 105 of file MatrixTypes.hpp.
using lvr2::Distortiond = typedef Distortion<double> |
Distortion Parameters (double precision)
Definition at line 108 of file MatrixTypes.hpp.
using lvr2::Distortionf = typedef Distortion<float> |
Distortion Parameters (single precision)
Definition at line 111 of file MatrixTypes.hpp.
typedef boost::shared_array<double> lvr2::doubleArr |
Definition at line 134 of file DataStruct.hpp.
using lvr2::DoubleChannel = typedef Channel<double> |
Definition at line 91 of file Channel.hpp.
using lvr2::DoubleChannelOptional = typedef DoubleChannel::Optional |
Definition at line 92 of file Channel.hpp.
using lvr2::DoubleChannelPtr = typedef DoubleChannel::Ptr |
Definition at line 93 of file Channel.hpp.
using lvr2::EdgeMap = typedef AttributeMap<EdgeHandle, ValueT> |
Definition at line 92 of file AttrMaps.hpp.
using lvr2::Extrinsics = typedef Eigen::Matrix<T, 4, 4> |
4x4 extrinsic calibration
Definition at line 85 of file MatrixTypes.hpp.
using lvr2::Extrinsicsd = typedef Extrinsics<double> |
4x4 extrinsic calibration (double precision)
Definition at line 91 of file MatrixTypes.hpp.
using lvr2::Extrinsicsf = typedef Extrinsics<float> |
4x4 extrinsic calibration (single precision)
Definition at line 88 of file MatrixTypes.hpp.
using lvr2::FaceInt = typedef Intersection<intelem::Face, intelem::Barycentrics> |
Definition at line 146 of file Intersection.hpp.
using lvr2::FaceMap = typedef AttributeMap<FaceHandle, ValueT> |
Definition at line 93 of file AttrMaps.hpp.
using lvr2::FeatureBuild = typedef typename FeatureConstruct<Feature>::type |
Definition at line 155 of file FeatureBase.hpp.
using lvr2::FileKernelPtr = typedef std::shared_ptr<FileKernel> |
Definition at line 110 of file FileKernel.hpp.
typedef boost::shared_array< float > lvr2::floatArr |
Definition at line 133 of file DataStruct.hpp.
using lvr2::FloatChannel = typedef Channel<float> |
Definition at line 87 of file Channel.hpp.
using lvr2::FloatChannelOptional = typedef FloatChannel::Optional |
Definition at line 88 of file Channel.hpp.
using lvr2::FloatChannelPtr = typedef FloatChannel::Ptr |
Definition at line 89 of file Channel.hpp.
using lvr2::floatOptional = typedef boost::optional<float> |
Definition at line 41 of file BaseBuffer.hpp.
using lvr2::FloatProxy = typedef ElementProxy<float> |
Definition at line 44 of file BaseBuffer.hpp.
using lvr2::Hdf5Build = typedef typename Hdf5Construct<Feature>::type |
Definition at line 169 of file HDF5FeatureBase.hpp.
using lvr2::HDF5KernelPtr = typedef std::shared_ptr<HDF5Kernel> |
Definition at line 252 of file HDF5Kernel.hpp.
using lvr2::HDF5SchemaPtr = typedef std::shared_ptr<HDF5Schema> |
Definition at line 94 of file ScanProjectSchema.hpp.
typedef struct lvr2::HyperspectralCalibration_ lvr2::HyperspectralCalibration |
using lvr2::HyperspectralCameraModelPtr = typedef std::shared_ptr<HyperspectralCameraModel> |
Definition at line 229 of file ScanTypes.hpp.
using lvr2::HyperspectralCameraPtr = typedef std::shared_ptr<HyperspectralCamera> |
Definition at line 268 of file ScanTypes.hpp.
using lvr2::HyperspectralPanoramaChannelOptional = typedef boost::optional<HyperspectralPanoramaChannel> |
Definition at line 178 of file ScanTypes.hpp.
using lvr2::HyperspectralPanoramaChannelPtr = typedef std::shared_ptr<HyperspectralPanoramaChannel> |
Definition at line 177 of file ScanTypes.hpp.
using lvr2::HyperspectralPanoramaOptional = typedef boost::optional<HyperspectralPanorama> |
Definition at line 196 of file ScanTypes.hpp.
using lvr2::HyperspectralPanoramaPtr = typedef std::shared_ptr<HyperspectralPanorama> |
Definition at line 195 of file ScanTypes.hpp.
typedef boost::shared_array< idxVal<float> > lvr2::idx1fArr |
Definition at line 147 of file DataStruct.hpp.
typedef boost::shared_array< idxVal<unsigned int> > lvr2::idx1uArr |
Definition at line 153 of file DataStruct.hpp.
typedef boost::shared_array< coord<unsigned int> > lvr2::idx3uArr |
Definition at line 150 of file DataStruct.hpp.
using lvr2::Index = typedef uint32_t |
Datatype used as index for each vertex, face and edge.
This index is used within {Edge, Face, Vertex}-Handles. Since those handles are also used within each {Edge, Face, Vertex} reducing the size of this type can greatly decrease memory usage, which in turn might increase performance due to cache locality.
When we assume a basic half-edge structure, we have to deal with the following struct sizes:
Assuming the most common case of float
vectors, this results in the following sizes (in bytes):
Using another approximation of the number of faces, edges and vertices in a triangle-mesh described at 1, we can calculate how much RAM we would need in order to run out of handles. The approximation: for each vertex, we have three edges and two faces. The de-facto cost per vertex can be calculated from that resulting in
Also note that this accounts for the mesh only and ignores all other data that might need to be stored in RAM. So you will need even more RAM.
From this, I think, we can safely conclude: 16 bit handles are way too small; 32 bit handles are probably fine for the next few years, even when working on a medium-sized cluster and 64 bit handles will be fine until after the singularity. And by then, I probably don't care anymore.
Definition at line 96 of file Handles.hpp.
typedef boost::shared_array<unsigned int> lvr2::indexArray |
Definition at line 128 of file DataStruct.hpp.
using lvr2::IndexChannel = typedef Channel<unsigned int> |
Definition at line 99 of file Channel.hpp.
using lvr2::IndexChannelOptional = typedef IndexChannel::Optional |
Definition at line 100 of file Channel.hpp.
using lvr2::IndexChannelPtr = typedef IndexChannel::Ptr |
Definition at line 101 of file Channel.hpp.
typedef std::pair<size_t, size_t> lvr2::indexPair |
Definition at line 162 of file DataStruct.hpp.
using lvr2::IndexProxy = typedef ElementProxy<unsigned int> |
Definition at line 46 of file BaseBuffer.hpp.
typedef boost::shared_array<int> lvr2::intArray |
Definition at line 126 of file DataStruct.hpp.
using lvr2::intOptional = typedef boost::optional<int> |
Definition at line 40 of file BaseBuffer.hpp.
using lvr2::Intrinsics = typedef Eigen::Matrix<T, 3, 3> |
4x4 extrinsic calibration
Definition at line 95 of file MatrixTypes.hpp.
using lvr2::Intrinsicsd = typedef Intrinsics<double> |
4x4 extrinsic calibration (double precision)
Definition at line 101 of file MatrixTypes.hpp.
using lvr2::Intrinsicsf = typedef Intrinsics<float> |
4x4 intrinsic calibration (single precision)
Definition at line 98 of file MatrixTypes.hpp.
using lvr2::KDTreePtr = typedef std::shared_ptr<KDTree> |
Definition at line 135 of file KDTree.hpp.
typedef std::map<std::string, std::vector<unsigned int> > lvr2::labeledFacesMap |
Definition at line 165 of file DataStruct.hpp.
typedef boost::shared_array< RGBMaterial* > lvr2::materialArr |
Definition at line 156 of file DataStruct.hpp.
using lvr2::Matrix3dRM = typedef Matrix3RM<double> |
3x3 row major matrix with double scalars
Definition at line 61 of file MatrixTypes.hpp.
using lvr2::Matrix3fRM = typedef Matrix3RM<float> |
3x3 row major matrix with float scalars
Definition at line 59 of file MatrixTypes.hpp.
using lvr2::Matrix3RM = typedef Eigen::Matrix<T, 3, 3, Eigen::RowMajor> |
General alias for row major 3x3 matrices.
Definition at line 56 of file MatrixTypes.hpp.
using lvr2::Matrix4d = typedef Eigen::Matrix4d |
Eigen 4x4 matrix, double precision.
Definition at line 150 of file MatrixTypes.hpp.
using lvr2::Matrix4dRM = typedef Matrix4RM<double> |
4x4 row major matrix with double scalars
Definition at line 52 of file MatrixTypes.hpp.
using lvr2::Matrix4f = typedef Eigen::Matrix4f |
Eigen 4x4 matrix, single precision.
Definition at line 147 of file MatrixTypes.hpp.
using lvr2::Matrix4fRM = typedef Matrix4RM<float> |
4x4 row major matrix with float scalars
Definition at line 49 of file MatrixTypes.hpp.
using lvr2::Matrix4RM = typedef Eigen::Matrix<T, 4, 4, Eigen::RowMajor> |
General alias for row major 4x4 matrices.
Definition at line 46 of file MatrixTypes.hpp.
using lvr2::Matrix6d = typedef Eigen::Matrix<double, 6, 6> |
6D matrix double precision
Definition at line 159 of file MatrixTypes.hpp.
using lvr2::Matrix6f = typedef Eigen::Matrix<float, 6, 6> |
6D Matrix, single precision
Definition at line 153 of file MatrixTypes.hpp.
typedef boost::shared_ptr<LVRMeshBufferBridge> lvr2::MeshBufferBridgePtr |
Definition at line 106 of file LVRMeshBufferBridge.hpp.
using lvr2::MeshBufferPtr = typedef std::shared_ptr<MeshBuffer> |
Definition at line 217 of file MeshBuffer.hpp.
typedef boost::shared_ptr<LVRModelBridge> lvr2::ModelBridgePtr |
Definition at line 120 of file LVRModelBridge.hpp.
typedef boost::shared_ptr<ModelFactory> lvr2::ModelFactoryPtr |
Definition at line 70 of file ModelFactory.hpp.
using lvr2::ModelPtr = typedef std::shared_ptr<Model> |
using lvr2::MultiChannelMap = typedef VariantChannelMap< char, unsigned char, short, unsigned short, int, unsigned int, float, double > |
Definition at line 59 of file MultiChannelMap.hpp.
using lvr2::NodeOptional = typedef boost::optional<YAML::Node> |
Definition at line 14 of file ScanProjectSchema.hpp.
using lvr2::NormalInt = typedef Intersection<intelem::Normal> |
Definition at line 144 of file Intersection.hpp.
typedef void(* lvr2::PacmanProgressCallbackPtr) (int) |
A class to manage progress information output for process where the number of performed operations is known in advance, e.g. number of loop iterations.
After each iteration the ++-operator should be called. The progress information in '' is automatically printed to stdout together with the given prefix string.
Definition at line 199 of file Progress.hpp.
typedef void(* lvr2::PacmanProgressTitleCallbackPtr) (string) |
Definition at line 200 of file Progress.hpp.
typedef map<PointCloud*, PointCloudAttribute*>::iterator lvr2::pc_attr_it |
Definition at line 60 of file MultiPointCloud.hpp.
typedef map<PointCloud*, PointCloudAttribute*> lvr2::pc_attr_map |
Definition at line 59 of file MultiPointCloud.hpp.
using lvr2::PinholeModeld = typedef PinholeModel<double> |
Definition at line 29 of file CameraModels.hpp.
using lvr2::PinholeModelf = typedef PinholeModel<float> |
Definition at line 30 of file CameraModels.hpp.
using lvr2::PinholeModelPtr = typedef std::shared_ptr<PinholeModel<T> > |
Definition at line 27 of file CameraModels.hpp.
typedef boost::shared_ptr<LVRPointBufferBridge> lvr2::PointBufferBridgePtr |
Definition at line 116 of file LVRPointBufferBridge.hpp.
using lvr2::PointBufferPtr = typedef std::shared_ptr<PointBuffer> |
Definition at line 130 of file PointBuffer.hpp.
using lvr2::PointInt = typedef Intersection<intelem::Point> |
Definition at line 143 of file Intersection.hpp.
using lvr2::PointsetSurfacePtr = typedef std::shared_ptr<PointsetSurface<BaseVecT> > |
Definition at line 161 of file PointsetSurface.hpp.
typedef void(* lvr2::ProgressCallbackPtr) (int) |
A class to manage progress information output for process where the number of performed operations is known in advance, e.g. number of loop iterations.
After each iteration the ++-operator should be called. The progress information in '' is automatically printed to stdout together with the given prefix string.
Definition at line 65 of file Progress.hpp.
typedef void(* lvr2::ProgressTitleCallbackPtr) (string) |
Definition at line 66 of file Progress.hpp.
typedef QueryPoint< Vec > lvr2::QueryPointC |
Definition at line 75 of file CudaSurface.hpp.
using lvr2::RaycasterBasePtr = typedef std::shared_ptr<RaycasterBase<IntT> > |
Definition at line 147 of file RaycasterBase.hpp.
using lvr2::Rgb8Color = typedef std::array<uint8_t, 3> |
Definition at line 54 of file ColorAlgorithms.hpp.
using lvr2::Rotation = typedef Eigen::Matrix<T, 3, 3> |
General 3x3 rotation matrix.
Definition at line 75 of file MatrixTypes.hpp.
using lvr2::Rotationd = typedef Rotation<double> |
Double precision 3x3 rotation matrix.
Definition at line 81 of file MatrixTypes.hpp.
using lvr2::Rotationf = typedef Rotation<float> |
Single precision 3x3 rotation matrix.
Definition at line 78 of file MatrixTypes.hpp.
using lvr2::ScanCameraPtr = typedef std::shared_ptr<ScanCamera> |
Definition at line 153 of file ScanTypes.hpp.
using lvr2::ScanImageOptional = typedef boost::optional<ScanImage> |
Definition at line 128 of file ScanTypes.hpp.
using lvr2::ScanImagePtr = typedef std::shared_ptr<ScanImage> |
Definition at line 127 of file ScanTypes.hpp.
using lvr2::ScanOptional = typedef boost::optional<Scan> |
Definition at line 99 of file ScanTypes.hpp.
using lvr2::ScanPositionPtr = typedef std::shared_ptr<ScanPosition> |
Definition at line 311 of file ScanTypes.hpp.
using lvr2::ScanProjectEditMarkPtr = typedef std::shared_ptr<ScanProjectEditMark> |
Definition at line 357 of file ScanTypes.hpp.
using lvr2::ScanProjectPtr = typedef std::shared_ptr<ScanProject> |
Definition at line 344 of file ScanTypes.hpp.
using lvr2::ScanProjectSchemaPtr = typedef std::shared_ptr<ScanProjectSchema> |
Definition at line 92 of file ScanProjectSchema.hpp.
using lvr2::ScanPtr = typedef std::shared_ptr<Scan> |
Shared pointer to scans.
Definition at line 98 of file ScanTypes.hpp.
using lvr2::SearchTreePtr = typedef std::shared_ptr<SearchTree<BaseVecT> > |
Definition at line 131 of file SearchTree.hpp.
typedef boost::shared_array<short> lvr2::shortArr |
Definition at line 139 of file DataStruct.hpp.
using lvr2::SLAMScanPtr = typedef std::shared_ptr<SLAMScanWrapper> |
Definition at line 221 of file SLAMScanWrapper.hpp.
using lvr2::SparseAttrMap = typedef HashMap<HandleT, ValueT> |
Definition at line 86 of file AttrMaps.hpp.
using lvr2::SparseClusterMap = typedef SparseAttrMap<ClusterHandle, ValueT> |
Definition at line 103 of file AttrMaps.hpp.
using lvr2::SparseEdgeMap = typedef SparseAttrMap<EdgeHandle, ValueT> |
Definition at line 104 of file AttrMaps.hpp.
using lvr2::SparseFaceMap = typedef SparseAttrMap<FaceHandle, ValueT> |
Definition at line 105 of file AttrMaps.hpp.
using lvr2::SparseVertexMap = typedef SparseAttrMap<VertexHandle, ValueT> |
Definition at line 106 of file AttrMaps.hpp.
using lvr2::StringOptional = typedef boost::optional<std::string> |
Definition at line 13 of file ScanProjectSchema.hpp.
typedef boost::shared_array< GlTexture* > lvr2::textureArr |
Definition at line 159 of file DataStruct.hpp.
using lvr2::TinyAttrMap = typedef ListMap<HandleT, ValueT> |
Definition at line 87 of file AttrMaps.hpp.
using lvr2::TinyClusterMap = typedef TinyAttrMap<ClusterHandle, ValueT> |
Definition at line 108 of file AttrMaps.hpp.
using lvr2::TinyEdgeMap = typedef TinyAttrMap<EdgeHandle, ValueT> |
Definition at line 109 of file AttrMaps.hpp.
using lvr2::TinyFaceMap = typedef TinyAttrMap<FaceHandle, ValueT> |
Definition at line 110 of file AttrMaps.hpp.
using lvr2::TinyVertexMap = typedef TinyAttrMap<VertexHandle, ValueT> |
Definition at line 111 of file AttrMaps.hpp.
using lvr2::Transform = typedef Eigen::Matrix<T, 4, 4> |
General 4x4 transformation matrix (4x4)
Definition at line 65 of file MatrixTypes.hpp.
typedef TransformableBase<double> lvr2::Transformable |
Object of types Transformable can be detected at runtime: SomeClass* obj; auto transform_obj = dynamic_cast< Transformable* >(obj); if(transform_obj) { auto T = transform_obj->getTransform(); } else { // obj is not derived from Transformable }
Definition at line 42 of file Transformable.hpp.
using lvr2::Transformd = typedef Transform<double> |
4x4 double precision transformation matrix
Definition at line 71 of file MatrixTypes.hpp.
using lvr2::Transformf = typedef Transform<float> |
4x4 single precision transformation matrix
Definition at line 68 of file MatrixTypes.hpp.
typedef boost::shared_array<unsigned char> lvr2::ucharArr |
Definition at line 137 of file DataStruct.hpp.
using lvr2::UCharChannel = typedef Channel<unsigned char> |
Definition at line 95 of file Channel.hpp.
using lvr2::UCharChannelOptional = typedef UCharChannel::Optional |
Definition at line 96 of file Channel.hpp.
using lvr2::UCharChannelPtr = typedef UCharChannel::Ptr |
Definition at line 97 of file Channel.hpp.
using lvr2::ucharOptional = typedef boost::optional<unsigned char> |
Definition at line 42 of file BaseBuffer.hpp.
using lvr2::UCharProxy = typedef ElementProxy<unsigned char> |
Definition at line 45 of file BaseBuffer.hpp.
using lvr2::uColorVertex = typedef ColorVertex<float, unsigned char> |
Definition at line 163 of file ColorVertex.hpp.
typedef boost::shared_array<unsigned int> lvr2::uintArr |
Definition at line 130 of file DataStruct.hpp.
using lvr2::VariantChannelOptional = typedef boost::optional<VariantChannel<Tp...> > |
Definition at line 145 of file VariantChannel.hpp.
typedef BaseVector< float > lvr2::Vec |
Definition at line 44 of file TexturedMesh.hpp.
using lvr2::Vector2 = typedef Eigen::Matrix<T, 2, 1> |
Eigen 2D vector.
Definition at line 138 of file MatrixTypes.hpp.
using lvr2::Vector2d = typedef Eigen::Vector2d |
Eigen 2D vector, double precision.
Definition at line 144 of file MatrixTypes.hpp.
using lvr2::Vector2f = typedef Eigen::Vector2f |
Eigen 2D vector, single precision.
Definition at line 141 of file MatrixTypes.hpp.
using lvr2::Vector3 = typedef Eigen::Matrix<T, 3, 1> |
Eigen 3D vector.
Definition at line 115 of file MatrixTypes.hpp.
using lvr2::Vector3d = typedef Eigen::Vector3d |
Eigen 3D vector, double precision.
Definition at line 121 of file MatrixTypes.hpp.
using lvr2::Vector3f = typedef Eigen::Vector3f |
Eigen 3D vector, single precision.
Definition at line 118 of file MatrixTypes.hpp.
using lvr2::Vector3i = typedef Eigen::Vector3i |
Eigen 3D vector, integer.
Definition at line 124 of file MatrixTypes.hpp.
using lvr2::Vector4 = typedef Eigen::Matrix<T, 4, 1> |
Eigen 4D vector.
Definition at line 128 of file MatrixTypes.hpp.
using lvr2::Vector4d = typedef Eigen::Vector4d |
Eigen 4D vector, double precision.
Definition at line 134 of file MatrixTypes.hpp.
using lvr2::Vector4f = typedef Eigen::Vector4f |
Eigen 4D vector, single precision.
Definition at line 131 of file MatrixTypes.hpp.
using lvr2::Vector6d = typedef Eigen::Matrix<double, 6, 1> |
6D vector double precision
Definition at line 162 of file MatrixTypes.hpp.
using lvr2::Vector6f = typedef Eigen::Matrix<float, 6, 1> |
6D vector, single precision
Definition at line 156 of file MatrixTypes.hpp.
using lvr2::VecUChar = typedef BaseVector<unsigned char> |
using lvr2::VertexMap = typedef AttributeMap<VertexHandle, ValueT> |
Definition at line 94 of file AttrMaps.hpp.
anonymous enum |
Enumerator | |
---|---|
RenderPoints | |
RenderNormals |
Definition at line 53 of file PointCloud.hpp.
anonymous enum |
Enumerator | |
---|---|
RenderSurfaces | |
RenderTriangles | |
RenderSurfaceNormals | |
RenderVertexNormals | |
RenderColors |
Definition at line 66 of file StaticMesh.hpp.
anonymous enum |
Definition at line 39 of file LVRItemTypes.hpp.
enum lvr2::Color |
enum lvr2::ColorTable |
enum lvr2::COORD_SYSTEM |
Enumerator | |
---|---|
SLAM6D | |
OPENGL_METERS | |
OPENGL_MM |
Definition at line 43 of file CoordinateTransform.hpp.
enum lvr2::fileType |
Enumerator | |
---|---|
XYZ | |
XYZRGB | |
XYZN | |
XYZNRGB |
Definition at line 47 of file LineReader.hpp.
|
strong |
Annotates the use of a Scan when creating an slam6D .frames file.
Enumerator | |
---|---|
INVALID | The Scan has not been registered yet. |
UPDATED | The Scan changed since the last Frame. |
UNUSED | The Scan did not change since the last Frame. |
GRAPHSLAM | |
LOOPCLOSE | The Scan was part of a Loopclose Iteration. |
Definition at line 48 of file SLAMScanWrapper.hpp.
enum lvr2::GradientType |
Identifies a color gradient.
Enumerator | |
---|---|
SOLID | |
GREY | |
HSV | |
JET | |
HOT | |
SHSV | |
SIMPSONS |
Definition at line 54 of file ColorMap.hpp.
|
strong |
Enumerator | |
---|---|
LINE | |
BAR |
Definition at line 38 of file LVRPlotter.hpp.
struct lvr2::__attribute__ | ( | (packed) | ) |
Definition at line 67 of file LineReader.hpp.
|
static |
Definition at line 106 of file cl_helper.h.
void lvr2::AsciiRendererErrorFunc | ( | void * | userPtr, |
enum RTCError | error, | ||
const char * | str | ||
) |
Definition at line 8 of file AsciiRenderer.cpp.
OutMapT< typename decltype(std::declval<IterProxyT>).begin())::HandleType, typename std::result_of<GenF(typename decltype(std::declval<IterProxyT>).begin())::HandleType)>::type> lvr2::attrMapFromFunc | ( | IterProxyT | iterProxy, |
GenF | func | ||
) |
Creates an attribute map by calling the given function for each element in the given iterator. The iterator yields the keys, the function gives us the corresponding value.
Transform<T> lvr2::buildTransformation | ( | T * | alignxf | ) |
Transforms an slam6d transformation matrix into an Eigen 4x4 matrix.
DenseVertexMap<float> lvr2::calcAverageVertexAngles | ( | const BaseMesh< BaseVecT > & | mesh, |
const VertexMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Calculates the average angle for each vertex.
mesh | The given mesh for the calculation. |
normals | The vertex normals of the given mesh. The normals are necessary in this function for delegating them to the submethods. |
Rgb8Color lvr2::calcColorForFaceCentroid | ( | const BaseMesh< BaseVecT > & | mesh, |
const PointsetSurface< BaseVecT > & | surface, | ||
FaceHandle | faceH | ||
) |
Calculate the color for the centroid of a given face.
For a given mesh and it's surface the color of the faces centroid is calculated. The face is identified by the given face handle.
mesh | The mesh |
surface | The surface of the mesh |
faceH | Face handle of the face |
boost::optional<DenseVertexMap<Rgb8Color> > lvr2::calcColorFromPointCloud | ( | const BaseMesh< BaseVecT > & | mesh, |
const PointsetSurfacePtr< BaseVecT > | surface | ||
) |
Calculates the color of each vertex from the point cloud.
For each vertex, its color is calculated from the rgb color information in the meshes surface.
mesh | The mesh |
surface | The surface of the mesh |
void lvr2::calcContourEdges | ( | const BaseMesh< BaseVecT > & | mesh, |
EdgeHandle | startH, | ||
std::vector< EdgeHandle > & | contourOut | ||
) |
Walks on a boundary contour starting at startH
and adds all visited edges to the given out vector.
Uses walkContour()
. See that function for detailed information.
void lvr2::calcContourEdges | ( | const BaseMesh< BaseVecT > & | mesh, |
EdgeHandle | startH, | ||
std::vector< EdgeHandle > & | contourOut, | ||
PredF | exists | ||
) |
Walks on a boundary contour starting at startH
and adds all visited edges to the given out vector.
Uses walkContour()
. See that function for detailed information.
void lvr2::calcContourVertices | ( | const BaseMesh< BaseVecT > & | mesh, |
EdgeHandle | startH, | ||
std::vector< VertexHandle > & | contourOut | ||
) |
Walks on a boundary contour starting at startH
and adds all visited vertices to the given out vector.
Uses walkContour()
. See that function for detailed information.
void lvr2::calcContourVertices | ( | const BaseMesh< BaseVecT > & | mesh, |
EdgeHandle | startH, | ||
std::vector< VertexHandle > & | contourOut, | ||
PredF | exists | ||
) |
Walks on a boundary contour starting at startH
and adds all visited vertices to the given out vector.
Uses walkContour()
. See that function for detailed information.
DenseFaceMap<Normal<typename BaseVecT::CoordType> > lvr2::calcFaceNormals | ( | const BaseMesh< BaseVecT > & | mesh | ) |
Calculates a normal for each face in the mesh.
A face's normal is calculated based on the position of its three vertices. If a face has zero area, the normal cannot be calculated correctly. In this case, a dummy normal (0, 0, 1) is inserted.
void lvr2::calcLocalVertexNeighborhood | ( | const BaseMesh< BaseVecT > & | mesh, |
VertexHandle | vH, | ||
double | radius, | ||
vector< VertexHandle > & | neighborsOut | ||
) |
Calculates the local neighborhood of a given vertex (defined by it's handle).
A local neighborhood for a vertex is constrained by a circular-shaped radius. The neighbors of a vertex do have to be connected by vertices and edges, which stay within this border. If one edge leaves the neighborhood radius, every further on connected vertex and edge isn't part of the local neighborhood, even if the topological "edge->vertex->edge->vertex->..."-chain, which left the radius once, reenters the radius.
mesh | The given BaseMesh for performing the neighborhood-search. |
vH | The given VertexHandle to which we want to get the local heighborhood. |
radius | The radius which defines the border of the local neighborhood. |
neighborsOut | The found neighbors, stored in a vector. |
Plane<BaseVecT> lvr2::calcRegressionPlane | ( | const BaseMesh< BaseVecT > & | mesh, |
const Cluster< FaceHandle > & | cluster, | ||
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Calcs a regression plane for the given cluster.
Plane<BaseVecT> lvr2::calcRegressionPlanePCA | ( | const BaseMesh< BaseVecT > & | mesh, |
const Cluster< FaceHandle > & | cluster, | ||
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
const int | num_iterations = 100 , |
||
const int | num_samples = 10 |
||
) |
Calcs a regression plane for the given cluster.
Plane<BaseVecT> lvr2::calcRegressionPlaneRANSAC | ( | const BaseMesh< BaseVecT > & | mesh, |
const Cluster< FaceHandle > & | cluster, | ||
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
const int | num_iterations = 100 , |
||
const int | num_samples = 10 |
||
) |
Calcs a regression plane for the given cluster.
DenseClusterMap<Plane<BaseVecT> > lvr2::calcRegressionPlanes | ( | const BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
int | minClusterSize | ||
) |
Calcs regression planes for all cluster in clusters.
minClusterSize | minimum size for clusters (number of faces) for which a regression plane should be generated |
DenseClusterMap<Plane<BaseVecT> > lvr2::calcRegressionPlanesRANSAC | ( | const BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
int | minClusterSize, | ||
int | iterations = 100 , |
||
int | samples = 10 |
||
) |
Calcs regression planes for all cluster in clusters.
minClusterSize | minimum size for clusters (number of faces) for which a regression plane should be generated |
BoundingRectangle<typename BaseVecT::CoordType> lvr2::calculateBoundingRectangle | ( | const vector< VertexHandle > & | contour, |
const BaseMesh< BaseVecT > & | mesh, | ||
const Cluster< FaceHandle > & | cluster, | ||
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
float | texelSize, | ||
ClusterHandle | clusterH | ||
) |
Calculates bounding rectangle for a given cluster.
Calculates a bounding rectangle for a given cluster. To do so, first a regression plane for the cluster must be calculated. It is assumed that the cluster is mostly planar for this to work. With the regression plane the algorithm creates an initial bounding rectangle that encloses all of the clusters vertices. Then, iterative improvement steps rotate the bounding rectangle and calculate the predicted number of texels for a bounding box of this size. The rotation with the least amount of texels will be used.
contour | contour of cluster |
mesh | mesh |
cluster | cluster |
normals | normals |
texelSize | texelSize |
clusterH | cluster handle (TODO: is not used! remove) |
vector<VertexHandle> lvr2::calculateClusterContourVertices | ( | ClusterHandle | clusterH, |
const BaseMesh< BaseVecT > & | mesh, | ||
const ClusterBiMap< FaceHandle > & | clusterBiMap | ||
) |
Calculates contour vertices for a given cluster.
Calculates the contour vertices for a given cluster. To do so, the algorithm will inspect each edge and find edges that only have one adjacent face as part of the given cluster. These edges are contour edges, so each unique vertex of such an edge will be added to the list of results.
clusterH | cluster handle for given cluster |
mesh | the mesh |
clusterBiMap | map of clusters for given mesh |
DenseEdgeMap<float> lvr2::calcVertexAngleEdges | ( | const BaseMesh< BaseVecT > & | mesh, |
const VertexMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Calculates the angle between two vertex normals for each edge.
mesh | The given mesh for the calculation. |
normals | The vertex normals of the given mesh. The normals are necessary in this function for delegating them to the submethods. |
DenseEdgeMap<float> lvr2::calcVertexDistances | ( | const BaseMesh< BaseVecT > & | mesh | ) |
Computes the distances between the vertices and stores them in the given dense edge map.
mesh | The mesh containing the vertices and edges of interest |
DenseVertexMap<float> lvr2::calcVertexHeightDifferences | ( | const BaseMesh< BaseVecT > & | mesh, |
double | radius | ||
) |
Calculate the height difference value for each vertex of the given BaseMesh.
mesh | The given BaseMesh for calculating vertex height differences. |
radius | The radius which defines the border of the local neighborhood. |
DenseVertexMap<Normal<typename BaseVecT::CoordType> > lvr2::calcVertexNormals | ( | const BaseMesh< BaseVecT > & | mesh, |
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Calculates a normal for each vertex in the mesh.
The normal is calculated by first attempting to interpolate from the adjacent faces. If a vertex doesn't have adjacent faces, the default normal (0, 0, 1) is used.
surface | A point cloud with normal information |
DenseVertexMap<Normal<typename BaseVecT::CoordType> > lvr2::calcVertexNormals | ( | const BaseMesh< BaseVecT > & | mesh, |
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
const PointsetSurface< BaseVecT > & | surface | ||
) |
Calculates a normal for each vertex in the mesh.
The normal is calculated by first attempting to interpolate from the adjacent faces. If a vertex doesn't have adjacent faces, the normal from the nearest point in the point cloud is used.
surface | A point cloud with normal information |
DenseVertexMap<float> lvr2::calcVertexRoughness | ( | const BaseMesh< BaseVecT > & | mesh, |
double | radius, | ||
const VertexMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Calculates the roughness for each vertex.
For the calculation of the roughness we sum up the average angles of neighbored vertices and divide that by the size of the neighborhood.
mesh | The given mesh for the calculation. |
radius | The radius which defines the local neighborhood. A local neighborhood is defined by a circular-shaped radius, which includes all connected edges and vertices. Once an edge leaves this radius and reenters somehow it isn't part of the neighborhood. |
normals | The vertex normals of the given mesh as a map. The normals are necessary in this function for delegating them to the submethods. |
void lvr2::calcVertexRoughnessAndHeightDifferences | ( | const BaseMesh< BaseVecT > & | mesh, |
double | radius, | ||
const VertexMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
DenseVertexMap< float > & | roughness, | ||
DenseVertexMap< float > & | heightDiff | ||
) |
Calculates the roughness and the height difference for each vertex.
This function combines the logic of the calcVertexRoughness- and calcVertexHeightDiff-functions, allowing us to calculate the local neighborhood for each single vertex just once. By that, this function should always be used when the roughness and height difference values are both needed.
mesh | The given mesh for the calculation. |
radius | The radius which defines the local neighborhood. A local neighborhood is defined by a circular-shaped radius, which includes all connected edges and vertices. Once an edge leaves this radius and reenters somehow, it isn't part of the neighborhood. |
normals | The vertex normals of the given mesh. |
roughness | The calculated roughness values for each vertex. |
heightDiff | The calculated height difference values for each vertex. |
|
static |
|
static |
|
static |
void lvr2::cleanContours | ( | BaseMesh< BaseVecT > & | mesh, |
int | iterations, | ||
float | areaThreshold | ||
) |
Removes faces with a high number of boundary edges.
Faces which have 2 or 3 adjacent boundary edges, are removed. If the face is adjacent to only one boundary edge, it is deleted if the face's area is smaller than areaThreshold
.
ClusterBiMap<FaceHandle> lvr2::clusterGrowing | ( | const BaseMesh< BaseVecT > & | mesh, |
Pred | pred | ||
) |
Algorithm which generates clusters from the given mesh. The given predicate decides which faces will be in the same clusters.
Pred | a predicate which decides, which faces will be in the same cluster. It gets the following parameters: (FaceHandle referenceFaceH, FaceHandle currentFaceH) and returs a bool. The referenceFaceH is the first FaceHandle, which was added to the current cluster. currentFaceH is the current FaceHandle for which the predicate has to decide, whether it should be added to the current cluster or not. The decision is done by returing true = add currentFaceH to cluster or false = don't add currentFaceH to cluster. |
Definition at line 98 of file LVRPointBufferBridge.cpp.
void lvr2::convert | ( | COORD_SYSTEM | from, |
COORD_SYSTEM | to, | ||
float * | point | ||
) |
Definition at line 46 of file CoordinateTransform.cpp.
void lvr2::convert | ( | COORD_SYSTEM | from, |
COORD_SYSTEM | to, | ||
PointBufferPtr & | buffer | ||
) |
Definition at line 71 of file CoordinateTransform.cpp.
|
static |
|
static |
size_t lvr2::countPointsInFile | ( | const boost::filesystem::path & | inFile | ) |
Counts the number of points (i.e. number of lines) in the given file.
inFile | An ASCII file containing point cloud data (one point per line) |
Definition at line 132 of file IOUtils.cpp.
KDTreePtr lvr2::create_recursive | ( | KDTree::Point * | points, |
int | n, | ||
int | maxLeafSize | ||
) |
Definition at line 109 of file KDTree.cpp.
void lvr2::createOctree | ( | Vector3f * | points, |
int | n, | ||
bool * | flagged, | ||
const Vector3f & | min, | ||
const Vector3f & | max, | ||
int | level, | ||
double | voxelSize, | ||
int | maxLeafSize | ||
) |
Definition at line 70 of file TreeUtils.cpp.
void lvr2::createTextures | ( | std::vector< int32_t > & | drcTextures, |
std::vector< GlTexture * > & | lvrTextures | ||
) |
transforms the int32_t vector with texture data into actual GlTextures
drcTextures | the int32_t vector holding the image data |
lvrTextures | a GlTexture vector with the created textures |
Definition at line 82 of file DracoDecoder.cpp.
void lvr2::createTextures | ( | std::vector< int32_t > & | drcTextures, |
std::vector< Texture > & | lvrTextures | ||
) |
transforms the int32_t vector with texture data into actual GlTextures
drcTextures | the int32_t vector holding the image data |
lvrTextures | a GlTexture vector with the created textures |
Definition at line 116 of file DracoDecoder.cpp.
void lvr2::debugPlanes | ( | const BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
const ClusterMap< Plane< BaseVecT >> & | planes, | ||
string | filename, | ||
size_t | minClusterSize | ||
) |
Creates a mesh containing the given regression planes (which match the given minimum cluster size) as planes and saves it to a file with the given filename.
filename | name for the file where the mesh containing the planes will be stored in |
minClusterSize | minimum size of clusters for which the planes will be added to the mesh |
ModelPtr lvr2::decodeDraco | ( | draco::DecoderBuffer & | buffer, |
draco::EncodedGeometryType | type | ||
) |
delivers ModelPtr from draco DecoderBuffer
buffer | Decoder Buffer thats contents get parsed to a Model |
type | GeometryType of loaded structure |
Definition at line 441 of file DracoDecoder.cpp.
void lvr2::deleteSmallPlanarCluster | ( | BaseMesh< BaseVecT > & | mesh, |
ClusterBiMap< FaceHandle > & | clusters, | ||
size_t | smallClusterThreshold | ||
) |
Removes all clusters and their cotained faces from the given mesh which are smaller than the given smallClusterThreshold.
bool lvr2::Dijkstra | ( | const BaseMesh< BaseVecT > & | mesh, |
const VertexHandle & | start, | ||
const VertexHandle & | goal, | ||
const DenseEdgeMap< float > & | edgeCosts, | ||
std::list< VertexHandle > & | path, | ||
DenseVertexMap< float > & | distances, | ||
DenseVertexMap< VertexHandle > & | predecessors, | ||
DenseVertexMap< bool > & | seen, | ||
DenseVertexMap< float > & | vertex_costs | ||
) |
Dijkstra's algorithm.
mesh | The mesh containing the vertices and edges of interest |
start | Start vertex |
goal | Goal vertex |
path | Resulted path from search |
void lvr2::dragOntoIntersection | ( | BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
const ClusterHandle & | clusterH, | ||
const ClusterHandle & | neighbourClusterH, | ||
const Line< BaseVecT > & | intersection | ||
) |
Drags all points between two clusters (planes) into their intersection.
void lvr2::dragToRegressionPlane | ( | BaseMesh< BaseVecT > & | mesh, |
const Cluster< FaceHandle > & | cluster, | ||
const Plane< BaseVecT > & | plane, | ||
FaceMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Drags all points from the given cluster into the given plane.
void lvr2::dragToRegressionPlanes | ( | BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
const ClusterMap< Plane< BaseVecT >> & | planes, | ||
FaceMap< Normal< typename BaseVecT::CoordType >> & | normals | ||
) |
Drags all points from the given clusters into their regression planes.
void lvr2::eigenToEuler | ( | Transform< T > & | mat, |
T * | pose | ||
) |
Definition at line 630 of file TransformUtils.hpp.
void lvr2::EmbreeErrorFunction | ( | void * | userPtr, |
enum RTCError | error, | ||
const char * | str | ||
) |
Definition at line 9 of file EmbreeRaycaster.cpp.
std::unique_ptr< draco::EncoderBuffer > lvr2::encodeDraco | ( | ModelPtr | modelPtr, |
draco::EncodedGeometryType | type | ||
) |
encodes Model to draco EncodeBuffer which contents can be written into a file
modelptr | modelPtr to Model that shall be encoded |
type | GeometryType of Geometry to be encoded |
Definition at line 655 of file DracoEncoder.cpp.
std::unique_ptr<draco::EncoderBuffer> lvr2::encodeMesh | ( | ModelPtr | modelPtr, |
draco::Encoder & | encoder | ||
) |
transfers a mesh of a modelPtr to a draco EncoderBuffer that can be written into a file
modelPtr | pointer to model thats mesh shall be encoded |
encoder | is used to encode the modelptr to a encodeBuffer |
Definition at line 280 of file DracoEncoder.cpp.
std::unique_ptr<draco::EncoderBuffer> lvr2::encodePointCloud | ( | ModelPtr | modelPtr, |
draco::Encoder & | encoder | ||
) |
transfers a pointcloud of a modelPtr to a draco EncoderBuffer that can be written into a file
modelPtr | pointer to model thats pointcloud shall be encoded |
encoder | is used to encode the modelptr to a encodeBuffer |
TODO: Change to channel
TODO: Change to channel
Definition at line 161 of file DracoEncoder.cpp.
|
inline |
Conversion from Pose to Matrix representation.
Conversion from Pose to Matrix representation in GraphSLAMs internally consistent Coordinate System
Definition at line 486 of file GraphSLAM.cpp.
void lvr2::extrinsicsToEuler | ( | Extrinsics< T > | mat, |
T * | pose | ||
) |
Definition at line 587 of file TransformUtils.hpp.
|
static |
|
static |
bool lvr2::findCloseScans | ( | const std::vector< SLAMScanPtr > & | scans, |
size_t | scan, | ||
const SLAMOptions & | options, | ||
std::vector< size_t > & | output | ||
) |
finds Scans that are "close" to a Scan as determined by a Loopclosing strategy
scans | A vector with all Scans |
scan | The index of the scan |
options | The options on how to search |
output | Will be filled with the indices of all close Scans |
bool lvr2::findCloseScans | ( | const vector< SLAMScanPtr > & | scans, |
size_t | scan, | ||
const SLAMOptions & | options, | ||
vector< size_t > & | output | ||
) |
Lists all numbers of scans near to the scan.
scans | reference to a vector containing the SlamScanPtr |
scan | number of the current scan |
options | SlamOptions struct with all params |
output | Returns vector of the scan-numbers which ar defined as "close" |
Definition at line 53 of file GraphSLAM.cpp.
vector<vector<VertexHandle> > lvr2::findContours | ( | BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
ClusterHandle | clusterH | ||
) |
Finds all contours of an given cluster. An contour can be an "real" boundary, so nothing is adjacent, or an boundary to another edge.
mesh | the mesh to operate on |
clusters | map of all clusters |
clusterH | the current cluster |
|
static |
Convert a given float to an 8-bit Grayscale-Color.
The given float, which we want to convert to an 8-bit GrayScale-Color, has to be in [0, 1]. If it is bigger than 1 it's value is set to 1. If it is smaller than 0 it's value is set to 0.
value | The float value, which will be converted to a Grayscale-Color. |
|
static |
Convert a given float to an 8-bit RGB-Color, using the rainbowcolor scale.
The given float, which we want to convert to an 8-bit RGB-Color, has to be in [0, 1]. If it is bigger than 1 it's value is set to 1. If it is smaller than 0 it's value is set to 0.
value | The float value, which will be converted to an RGB-Rainbowcolor. |
|
static |
|
static |
|
static |
std::string lvr2::get_first_group_regex | ( | std::regex | regex_string, |
std::string | data | ||
) |
Definition at line 61 of file RieglProject.cpp.
const draco::PointAttribute* lvr2::getDracoAttributeByAttributeMetadata | ( | draco::PointCloud * | geometry, |
std::string | key, | ||
std::string | value | ||
) |
delivers PointAttribute by searching for given Attribute Metadata Entries
geometry | pointcloud that contains the attribute and its metadata |
key | String key of key value pair to be searched for |
value | String value of key value pair to be searched for |
Definition at line 153 of file DracoDecoder.cpp.
vector<vector<VertexHandle> > lvr2::getDuplicateVertices | ( | const BaseMesh< BaseVecT > & | mesh | ) |
Returns all handles of duplicate vertices from the given mesh.
The equality of two points is check via Point::operator==().
boost::optional<Normal<typename BaseVecT::CoordType> > lvr2::getFaceNormal | ( | array< BaseVecT, 3 > | vertices | ) |
Returns the normal of a face with the given three vertices.
vertices | The face's vertex-positions in counter-clockwise order. |
none
if the face has a zero area. boost::filesystem::path lvr2::getHyperspectralCameraDirectory | ( | boost::filesystem::path | root, |
const std::string | positionDirectory, | ||
const std::string | cameraDirectory | ||
) |
HYPERSPECTRAL_CAMERA.
Definition at line 714 of file ScanIOUtils.cpp.
std::pair< std::string, std::string > lvr2::getNames | ( | const std::string & | defaultGroup, |
const std::string & | defaultContainer, | ||
const Description & | d | ||
) |
Definition at line 6 of file ScanProjectSchema.cpp.
size_t lvr2::getNumberOfPointsInPLY | ( | const std::string & | filename | ) |
Get the Number Of Points (element points if present, vertex count otherwise) in a PLY file.
filename | A valid PLY file. |
Definition at line 295 of file IOUtils.cpp.
boost::filesystem::path lvr2::getPanoramaChannelDirectory | ( | boost::filesystem::path | root, |
const std::string | positionDirectory, | ||
const std::string | panoramaDirectory | ||
) |
HYPERSPECTRAL_PANORAMA_CHANNEL.
Definition at line 571 of file ScanIOUtils.cpp.
void lvr2::getPoseFromFile | ( | BaseVector< float > & | position, |
BaseVector< float > & | angles, | ||
const boost::filesystem::path | file | ||
) |
Loads an Euler representation of from a pose file.
position | Will contain the postion |
angles | Will contain the rotation angles in degrees |
file | The pose file |
Definition at line 285 of file IOUtils.cpp.
void lvr2::getPoseFromMatrix | ( | BaseVector< T > & | position, |
BaseVector< T > & | angles, | ||
const Transform< T > & | mat | ||
) |
Computes a Euler representation from the given transformation matrix.
position | Will contain the position |
angles | Will contain the rotation angles in radians |
mat | The transformation matrix |
size_t lvr2::getReductionFactor | ( | boost::filesystem::path & | inFile, |
size_t | targetSize | ||
) |
Computes the reduction factor for a given target size (number of points) when reducing a point cloud loaded from an ASCII file using a modulo filter.
inFile | An ASCII file containing point cloud data |
targetSize | The desired number of points in the reduced model |
Definition at line 228 of file IOUtils.cpp.
size_t lvr2::getReductionFactor | ( | ModelPtr | model, |
size_t | targetSize | ||
) |
Computes the reduction factor for a given target size (number of points) when reducing a point cloud using a modulo filter.
model | A model containing point cloud data |
targetSize | The desired number of points in the reduced model |
Definition at line 202 of file IOUtils.cpp.
boost::filesystem::path lvr2::getScanCameraDirectory | ( | boost::filesystem::path | root, |
const std::string | positionDirectory, | ||
const std::string | cameraDirectory | ||
) |
SCANCAMERA.
Definition at line 243 of file ScanIOUtils.cpp.
boost::filesystem::path lvr2::getScanImageDirectory | ( | boost::filesystem::path | root, |
const std::string | positionDirectory, | ||
const std::string | cameraDirectory | ||
) |
Definition at line 67 of file ScanIOUtils.cpp.
SearchTreePtr<BaseVecT> lvr2::getSearchTree | ( | string | name, |
PointBufferPtr | buffer | ||
) |
Returns the search tree implementation specified by name
.
If name
doesn't contain a valid implementation, nullptr
is returned. Currently, the only supported implementation is "flann".
std::string lvr2::getSensorType | ( | const boost::filesystem::path & | dir | ) |
Gets the sensor type for a given directory. Return an empty string if the directory does not contain a meta.yaml file with 'sensor_type' element.
dir | Directory to check for sensor data |
Definition at line 19 of file ScanIOUtils.cpp.
Transform<T> lvr2::getTransformationFromDat | ( | const boost::filesystem::path & | frames | ) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given dat file.
Transform<T> lvr2::getTransformationFromFile | ( | const boost::filesystem::path & | file | ) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given file.
Transform<T> lvr2::getTransformationFromFrames | ( | const boost::filesystem::path & | frames | ) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given frame file.
Transform<T> lvr2::getTransformationFromPose | ( | const boost::filesystem::path & | pose | ) |
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given pose file.
|
static |
Definition at line 61 of file CudaSurface.hpp.
boost::optional<Normal<typename BaseVecT::CoordType> > lvr2::interpolatedVertexNormal | ( | const BaseMesh< BaseVecT > & | mesh, |
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
VertexHandle | handle | ||
) |
Returns a vertex normal for the given vertex interpolated from the normals of its adjacent faces.
Computes the inverse transformation from the given transformation matrix, which means if transform encodes the transformation A->B, the return will transform from B to A.
transform | A transformation matrix |
bool lvr2::isSelfOrChildSelected | ( | QTreeWidgetItem * | item | ) |
Definition at line 749 of file LVRMainWindow.cpp.
size_t lvr2::iterativeEdgeCollapse | ( | BaseMesh< BaseVecT > & | mesh, |
const size_t | count, | ||
FaceMap< Normal< typename BaseVecT::CoordType >> & | faceNormals, | ||
CostF | collapseCost | ||
) |
Collapses count
many edges of mesh
for which collapseCost
returns the smallest values.
This algorithm collapses edges in the given mesh. The order of edge collapses is determined by collapseCost
: the edge with the smallest cost is collapsed first, if that is possible. In case the edge is not collapsable, it is ignored and the next edge is choosen. After each collapse, the cost function is called again to update the costs for all edges that could have been affected, which are the edges of all faces which touch the vertex the edge was collapsed to.
This algorithm stops when either count
many edges have been collapsed or if there are no collapsable edges left.
[in] | count | Number of edges to collapse |
[in,out] | faceNormals | A face map storing valid normals of all faces in the mesh. This map is altered by this algorithm according to the changes done in the mesh. |
[in] | collapseCost | Function which is called with an edge handle and a FaceMap containing normals; it is expected to return an optional float. boost::none means that this edge cannot be collapsed. |
ClusterBiMap<FaceHandle> lvr2::iterativePlanarClusterGrowing | ( | BaseMesh< BaseVecT > & | mesh, |
FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
float | minSinAngle, | ||
int | numIterations, | ||
int | minClusterSize | ||
) |
Algorithm which generates planar clusters from the given mesh, drags points in clusters into regression planes and improves clusters iteratively.
mesh | |
minSinAngle | 1 - minSinAngle is the allowed difference between the sin of the angle of the starting face and all other faces in one cluster. |
numIterations | for cluster improvement |
minClusterSize | minimum size for clusters (number of faces) for which a regression plane should be generated |
ClusterBiMap<FaceHandle> lvr2::iterativePlanarClusterGrowingRANSAC | ( | BaseMesh< BaseVecT > & | mesh, |
FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
float | minSinAngle, | ||
int | numIterations, | ||
int | minClusterSize, | ||
int | ransacIterations = 100 , |
||
int | ransacSamples = 10 |
||
) |
Algorithm which generates planar clusters from the given mesh, drags points in clusters into regression planes and improves clusters iteratively.
mesh | |
minSinAngle | 1 - minSinAngle is the allowed difference between the sin of the angle of the starting face and all other faces in one cluster. |
numIterations | for cluster improvement |
minClusterSize | minimum size for clusters (number of faces) for which a regression plane should be generated |
LvrArrType lvr2::loadAttributeFromDraco | ( | const draco::PointAttribute * | attribute | ) |
loads any GeometryAttribute from draco pointcloud and returns its values
LvrArrType | Array type in Lvr (something like floatArr, or uintArr) |
DataType | Type of data that gets stored in the array that gets returned |
numComponents | num of the components of the dtaco attribute that gets loaded |
attribute | Pointer to PointAttribute which is used to load data into lvr structure |
Definition at line 49 of file DracoDecoder.cpp.
Transform<T> lvr2::loadFromFile | ( | const boost::filesystem::path & | file | ) |
Reads an Eigen 4x4 matrix from the given file (16 coefficients, row major)
T | Scalar type of the created Eigen matrix |
file | A file with serialized matrix data |
bool lvr2::loadHyperspectralCamera | ( | const boost::filesystem::path & | root, |
HyperspectralCamera & | camera, | ||
const size_t & | positionNumber | ||
) |
Definition at line 873 of file ScanIOUtils.cpp.
bool lvr2::loadHyperspectralCamera | ( | const boost::filesystem::path & | root, |
HyperspectralCamera & | camera, | ||
const std::string & | positionDirectory | ||
) |
Definition at line 865 of file ScanIOUtils.cpp.
bool lvr2::loadHyperspectralCamera | ( | const boost::filesystem::path & | root, |
HyperspectralCamera & | camera, | ||
const std::string & | positionDirectory, | ||
const std::string & | cameraDirectory | ||
) |
Definition at line 805 of file ScanIOUtils.cpp.
void lvr2::loadHyperspectralPanoramaChannels | ( | std::vector< HyperspectralPanoramaChannelPtr > & | channels, |
boost::filesystem::path | dataPath | ||
) |
Definition at line 657 of file ScanIOUtils.cpp.
YAML::Node lvr2::loadMetaInformation | ( | const std::string & | in | ) |
Definition at line 54 of file MetaFormatFactory.cpp.
bool lvr2::loadScan | ( | const boost::filesystem::path & | root, |
Scan & | scan, | ||
const size_t & | positionNumber, | ||
const size_t & | scanNumber | ||
) |
Definition at line 550 of file ScanIOUtils.cpp.
bool lvr2::loadScan | ( | const boost::filesystem::path & | root, |
Scan & | scan, | ||
const std::string & | positionDirectory, | ||
const size_t & | scanNumber | ||
) |
Definition at line 538 of file ScanIOUtils.cpp.
bool lvr2::loadScan | ( | const boost::filesystem::path & | root, |
Scan & | scan, | ||
const std::string & | positionDirectory, | ||
const std::string & | scanDirectory, | ||
const size_t & | scanNumber | ||
) |
bool lvr2::loadScan | ( | const boost::filesystem::path & | root, |
Scan & | scan, | ||
const std::string & | positionDirectory, | ||
const std::string & | scanDirectory, | ||
const std::string & | scanName | ||
) |
Definition at line 487 of file ScanIOUtils.cpp.
bool lvr2::loadScanCamera | ( | const boost::filesystem::path & | root, |
ScanCamera & | image, | ||
const size_t & | positionNumber, | ||
const size_t & | cameraNumber | ||
) |
Definition at line 331 of file ScanIOUtils.cpp.
bool lvr2::loadScanCamera | ( | const boost::filesystem::path & | root, |
ScanCamera & | image, | ||
const std::string & | positionDirectory, | ||
const size_t & | cameraNumber | ||
) |
Definition at line 319 of file ScanIOUtils.cpp.
bool lvr2::loadScanCamera | ( | const boost::filesystem::path & | root, |
ScanCamera & | image, | ||
const std::string & | positionDirectory, | ||
const std::string & | cameraDirectory | ||
) |
Definition at line 346 of file ScanIOUtils.cpp.
bool lvr2::loadScanImage | ( | const boost::filesystem::path & | root, |
ScanImage & | image, | ||
const size_t & | positionNumber, | ||
const size_t & | cameraNumber, | ||
const size_t & | imageNumber | ||
) |
Definition at line 125 of file ScanIOUtils.cpp.
bool lvr2::loadScanImage | ( | const boost::filesystem::path & | root, |
ScanImage & | image, | ||
const std::string & | positionDirectory, | ||
const size_t & | cameraNumber, | ||
const size_t & | imageNumber | ||
) |
Definition at line 141 of file ScanIOUtils.cpp.
bool lvr2::loadScanImage | ( | const boost::filesystem::path & | root, |
ScanImage & | image, | ||
const std::string & | positionDirectory, | ||
const std::string & | cameraDirectory, | ||
const size_t & | imageNumber | ||
) |
Definition at line 154 of file ScanIOUtils.cpp.
void lvr2::loadScanImages | ( | std::vector< ScanImagePtr > & | images, |
boost::filesystem::path | dataPath | ||
) |
Definition at line 187 of file ScanIOUtils.cpp.
void lvr2::loadScanImages | ( | vector< ScanImagePtr > & | images, |
boost::filesystem::path | dataPath | ||
) |
bool lvr2::loadScanPosition | ( | const boost::filesystem::path & | root, |
ScanPosition & | scanPos, | ||
const size_t & | positionNumber | ||
) |
Definition at line 1032 of file ScanIOUtils.cpp.
bool lvr2::loadScanPosition | ( | const boost::filesystem::path & | root, |
ScanPosition & | scanPos, | ||
const std::string & | positionDirectory | ||
) |
Definition at line 951 of file ScanIOUtils.cpp.
bool lvr2::loadScanProject | ( | const boost::filesystem::path & | root, |
ScanProject & | scanProj | ||
) |
Definition at line 1083 of file ScanIOUtils.cpp.
Definition at line 548 of file TransformUtils.hpp.
Definition at line 566 of file TransformUtils.hpp.
Lvr to OpenCV coordinate change: Point.
OpenCV
z / /___ x
| | y
scale: m
LVR / ROS z x
| / y ___|/
Definition at line 538 of file TransformUtils.hpp.
Definition at line 454 of file TransformUtils.hpp.
Definition at line 486 of file TransformUtils.hpp.
Lvr to Slam6D coordinate change: Point.
Slam6D
y z
| / |/___ x
LVR / ROS z x
| / y ___|/
Definition at line 444 of file TransformUtils.hpp.
|
static |
OutMapT<typename InMapT::HandleType, std::result_of_t<MapF(typename InMapT::ValueType)> > lvr2::map | ( | const InMapT & | mapIn, |
MapF | func | ||
) |
Calls func
for each value of the given map and save the result in the output map.
The type of the output map needs to be specified explicitly as template parameter. You typically call it like this:
MapT | The (rank-2) type of the attribute map implementation used for the output map. E.g. DenseAttrMap or SparseAttrMap . |
Conversion from Matrix to Pose representation.
Conversion from Matrix to Pose representation in GraphSLAMs internally consistent Coordinate System
Definition at line 519 of file GraphSLAM.cpp.
|
static |
pair<ValueT, ValueT> lvr2::minMaxOfMap | ( | const AttributeMap< HandleT, ValueT > & | map | ) |
Returns the minimum and maximum element from the given map.
Of course, this assumes that the values in the map are comparable with the standard comparison operators.
Vector3<T> lvr2::multiply | ( | const Transform< T > & | transform, |
const Vector3< T > & | p | ||
) |
Definition at line 165 of file MatrixTypes.hpp.
size_t lvr2::naiveFillSmallHoles | ( | BaseMesh< BaseVecT > & | mesh, |
size_t | maxSize, | ||
bool | collapseOnly | ||
) |
Fills holes consisting of less than or equal to maxSize
edges.
It is a rather simple algorithm, really. For each connected part of the mesh it assumes that each boundary-contour except the one with most edges is a hole. These holes are then filled by collapsing all of their boundary edges until no collapsable edge is left (which happens in any case when the hole has only three edges left). If the remaining hole has only three edges after the previous step, it is filled by simply inserting a triangle.
Important: this algorithm assumes that the mesh doesn't contain any lonely edges.
|
static |
int lvr2::octreeReduce | ( | Vector3f * | points, |
int | n, | ||
double | voxelSize, | ||
int | maxLeafSize | ||
) |
Reduces a Point Cloud using an Octree with a minimum Voxel size.
points | The Point Cloud |
n | The number of Points in the Point Cloud |
voxelSize | The minimum size of a Voxel |
maxLeafSize | When to stop subdividing Voxels |
Definition at line 130 of file TreeUtils.cpp.
Definition at line 374 of file TransformUtils.hpp.
Definition at line 392 of file TransformUtils.hpp.
OpenCV to Lvr coordinate change: Point.
OpenCV
z / /___ x
| | y
LVR / ROS z x
| / y ___|/
Definition at line 364 of file TransformUtils.hpp.
|
inline |
Multiplication operator to support transformation with Eigen matrices. Rotates the normal, ignores translation. Implementation for RowMajor matrices.
CoordType | Coordinate type of the normals |
Scalar | Scalar type of the Eigen matrix |
mat | Eigen matrix |
normal | Input normal |
Definition at line 249 of file BaseVector.hpp.
|
inline |
Multiplication operator to support transformation with Eigen matrices. Rotates the normal, ignores translation. Implementation for RowMajor matrices.
CoordType | Coordinate type of the normals |
Scalar | Scalar type of the Eigen matrix |
mat | Eigen matrix |
normal | Input normal |
Definition at line 162 of file Normal.hpp.
|
inline |
Output operator for matrices.
Definition at line 638 of file Matrix4.hpp.
|
inline |
The output operator for Timestamp objects.
Definition at line 119 of file Timestamp.hpp.
std::ostream & lvr2::operator<< | ( | std::ostream & | lhs, |
const RieglProject & | rhs | ||
) |
Definition at line 381 of file RieglProject.cpp.
std::ostream & lvr2::operator<< | ( | std::ostream & | lhs, |
const ScanPosition & | rhs | ||
) |
Definition at line 391 of file RieglProject.cpp.
std::ostream& lvr2::operator<< | ( | std::ostream & | os, |
const BaseVector< T > & | v | ||
) |
Definition at line 227 of file BaseVector.hpp.
|
inline |
Definition at line 169 of file BoundingBox.hpp.
|
inline |
Definition at line 205 of file Handles.hpp.
|
inline |
Output operator for color vertex types.
Definition at line 170 of file ColorVertex.hpp.
|
inline |
Definition at line 187 of file Handles.hpp.
|
inline |
Definition at line 193 of file Handles.hpp.
|
inline |
Definition at line 103 of file HalfEdge.hpp.
|
inline |
|
inline |
Definition at line 140 of file Normal.hpp.
|
inline |
Definition at line 250 of file Handles.hpp.
|
inline |
Definition at line 211 of file Handles.hpp.
|
inline |
Definition at line 224 of file Handles.hpp.
|
inline |
Definition at line 109 of file HalfEdge.hpp.
|
inline |
Definition at line 237 of file Handles.hpp.
|
inline |
|
inline |
Definition at line 199 of file Handles.hpp.
void lvr2::optimizePlaneIntersections | ( | BaseMesh< BaseVecT > & | mesh, |
const ClusterBiMap< FaceHandle > & | clusters, | ||
const ClusterMap< Plane< BaseVecT >> & | planes | ||
) |
Compares every plane with its presumabl neighours, calculates their intersection and drags all points in-between to this intersection.
|
inline |
|
inline |
void lvr2::parseSLAMDirectory | ( | std::string | dir, |
vector< ScanPtr > & | scans | ||
) |
Reads a directory containing data from slam6d. Represents.
dir | A directory containing scans |
scans | The vector of all scans in this directory |
Definition at line 476 of file IOUtils.cpp.
ClusterBiMap<FaceHandle> lvr2::planarClusterGrowing | ( | const BaseMesh< BaseVecT > & | mesh, |
const FaceMap< Normal< typename BaseVecT::CoordType >> & | normals, | ||
float | minSinAngle | ||
) |
Algorithm which generates plane clusters from the given mesh.
minSinAngle | 1 - minSinAngle is the allowed difference between the sin of the angle of the starting face and all other faces in one cluster. |
ModelPtr lvr2::readMesh | ( | draco::DecoderBuffer & | buffer, |
draco::Decoder & | decoder | ||
) |
loads a mesh from the decoderBuffer and converts it into the lvr structure
buffer | DecoderBuffer that contains the encoded data from the draco file |
decoder | Decoder that is used to decode the buffer |
Definition at line 268 of file DracoDecoder.cpp.
ModelPtr lvr2::readPointCloud | ( | draco::DecoderBuffer & | buffer, |
draco::Decoder & | decoder | ||
) |
loads a pointcloud from the decoderBuffer and converts it into the lvr structure
buffer | DecoderBuffer that contains the encoded data from the draco file |
decoder | Decoder that is used to decode the buffer |
Definition at line 180 of file DracoDecoder.cpp.
void lvr2::removeDanglingCluster | ( | BaseMesh< BaseVecT > & | mesh, |
size_t | sizeThreshold | ||
) |
Removes all faces in connected clusters which are smaller (have less faces) than sizeThreshold
mesh | the mesh to operate on |
sizeThreshold | number of faces which a cluster has to contain to not be deleted |
|
static |
Converts a transformation matrix that is used in riegl coordinate system into a transformation matrix that is used in slam6d coordinate system.
in | The transformation matrix in riegl coordinate system |
Definition at line 172 of file TransformUtils.hpp.
int lvr2::saveAttributeToDraco | ( | ArrayType | array, |
draco::PointCloud * | drcPointcloud, | ||
draco::GeometryAttribute::Type | geometryType, | ||
draco::DataType | dracoDataType, | ||
size_t | numPoints, | ||
bool | normalized | ||
) |
adds the given data to a new attribute and attaches the attribute to the pointcloud
ArrayType | LVR intern type for storing pointcloud information |
DataType | data type for the data that is to be stored in the attribute |
size | is the number of values linked to a single point in the point cloud |
array | contains the data that is attempted to be stored in the attribute |
drcPointcloud | the draco intern pointcloud holding all the attributes |
geometryType | information about what is being stored in the attribute |
dracoDataType | data type that is used in draco |
numPoints | number of points in the array |
normalized | do the values have to be normalized? |
Definition at line 53 of file DracoEncoder.cpp.
void lvr2::saveHyperspectralCamera | ( | const boost::filesystem::path & | root, |
const HyperspectralCamera & | camera, | ||
const size_t & | positionNumber | ||
) |
Definition at line 794 of file ScanIOUtils.cpp.
void lvr2::saveHyperspectralCamera | ( | const boost::filesystem::path & | root, |
const HyperspectralCamera & | camera, | ||
const std::string & | positionDirectory | ||
) |
Definition at line 786 of file ScanIOUtils.cpp.
void lvr2::saveHyperspectralCamera | ( | const boost::filesystem::path & | root, |
const HyperspectralCamera & | camera, | ||
const std::string | positionDirectory, | ||
const std::string & | cameraDirectory | ||
) |
Definition at line 724 of file ScanIOUtils.cpp.
void lvr2::saveHyperspectralPanoramaChannel | ( | const boost::filesystem::path & | root, |
const HyperspectralPanoramaChannel & | channel, | ||
const std::string | positionDirectory, | ||
const std::string | panoramaDirectory, | ||
const size_t & | channelNumber | ||
) |
Definition at line 610 of file ScanIOUtils.cpp.
void lvr2::saveMetaInformation | ( | const std::string & | outfile, |
const YAML::Node & | node | ||
) |
Definition at line 6 of file MetaFormatFactory.cpp.
void lvr2::saveScan | ( | const boost::filesystem::path & | root, |
const Scan & | scan, | ||
const size_t & | positionNumber, | ||
const size_t & | scanNumber | ||
) |
Definition at line 472 of file ScanIOUtils.cpp.
void lvr2::saveScan | ( | const boost::filesystem::path & | root, |
const Scan & | scan, | ||
const std::string | positionDirectory, | ||
const std::string | scanDirectory, | ||
const size_t & | scanNumber | ||
) |
Definition at line 459 of file ScanIOUtils.cpp.
void lvr2::saveScan | ( | const boost::filesystem::path & | root, |
const Scan & | scan, | ||
const std::string | positionName, | ||
const std::string | scanDirectoryName, | ||
const std::string | scanName | ||
) |
SCAN.
Save a Scan struct.
root | Project root directory |
scan | The scan object to save |
positionName | The name of the scan position |
scanDirectoryName | The name of the scan directory |
scanName | The name of the generated scan file |
Definition at line 379 of file ScanIOUtils.cpp.
void lvr2::saveScanCamera | ( | const boost::filesystem::path & | root, |
const ScanCamera & | image, | ||
const size_t & | positionNumber, | ||
const size_t & | cameraNumber | ||
) |
Definition at line 306 of file ScanIOUtils.cpp.
void lvr2::saveScanCamera | ( | const boost::filesystem::path & | root, |
const ScanCamera & | image, | ||
const std::string & | positionDirectory, | ||
const size_t & | cameraNumber | ||
) |
Definition at line 294 of file ScanIOUtils.cpp.
void lvr2::saveScanCamera | ( | const boost::filesystem::path & | root, |
const ScanCamera & | image, | ||
const std::string | positionDirectory, | ||
const std::string | cameraDirectory | ||
) |
SCANCAMERA.
Definition at line 254 of file ScanIOUtils.cpp.
void lvr2::saveScanImage | ( | const boost::filesystem::path & | root, |
const ScanImage & | image, | ||
const size_t & | positionNumber, | ||
const size_t & | cameraNumber, | ||
const size_t & | imageNumber | ||
) |
SCANIMAGE.
Definition at line 38 of file ScanIOUtils.cpp.
void lvr2::saveScanImage | ( | const boost::filesystem::path & | root, |
const ScanImage & | image, | ||
const std::string | positionDirectory, | ||
const size_t & | cameraNumber, | ||
const size_t & | imageNumber | ||
) |
Definition at line 54 of file ScanIOUtils.cpp.
void lvr2::saveScanImage | ( | const boost::filesystem::path & | root, |
const ScanImage & | image, | ||
const std::string | positionDirectory, | ||
const std::string | cameraDirectory, | ||
const size_t & | imageNr | ||
) |
Definition at line 78 of file ScanIOUtils.cpp.
void lvr2::saveScanPosition | ( | const boost::filesystem::path & | root, |
const ScanPosition & | scanPos, | ||
const size_t & | positionNumber | ||
) |
Definition at line 940 of file ScanIOUtils.cpp.
void lvr2::saveScanPosition | ( | const boost::filesystem::path & | root, |
const ScanPosition & | scanPos, | ||
const std::string | positionDirectory | ||
) |
SCAN_POSITION.
Save a ScanPosition struct.
root | Project root directory |
scanPos | The scan object to save |
positionName | The name of the scan position |
scanDirectoryName | The name of the scan directory |
scanName | The name of the generated scan file |
Definition at line 888 of file ScanIOUtils.cpp.
void lvr2::saveScanProject | ( | const boost::filesystem::path & | root, |
const ScanProject & | scanProj | ||
) |
SCAN_PROJECT.
Save a ScanProject struct.
root | Project root directory |
scanProj | The scanproject object to save |
Definition at line 1046 of file ScanIOUtils.cpp.
void lvr2::saveTextures | ( | std::vector< int32_t > * | textureValue, |
textureArr | textures, | ||
size_t | numTextures | ||
) |
pushes the given textures in a int32_t vector to store it in the draco structure
textureValue | the vector to be stored in draco |
textures | the exported textures from lvr |
numTextures | number of textures in the textureArr |
Definition at line 90 of file DracoEncoder.cpp.
void lvr2::saveTextures | ( | std::vector< int32_t > * | textureValue, |
vector< Texture > & | textures | ||
) |
pushes the given textures in a int32_t vector to store it in the draco structure
textureValue | the vector to be stored in draco |
textures | the exported textures from lvr |
numTextures | number of textures in the textureArr |
Definition at line 125 of file DracoEncoder.cpp.
Iter lvr2::select_randomly | ( | Iter | start, |
Iter | end | ||
) |
Select a random element between start and end using the std::mt19937 random generator
Iter | Iter Type for the start and end iterator |
start | Start of the range to pick random element between |
end | End of the range to pick random element between |
Iter lvr2::select_randomly | ( | Iter | start, |
Iter | end, | ||
RandomGenerator & | g | ||
) |
Select a random element between start and end
Iter | Type for the start and end iterator |
RandomGenerator | Type for the random generator |
start | Start of the range to pick random element between |
end | End of the range to pick random element between |
g | random generator for selecting process |
size_t lvr2::simpleMeshReduction | ( | BaseMesh< BaseVecT > & | mesh, |
const size_t | count, | ||
FaceMap< Normal< typename BaseVecT::CoordType >> & | faceNormals | ||
) |
Like iterativeEdgeCollapse
but with a fixed cost function.
vector<VertexHandle> lvr2::simplifyContour | ( | const BaseMesh< BaseVecT > & | mesh, |
const vector< VertexHandle > & | contour, | ||
float | threshold | ||
) |
Simplifies the given contour with the Reumann-Witkam algorithm.
mesh | the mesh to operate on |
contour | the contour to be simplified |
threshold | angle between edges / lines on one contour |
Definition at line 283 of file TransformUtils.hpp.
Definition at line 315 of file TransformUtils.hpp.
Slam6D to LVR coordinate change: Point.
Slam6D
y z
| / |/___ x
LVR / ROS z x
| / y ___|/
Definition at line 273 of file TransformUtils.hpp.
Definition at line 230 of file TransformUtils.hpp.
|
static |
Converts a transformation matrix that is used in slam6d coordinate system into a transformation matrix that is used in riegl coordinate system.
in | The transformation matrix in slam6d coordinate system |
Definition at line 205 of file TransformUtils.hpp.
void lvr2::slamToLVRInPlace | ( | PointBufferPtr | src | ) |
Transforms src, which is assumed to be in slam6Ds left-handed coordinate system into our right-handed default coordinate system. The transformation is done in-place, so the original data will be modified.
src | Source buffer |
Definition at line 452 of file IOUtils.cpp.
|
static |
|
static |
|
static |
|
static |
int lvr2::splitPoints | ( | Vector3f * | points, |
int | n, | ||
int | axis, | ||
double | splitValue | ||
) |
Sorts a Point array so that all Points smaller than splitValue are on the left.
Uses the QuickSort Pivot step
points | The Point array |
n | The number of Points |
axis | The axis to sort by |
splitValue | The value to sort by |
Definition at line 47 of file TreeUtils.cpp.
Transformd lvr2::string2mat4f | ( | const std::string | data | ) |
Definition at line 44 of file RieglProject.cpp.
void lvr2::subsample | ( | PointBufferPtr | src, |
PointBufferPtr | dst, | ||
const vector< size_t > & | indices | ||
) |
Definition at line 375 of file IOUtils.cpp.
Channel<T>::Ptr lvr2::subSampleChannel | ( | Channel< T > & | src, |
std::vector< size_t > | ids | ||
) |
Definition at line 354 of file IOUtils.cpp.
PointBufferPtr lvr2::subSamplePointBuffer | ( | PointBufferPtr | src, |
const size_t & | n | ||
) |
Computes a random sub-sampling of a point buffer by creating a uniform distribution over all point indices with given target size. The sub-sampling is applied to all channels in the source buffer.
src | Source buffer |
n | Number of target points |
Definition at line 405 of file IOUtils.cpp.
PointBufferPtr lvr2::subSamplePointBuffer | ( | PointBufferPtr | src, |
const std::vector< size_t > & | indices | ||
) |
Computes a reduced version of the source buffer by sampling all channels using the given set of point indices.
src | Source buffer |
indices | Vector of the point indices that will be copied into the returned buffer |
Definition at line 389 of file IOUtils.cpp.
void lvr2::swap | ( | T *& | arr, |
size_t | i1, | ||
size_t | i2, | ||
size_t | n | ||
) |
boost::shared_ptr<T> lvr2::to_boost_ptr | ( | const std::shared_ptr< T > & | p | ) |
Definition at line 61 of file ConvertShared.hpp.
std::shared_ptr<T> lvr2::to_std_ptr | ( | const boost::shared_ptr< T > & | p | ) |
Definition at line 52 of file ConvertShared.hpp.
void lvr2::tokenize | ( | const string & | str, |
vector< string > & | tokens, | ||
const string & | delimiters = " " |
||
) |
void lvr2::transformAndReducePointCloud | ( | ModelPtr & | model, |
int | modulo, | ||
const CoordinateTransform< T > & | c | ||
) |
Transforms (scale and switch coordinates) and reduces a model containing point cloud data using a modulo filter. Use this function the convert between different coordinate systems.
model | A model containing point cloud data |
modulo | The reduction factor for the modulo filter. Set to 1 to keep the original resolution. |
c | The coordinate transformation applied to the model |
void lvr2::transformAndReducePointCloud | ( | ModelPtr | model, |
int | modulo, | ||
const T & | sx, | ||
const T & | sy, | ||
const T & | sz, | ||
const unsigned char & | xPos, | ||
const unsigned char & | yPos, | ||
const unsigned char & | zPos | ||
) |
Transforms (scale and switch coordinates) and reduces a model containing point cloud data using a modulo filter. Use this function the convert between different coordinate systems.
model | A model containing point cloud data |
modulo | The reduction factor for the modulo filter. Set to 1 to keep the original resolution. |
sx | Scaling factor in x direction |
sy | Scaling factor in y direction |
sz | Scaling factor in z direction |
xPos | Position of the x position in the input data, i.e, "which array position has the x coordinate that is written to the output data in the input data" |
yPos | Same as with xPos for y. |
zPos | Same as with xPos for z. |
Transform<T> lvr2::transformFrame | ( | const Transform< T > & | frame, |
const CoordinateTransform< T > & | ct | ||
) |
Transforms the given source frame according to the given coordinate transform struct.
frame | Source frame |
ct | Coordinate system transformation |
void lvr2::transformPointCloud | ( | ModelPtr | model, |
const Transform< T > & | transformation | ||
) |
Transforms a model containing a point cloud according to the given transformation (usually from a .frames file)
A | model containing point cloud data. |
A | transformation. |
void lvr2::transformPointCloudAndAppend | ( | PointBufferPtr & | buffer, |
boost::filesystem::path & | transfromFile, | ||
std::vector< float > & | pts, | ||
std::vector< float > & | nrm | ||
) |
Transforms the given point buffer according to the transformation stored in transformFile and appends the transformed points and normals to pts and nrm.
buffer | A PointBuffer |
transformFile | The input file name. The fuction will search for transformation information (.pose or .frames) |
pts | The transformed points are added to this vector |
nrm | The transformed normals are added to this vector |
Definition at line 40 of file IOUtils.cpp.
Transform<T> lvr2::transformRegistration | ( | const Transform< T > & | transform, |
const Transform< T > & | registration | ||
) |
Transforms a registration matrix according to the given transformation matrix, i.e., applies transform to registration.
transform | A transformation matrix |
registration | A matrix representing a registration (i.e. transformation) that |
void lvr2::visitLocalVertexNeighborhood | ( | const BaseMesh< BaseVecT > & | mesh, |
VertexHandle | vH, | ||
double | radius, | ||
VisitorF | visitor | ||
) |
Visits every vertex in the local neighborhood of vH
.
The local neighborhood is defined as all vertices that are connected to vH
and where the "path" in between those vertices only contains vertices that are no further away from vH
than radius
.
For every such vertex in the local neighborhood (not vH
itself!) the given visitor
is called exactly once.
lvr2::vtkStandardNewMacro | ( | LVRPickingInteractor | ) |
void lvr2::walkContour | ( | const BaseMesh< BaseVecT > & | mesh, |
EdgeHandle | startH, | ||
VisitorF | visitor | ||
) |
Like the other overload, but without ignoring any faces.
void lvr2::walkContour | ( | const BaseMesh< BaseVecT > & | mesh, |
EdgeHandle | startH, | ||
VisitorF | visitor, | ||
PredF | exists | ||
) |
Walks on a boundary contour starting at startH
.
To make the method more generic, it has a exists
function object which can filter out faces. Each face for which exists
returns false
is treated as if it wouldn't exist in the mesh at all! If you don't want to ignore faces, you can just not provide the exists
parameter to use the other overload.
The given startH
as well as all other edges on the contour mustn't be a lonely edge (when ignoring faces according to exists
).
The edges of the contour are visited in counter-clockwise order. That is, if you look at the contour as if it were a hole in the mesh. If you are thinking of the contour as an outer contour, it's in clockwise order. This matter is pretty confusing and I don't know how to explain it a lot better. Here another attempt:
Inner contours are visited in counter-clockwise order and outer ones in clockwise order. Inner contours are commonly referred to as "holes in the mesh", while the outer one is often called "mesh boundary". However, for 3D meshes, the distinction isn't all that clear. What matters here is the planar embedding of the mesh. There are many possible planar embeddings, including the ones that make the "mesh boundary" look like a hole and vice versa.
Anyway, we can say this for sure: given one concrete embedding for your mesh, the outer contour's edges are returned in clockwise order and the edges of all inner contours are returned in counter-clockwise order.
visitor | A function object taking two parameters: a VertexHandle and an EdgeHandle . The vertex is the vertex of the edge that comes "before" the edge, speaking about the direction of visiting the edges. |
exists | A function object taking one FaceHandle as parameter and returning bool. This function decides whether a face should be treated as existing or not. This is mainly used to walk on the boundary of clusters. This can be achieved by making exists return false for all faces not in the cluster. |
void lvr2::writeDebugContourMesh | ( | const BaseMesh< BaseVecT > & | mesh, |
string | filename = "debug-contours.ply" , |
||
Rgb8Color | connectedColor = {0, 255, 0} , |
||
Rgb8Color | contourColor = {0, 0, 255} , |
||
Rgb8Color | bugColor = {255, 0, 0} |
||
) |
Writes a mesh to the given filename and colors it with the following meaning:
void lvr2::writeDebugMesh | ( | const BaseMesh< BaseVecT > & | mesh, |
string | filename = "debug.ply" , |
||
Rgb8Color | color = {255, 0, 0} |
||
) |
Write a mesh to the given filename and color it with the given color.
void lvr2::writeFrame | ( | const Transform< T > & | transform, |
const boost::filesystem::path & | framesOut | ||
) |
Writes a Eigen transformation into a .frames file.
transform | The transformation |
framesOut | The target file. |
size_t lvr2::writeModel | ( | ModelPtr | model, |
const boost::filesystem::path & | outfile | ||
) |
Writes the given model to the given file.
model | A LVR model |
outfile | The target file. |
Definition at line 164 of file IOUtils.cpp.
void lvr2::writePointsAndNormals | ( | std::vector< float > & | p, |
std::vector< float > & | n, | ||
std::string | outfile | ||
) |
Writes the points and normals (float triples) stored in p and n to the given output file. Attention: The data is converted to a PointBuffer structure to be able to use the IO library, which results in a considerable memory overhead.
p | A vector containing point definitions. |
n | A vector containing normal information. |
outfile | The target file. |
Definition at line 252 of file IOUtils.cpp.
size_t lvr2::writePointsToStream | ( | ModelPtr | model, |
std::ofstream & | out, | ||
bool | nocolor = false |
||
) |
Writes the points stored in the given model to the fiven output stream. This function is used to apend point cloud data to an already existing ASCII file..
model | A model containing point cloud data |
out | A output stream |
nocolor | If set to true, the color information in the model is ignored. |
Definition at line 174 of file IOUtils.cpp.
void lvr2::writePose | ( | const BaseVector< float > & | position, |
const BaseVector< float > & | angles, | ||
const boost::filesystem::path & | out | ||
) |
Writes pose information in Euler representation to the given file.
position | Position |
angles | Rotation angles in degrees |
Definition at line 154 of file IOUtils.cpp.
|
static |
This table states where each coordinate of a box vertex is relative to the box center.
Definition at line 86 of file FastReconstructionTables.hpp.
|
static |
Definition at line 97 of file FastReconstructionTables.hpp.
|
static |
Definition at line 9 of file Braille.hpp.
|
static |
Definition at line 97 of file FastBoxTables.hpp.
|
static |
Definition at line 86 of file FastBoxTables.hpp.
|
static |
Definition at line 167 of file OctreeTables.hpp.
|
static |
Definition at line 34 of file cl_helper.h.
|
static |
Definition at line 41 of file ExtendedMCTable.hpp.
|
static |
Definition at line 124 of file FastReconstructionTables.hpp.
|
static |
Definition at line 41 of file MCTable.hpp.
|
static |
Definition at line 41 of file FastBoxTables.hpp.
|
static |
Definition at line 56 of file FastBoxTables.hpp.
|
static |
Definition at line 81 of file OctreeTables.hpp.
|
static |
Definition at line 92 of file OctreeTables.hpp.
|
static |
Definition at line 40 of file OctreeTables.hpp.
|
static |
Definition at line 55 of file OctreeTables.hpp.
|
static |
Definition at line 70 of file OctreeTables.hpp.
|
static |
A table coding the relations between shared vertices of adjacent positions in the grid created during the marching cubes reconstruction process.
Each box corner in the grid is shared with 7 other boxes. To find an already existing corner, these boxes have to be checked. The following table holds the information where to look for a given corner. The coding is as follows:
Table row = query vertex
Each row consists of 7 quadruples. The first three numbers indicate, how the indices in x- y- and z-direction have to be modified. The fourth entry is the vertex of the box correspondig to the modified indices.
Example: index_x = 10, index_y = 7, index_z = 5
Query vertex = 5
First quadruple: {+1, 0, +1, 0} Indices pointing to the nb-box: 10 + 1, 7 + 0, 5 + 1. --> The first shared vertex is vertex number 0 of the box in position (11, 7, 6) of the grid.
Simple isn't it?
Definition at line 70 of file FastReconstructionTables.hpp.
|
static |
Definition at line 91 of file TetraederTables.hpp.
|
static |
Definition at line 80 of file TetraederTables.hpp.
|
static |
Definition at line 101 of file TetraederTables.hpp.
|
static |
Definition at line 60 of file TetraederTables.hpp.
|
static |
Definition at line 124 of file TetraederTables.hpp.
|
static |
A global time stamp object for program runtime measurement.
Definition at line 116 of file Timestamp.hpp.
|
static |
This tables stors adjacency information for the grid creation algorithm.
Definition at line 113 of file FastReconstructionTables.hpp.
|
static |
Definition at line 71 of file FastBoxTables.hpp.