supereight
Loading...
Searching...
No Matches
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
se Namespace Reference

Helper wrapper to allocate and de-allocate octants in the octree. More...

Namespaces

namespace  algorithms
 
namespace  allocator
 
namespace  colour
 
namespace  colours
 
namespace  data
 
namespace  detail
 
namespace  eigen
 Helper functions for Eigen objects.
 
namespace  fetcher
 
namespace  icp
 
namespace  image
 
namespace  integrator
 Helper wrapper to integrate data in the octree.
 
namespace  io
 
namespace  keyops
 
namespace  math
 
namespace  meshing
 
namespace  octantops
 
namespace  preprocessor
 
namespace  propagator
 
namespace  ray_integrator
 
namespace  raycaster
 
namespace  str_utils
 
namespace  system
 
namespace  uncert
 
namespace  updater
 
namespace  visitor
 
namespace  yaml
 

Classes

struct  AppConfig
 
struct  BaseIterator
 Iterates over all valid data in the octree at the last scale it was updated at. More...
 
struct  BaseTraits
 
struct  BaseTraits< BlocksIterator< OctreeT > >
 
struct  BaseTraits< FrustumIterator< MapT, SensorT > >
 
struct  BaseTraits< LeavesIterator< OctreeT > >
 
struct  BaseTraits< NodesIterator< OctreeT > >
 
struct  BaseTraits< OctreeIterator< OctreeT > >
 
struct  BaseTraits< UpdateIterator< OctreeT > >
 
class  Block
 A leaf node of an se::Octree. More...
 
class  BlockMultiRes
 
class  BlockMultiRes< Data< Field::Occupancy, ColB, SemB >, BlockSize, DerivedT >
 
class  BlockMultiRes< Data< Field::TSDF, ColB, SemB >, BlockSize, DerivedT >
 
class  BlockMultiRes< Data< FldT, ColB, SemB >, BlockSize, DerivedT >
 
class  BlockSingleRes
 The base used for single-resolution blocks. More...
 
struct  BlocksIterator
 
struct  ColourData
 
struct  ColourData< Colour::On >
 
struct  Config
 
struct  Data
 
class  DensePoolingImage
 
struct  FieldData
 
struct  FieldData< Field::Occupancy >
 
struct  FieldData< Field::TSDF >
 
struct  FrustumIterator
 
class  Image
 
class  InteriorNetReader
 Reader for the InteriorNet dataset. More...
 
struct  LeavesIterator
 
class  LeicaLidar
 
class  LeicaReader
 Reader for Leica style datasets. More...
 
class  Map
 
class  Map< se::Data< FldT, ColB, SemB >, ResT, BlockSize >
 
class  MapIntegrator
 
struct  Measurement
 Contains an image captured from sensor at pose T_WC. More...
 
struct  Measurements
 Contains measurements from different modalities that must be integrated together. More...
 
class  MemoryPool
 Manages memory for se::Octree nodes and blocks in an efficient manner. More...
 
struct  MeshFace
 
struct  MeshFaceColourData
 
struct  MeshFaceColourData< NumVertexes, Colour::On >
 
struct  MeshFaceSemanticData
 
class  NewerCollegeReader
 Reader for the Newer College dataset. More...
 
class  Node
 An intermediate node of an se::Octree. More...
 
struct  NodeData
 Contains se::Data stored in se::Node and appropriate methods. More...
 
struct  NodeData< Data< Field::Occupancy, ColB, SemB >, ResT >
 Specialization of se::NodeData for se::Field::Occupancy. More...
 
struct  NodesIterator
 
class  NullMemoryPool
 An alternate implementation of se::MemoryPool that can help debug certain memory-related bugs. More...
 
class  OctantBase
 The base class of all octants (se::Node and se::Block) in an se::Octree. More...
 
class  Octree
 The octree data structure containing the map data. More...
 
struct  OctreeIterator
 
class  OpenNIReader
 Reader for the Microsoft Kinect and Asus Xtion using the OpenNI2 driver. More...
 
class  OusterLidar
 
struct  PerfStats
 
class  PinholeCamera
 
struct  Pixel
 
class  RAWReader
 Reader for SLAMBench 1.0 .raw files. More...
 
class  RaycastCarver
 Allocator used for TSDF mapping. More...
 
class  RayIntegrator
 
class  RayIntegrator< Map< Data< se::Field::Occupancy, ColB, SemB >, se::Res::Multi, BlockSize >, SensorT >
 
class  Reader
 Base abstract class for dataset readers. More...
 
struct  RGB
 A colour represented as a Red-Green-Blue tuple with 8-bits per channel. More...
 
struct  RGBA
 A colour represented as a Red-Green-Blue-Alpha tuple with 8-bits per channel. More...
 
struct  SemanticData
 
struct  SemanticData< Semantics::On >
 
class  SensorBase
 Base class for all sensor models used for integrating measurements. More...
 
struct  Submap
 Stores an se::Map and an associated transformation from the submap to the world frame. More...
 
class  Tracker
 
struct  TrackerConfig
 
class  TUMReader
 Reader for the TUM RGBD dataset. More...
 
struct  UpdateIterator
 
struct  Updater
 
class  Updater< Map< Data< Field::Occupancy, ColB, SemB >, Res::Multi, BlockSize >, SensorT >
 
struct  Updater< Map< Data< Field::TSDF, ColB, SemB >, Res::Multi, BlockSize >, SensorT >
 Specialization of se::Updater for multi-resolution TSDF mapping. More...
 
struct  Updater< Map< Data< Field::TSDF, ColB, SemB >, Res::Single, BlockSize >, SensorT >
 Specialization of se::Updater for single-resolution TSDF mapping. More...
 
class  VolumeCarver
 Unimplemented on purpose so that the template specialization is used. More...
 
class  VolumeCarver< Map< Data< se::Field::Occupancy, ColB, SemB >, se::Res::Multi, BlockSize >, SensorT >
 Allocate the frustum using a map-to-camera volume carving approach. More...
 
struct  VolumeCarverAllocation
 
class  VoxelBlockRayIterator
 

Typedefs

template<typename T , std::size_t N>
using BoundedVector = std::vector< T, detail::ArrayAllocator< T, N > >
 A statically-allocated std::vector that can store at most N elements.
 
using Value = float
 
using Status = int
 
template<typename FaceT >
using Mesh = std::vector< FaceT >
 Meshes are represented as lists of faces.
 
template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using Triangle = MeshFace< 3, ColB, SemB >
 
template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using TriangleMesh = Mesh< Triangle< ColB, SemB > >
 
template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using Quad = MeshFace< 4, ColB, SemB >
 
template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using QuadMesh = Mesh< Quad< ColB, SemB > >
 
typedef Data< Field::Occupancy, Colour::Off, Semantics::OffOccupancyData
 
typedef Data< Field::Occupancy, Colour::On, Semantics::OffOccupancyColData
 
typedef Data< Field::Occupancy, Colour::Off, Semantics::OnOccupancySemData
 
typedef Data< Field::Occupancy, Colour::On, Semantics::OnOccupancyColSemData
 
typedef Data< Field::TSDF, Colour::Off, Semantics::OffTSDFData
 
typedef Data< Field::TSDF, Colour::On, Semantics::OffTSDFColData
 
typedef Data< Field::TSDF, Colour::Off, Semantics::OnTSDFSemData
 
typedef Data< Field::TSDF, Colour::On, Semantics::OnTSDFColSemData
 
template<se::Field FldT = se::Field::TSDF, se::Colour ColB = se::Colour::Off, se::Semantics SemB = se::Semantics::Off, se::Res ResT = se::Res::Single, int BlockSize = 8>
using MapD = Map< Data< FldT, ColB, SemB >, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using OccupancyMap = Map< OccupancyData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using OccupancyColMap = Map< OccupancyColData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using OccupancySemMap = Map< OccupancySemData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using OccupancyColSemMap = Map< OccupancyColSemData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using TSDFMap = Map< TSDFData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using TSDFColMap = Map< TSDFColData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using TSDFSemMap = Map< TSDFSemData, ResT, BlockSize >
 
template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using TSDFColSemMap = Map< TSDFColSemData, ResT, BlockSize >
 
typedef uint64_t key_t
 key = 1 bit buffer + 57 bits of morton code + 6 bits of scale information The maxium scale is limited by 57 / 3 = 19 scales
 
typedef uint64_t code_t
 The type of the Morton code.
 
typedef uint64_t scale_t
 The type of the scale in the morton code.
 
typedef unsigned int idx_t
 Child or voxel index type.
 
typedef float field_t
 The type of the stored field (e.g. TSDF, ESDF or occupancy)
 
typedef Eigen::Matrix< field_t, 3, 1 > field_vec_t
 
typedef se::field_t weight_t
 The type of the field type weight.
 
typedef int timestamp_t
 The type of the time stamp.
 
typedef RGB colour_t
 The type of the colour.
 
typedef uint8_t semantics_t
 The type of the semantic class.
 
template<typename MapT >
using SubmapVec = std::vector< Submap< MapT >, Eigen::aligned_allocator< Submap< MapT > > >
 
template<typename KeyT , typename MapT >
using SubmapUnordMap = std::unordered_map< KeyT, Submap< MapT >, std::hash< KeyT >, std::equal_to< KeyT >, Eigen::aligned_allocator< std::pair< const KeyT, Submap< MapT > > > >
 

Enumerations

enum class  VarianceState { Constant , Gradient , Undefined }
 
enum class  RayState { FreeSpace , Transition , Occupied , Undefined }
 
enum class  UncertaintyModel { Linear , Quadratic }
 
enum class  Field { TSDF , Occupancy }
 
enum class  Colour { Off , On }
 
enum class  Semantics { Off , On }
 
enum class  Res { Single , Multi }
 
enum class  Integ { Simple , LiDAR , PinholeCamera }
 
enum class  Safe { On = true , Off = false }
 
enum class  AllocMeth { Raycasting , VoxelCarving }
 
enum class  Rep { Surface , Freespace }
 
enum class  Sort { SmallToLarge , LargeToSmall }
 The enum classes to define the sorting templates. More...
 
enum class  ReaderType {
  OPENNI , RAW , TUM , INTERIORNET ,
  NEWERCOLLEGE , LEICA , UNKNOWN
}
 
enum class  ReaderStatus : int { ok = 0 , skip , eof , error }
 The result of trying to read a depth/RGB image or a pose. More...
 

Functions

void depth_to_rgba (RGBA *depth_RGBA_image_data, const float *depth_image_data, const Eigen::Vector2i &depth_image_res, const float min_depth, const float max_depth)
 Convert a depth image to an RGBA image to allow visualizing it.
 
static RGB scale_colour (const int scale)
 Return the color from se::colours::scale that should be used to visualize the supplied scale.
 
int save_depth_png (const float *depth_image_data, const Eigen::Vector2i &depth_image_res, const std::string &filename, const float scale=1000.0f)
 Save a depth image with depth values in metres to a PNG.
 
int save_depth_png (const uint16_t *depth_image_data, const Eigen::Vector2i &depth_image_res, const std::string &filename)
 Save a depth image with depth values in millimetres to a PNG.
 
int load_depth_png (float **depth_image_data, Eigen::Vector2i &depth_image_res, const std::string &filename, const float inverse_scale=1.0f/1000.0f)
 Load a PNG depth image into a buffer with depth values in metres.
 
int load_depth_png (uint16_t **depth_image_data, Eigen::Vector2i &depth_image_res, const std::string &filename)
 Load a PNG depth image into a buffer with depth values in millimetres.
 
int save_depth_pgm (const float *depth_image_data, const Eigen::Vector2i &depth_image_res, const std::string &filename, const float scale=1000.0f)
 Save a depth image with depth values in metres to a P2 PGM.
 
int save_depth_pgm (const uint16_t *depth_image_data, const Eigen::Vector2i &depth_image_res, const std::string &filename)
 Save a depth image with depth values in millimetres to a P2 PGM.
 
int load_depth_pgm (float **depth_image_data, Eigen::Vector2i &depth_image_res, const std::string &filename, const float inverse_scale=1.0f/1000.0f)
 Load a P2 PGM depth image into a buffer with depth values in metres.
 
int load_depth_pgm (uint16_t **depth_image_data, Eigen::Vector2i &depth_image_res, const std::string &filename)
 Load a P2 PGM depth image into a buffer with depth values in millimeters.
 
static Eigen::Vector2i round_pixel (const Eigen::Vector2f &pixel_f)
 
static void convert_to_output_depth_img (const se::Image< float > &input_depth_img, RGBA *output_depth_img_data)
 
static void convert_to_output_depth_img (const se::Image< float > &input_depth_img, const float min_depth, const float max_depth, RGBA *output_depth_img_data)
 
template<typename SensorT , typename T >
 Measurement (const Image< T > &, const SensorT &, const Eigen::Isometry3f &) -> Measurement< SensorT, T >
 
template<typename SensorT >
 Measurements (const Measurement< SensorT, float > &) -> Measurements< SensorT >
 
template<typename SensorT >
 Measurements (const Measurement< SensorT, float > &, const Measurement< SensorT, colour_t > &) -> Measurements< SensorT >
 
template<typename SensorT >
 Measurements (const Measurement< SensorT, float > &, const Measurement< SensorT, colour_t > &, const Image< float > *) -> Measurements< SensorT >
 
template<typename ConfigT >
float compute_three_sigma (const field_t depth_value, const float sigma_min, const float sigma_max, const ConfigT config)
 Compute the estimated uncertainty boundary for a given depth measurement.
 
template<typename ConfigT >
float compute_tau (const field_t depth_value, const float tau_min, const float tau_max, const ConfigT config)
 Compute the estimated wall thickness tau for a given depth measurement.
 
template<Colour ColB, Semantics SemB>
TriangleMesh< ColB, SemBquad_to_triangle_mesh (const QuadMesh< ColB, SemB > &quad_mesh)
 Return a triangle mesh containig two triangles for each face of quad_mesh.
 
template<typename OctreeT >
OctreeT::StructureMesh octree_structure_mesh (OctreeT &octree, const bool only_leaves=true)
 Return a mesh of the octants of octree.
 
template<Field FldT, Colour ColB, Semantics SemB>
void set_invalid (Data< FldT, ColB, SemB > &data)
 
template<Colour ColB, Semantics SemB>
void set_invalid (Data< Field::TSDF, ColB, SemB > &data)
 
template<Colour ColB, Semantics SemB>
void set_invalid (Data< Field::Occupancy, ColB, SemB > &data)
 
template<Field FldT, Colour ColB, Semantics SemB>
bool is_valid (const Data< FldT, ColB, SemB > &data)
 
template<Field FldT, Colour ColB, Semantics SemB>
field_t get_field (const Data< FldT, ColB, SemB > &data)
 
template<Colour ColB, Semantics SemB>
field_t get_field (const Data< Field::TSDF, ColB, SemB > &data)
 
template<Colour ColB, Semantics SemB>
field_t get_field (const Data< Field::Occupancy, ColB, SemB > &data)
 
template<Field FldT, Colour ColB, Semantics SemB>
bool is_inside (const Data< FldT, ColB, SemB > &data)
 
template<Colour ColB, Semantics SemB>
bool is_inside (const Data< Field::TSDF, ColB, SemB > &data)
 
template<Colour ColB, Semantics SemB>
bool is_inside (const Data< Field::Occupancy, ColB, SemB > &data)
 
std::ostream & operator<< (std::ostream &os, const ColourData< Colour::Off >::Config &c)
 
std::ostream & operator<< (std::ostream &os, const ColourData< Colour::On >::Config &c)
 
std::ostream & operator<< (std::ostream &os, const FieldData< Field::Occupancy >::Config &c)
 
std::ostream & operator<< (std::ostream &os, const FieldData< Field::TSDF >::Config &c)
 
std::ostream & operator<< (std::ostream &os, const SemanticData< Semantics::Off >::Config &c)
 
std::ostream & operator<< (std::ostream &os, const SemanticData< Semantics::On >::Config &c)
 
std::ostream & operator<< (std::ostream &os, const LeicaLidar::Config &c)
 
std::ostream & operator<< (std::ostream &os, const OusterLidar::Config &c)
 
std::ostream & operator<< (std::ostream &os, const PinholeCamera::Config &c)
 
std::ostream & operator<< (std::ostream &os, const TrackerConfig &c)
 
std::ostream & operator<< (std::ostream &os, const AppConfig &c)
 
template<typename MapT , typename SensorT >
std::ostream & operator<< (std::ostream &os, const Config< MapT, SensorT > &c)
 
cv::Mat montage (int montage_width, int montage_height, const std::vector< cv::Mat > &images, const std::vector< std::string > &labels)
 Create a montage of several images and overlay labels.
 
Readercreate_reader (const se::Reader::Config &config)
 Create the appropriate reader instance based on the configuration.
 
ReaderType string_to_reader_type (const std::string &s)
 
std::string reader_type_to_string (ReaderType t)
 
std::ostream & operator<< (std::ostream &os, const ReaderStatus &s)
 
std::ostream & operator<< (std::ostream &os, const Reader::Config &c)
 

Variables

PerfStats perfstats
 
constexpr uint64_t CODE_MASK []
 The code mask for a given scale.
 
constexpr uint64_t SCALE_MASK = 0x1F
 11 111
 
static Eigen::Vector3f sample_offset_frac = Eigen::Vector3f::Constant(0.5f)
 
constexpr float e_delta = 0.1f
 

Detailed Description

Helper wrapper to allocate and de-allocate octants in the octree.

Helper wrapper to traverse the octree.

The actual allocation and deallocation of memory is still only handled by the octree class.

All functions take a const octree references and as no manipulation of the octree is done.

Typedef Documentation

◆ BoundedVector

template<typename T , std::size_t N>
using se::BoundedVector = typedef std::vector<T, detail::ArrayAllocator<T, N> >

A statically-allocated std::vector that can store at most N elements.

Allows avoiding dynamic memory allocation when the maximum size of a vector is known at compile-time.

Note
N must be a power of 2 due to how std::vector typically grows the internal buffer.

◆ Value

◆ Status

◆ Mesh

template<typename FaceT >
using se::Mesh = typedef std::vector<FaceT>

Meshes are represented as lists of faces.

Bug:
This representation has the inherent problem that there is vertex duplication. A more advanced representation would be needed to alleviate this, e.g. a list of vertices and a list of faces with indices to the list of faces.

◆ Triangle

template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using se::Triangle = typedef MeshFace<3, ColB, SemB>

◆ TriangleMesh

template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using se::TriangleMesh = typedef Mesh<Triangle<ColB, SemB> >

◆ Quad

template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using se::Quad = typedef MeshFace<4, ColB, SemB>

◆ QuadMesh

template<Colour ColB = Colour::Off, Semantics SemB = Semantics::Off>
using se::QuadMesh = typedef Mesh<Quad<ColB, SemB> >

◆ OccupancyData

◆ OccupancyColData

◆ OccupancySemData

◆ OccupancyColSemData

◆ TSDFData

◆ TSDFColData

◆ TSDFSemData

◆ TSDFColSemData

◆ MapD

template<se::Field FldT = se::Field::TSDF, se::Colour ColB = se::Colour::Off, se::Semantics SemB = se::Semantics::Off, se::Res ResT = se::Res::Single, int BlockSize = 8>
using se::MapD = typedef Map<Data<FldT, ColB, SemB>, ResT, BlockSize>

◆ OccupancyMap

template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using se::OccupancyMap = typedef Map<OccupancyData, ResT, BlockSize>

◆ OccupancyColMap

template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using se::OccupancyColMap = typedef Map<OccupancyColData, ResT, BlockSize>

◆ OccupancySemMap

template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using se::OccupancySemMap = typedef Map<OccupancySemData, ResT, BlockSize>

◆ OccupancyColSemMap

template<se::Res ResT = se::Res::Multi, int BlockSize = 8>
using se::OccupancyColSemMap = typedef Map<OccupancyColSemData, ResT, BlockSize>

◆ TSDFMap

template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using se::TSDFMap = typedef Map<TSDFData, ResT, BlockSize>

◆ TSDFColMap

template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using se::TSDFColMap = typedef Map<TSDFColData, ResT, BlockSize>

◆ TSDFSemMap

template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using se::TSDFSemMap = typedef Map<TSDFSemData, ResT, BlockSize>

◆ TSDFColSemMap

template<se::Res ResT = se::Res::Single, int BlockSize = 8>
using se::TSDFColSemMap = typedef Map<TSDFColSemData, ResT, BlockSize>

◆ key_t

key = 1 bit buffer + 57 bits of morton code + 6 bits of scale information The maxium scale is limited by 57 / 3 = 19 scales

Note
uint64_t has 64 bits We'll use the key to store both, the Morton code and scale information In 3D three bits are required to encode the Morton code at each scale. 21 scales -> 3 bits * 21 = 63 bits; 64 bits - 63 bits = 1 bit to encode unsigned int up to 21 [not possible] 20 scales -> 3 bits * 20 = 60 bits; 64 bits - 60 bits = 4 bits to encode unsigned int up to 20 [not possible] 19 scales -> 3 bits * 19 = 57 bits; 64 bits - 57 bits = 7 bits to encode unsigend int up to 19 [possible]

The tree cannot allocate any depth further than 19 allowing a map size = 524288 * map resolution That is a maximum map size of 1 x 1 x 1 km^3 at 2 mm resolution The type of the Key i.e. code | scale

◆ code_t

The type of the Morton code.

◆ scale_t

The type of the scale in the morton code.

◆ idx_t

Child or voxel index type.

◆ field_t

The type of the stored field (e.g. TSDF, ESDF or occupancy)

◆ field_vec_t

typedef Eigen::Matrix<field_t, 3, 1> se::field_vec_t

◆ weight_t

The type of the field type weight.

◆ timestamp_t

The type of the time stamp.

◆ colour_t

The type of the colour.

◆ semantics_t

The type of the semantic class.

◆ SubmapVec

template<typename MapT >
using se::SubmapVec = typedef std::vector<Submap<MapT>, Eigen::aligned_allocator<Submap<MapT> >>

◆ SubmapUnordMap

template<typename KeyT , typename MapT >
using se::SubmapUnordMap = typedef std::unordered_map<KeyT, Submap<MapT>, std::hash<KeyT>, std::equal_to<KeyT>, Eigen::aligned_allocator<std::pair<const KeyT, Submap<MapT> >> >

Enumeration Type Documentation

◆ VarianceState

Enumerator
Constant 
Gradient 
Undefined 

◆ RayState

Enumerator
FreeSpace 
Transition 
Occupied 
Undefined 

◆ UncertaintyModel

Enumerator
Linear 
Quadratic 

◆ Field

Enumerator
TSDF 
Occupancy 

◆ Colour

Enumerator
Off 
On 

◆ Semantics

Enumerator
Off 
On 

◆ Res

enum class se::Res
strong
Enumerator
Single 
Multi 

◆ Integ

Enumerator
Simple 
LiDAR 
PinholeCamera 

◆ Safe

Enumerator
On 
Off 

◆ AllocMeth

Enumerator
Raycasting 
VoxelCarving 

◆ Rep

enum class se::Rep
strong
Enumerator
Surface 
Freespace 

◆ Sort

The enum classes to define the sorting templates.

Enumerator
SmallToLarge 
LargeToSmall 

◆ ReaderType

Enumerator
OPENNI 

Use the se::OpenNIReader.

RAW 

Use the se::RAWReader.

TUM 

Use the se::TUMReader.

INTERIORNET 

Use the se::InteriorNetReader.

NEWERCOLLEGE 

Use the se::NewerCollegeReader.

LEICA 

Use the se::LeicaReader.

UNKNOWN 

◆ ReaderStatus

The result of trying to read a depth/RGB image or a pose.

Enumerator
ok 

Data read successfully.

skip 

Temporary data read error.

Further reads might succeed. Typically used to indicate an invalid image or pose.

eof 

End of dataset reached.

error 

Fatal data read error.

No further read should be attempted. Typically used to indicate that the dataset could not be read at all or no camera was found.

Function Documentation

◆ depth_to_rgba()

void se::depth_to_rgba ( RGBA depth_RGBA_image_data,
const float depth_image_data,
const Eigen::Vector2i &  depth_image_res,
const float  min_depth,
const float  max_depth 
)

Convert a depth image to an RGBA image to allow visualizing it.

The depth image is scaled using the minimum and maximum depth values to increase contrast.

Parameters
[in]depth_RGBA_image_dataPointer to the ouput RGBA image data.
[in]depth_image_dataPointer to the input depth image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]min_depthThe minimum possible depth value.
[in]max_depthThe maximum possible depth value.

◆ scale_colour()

static RGB se::scale_colour ( const int  scale)
inlinestatic

Return the color from se::colours::scale that should be used to visualize the supplied scale.

If the scale is greater or equal to the number of colours in se::colours::scale then the last colour will be returned.

◆ save_depth_png() [1/2]

int se::save_depth_png ( const float depth_image_data,
const Eigen::Vector2i &  depth_image_res,
const std::string &  filename,
const float  scale = 1000.0f 
)

Save a depth image with depth values in metres to a PNG.

The data is saved in a 16-bit image with the depth values scaled by scale.

Parameters
[in]depth_image_dataPointer to the float image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PNG file to create.
[in]scaleThe number each float depth value is multiplied with before being converted to a uint16_t. By default the resulting PNG contains depth values in millimetres.
Returns
0 on success, nonzero on error.

◆ save_depth_png() [2/2]

int se::save_depth_png ( const uint16_t depth_image_data,
const Eigen::Vector2i &  depth_image_res,
const std::string &  filename 
)

Save a depth image with depth values in millimetres to a PNG.

Parameters
[in]depth_image_dataPointer to the 16-bit image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PNG file to create.
Returns
0 on success, nonzero on error.

◆ load_depth_png() [1/2]

int se::load_depth_png ( float **  depth_image_data,
Eigen::Vector2i &  depth_image_res,
const std::string &  filename,
const float  inverse_scale = 1.0f/1000.0f 
)

Load a PNG depth image into a buffer with depth values in metres.

Parameters
[in]depth_image_dataPointer to the loaded float image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PNG file to load.
[in]inverse_scaleThe number each uint16_t depth value is multiplied with in order to convert it to a float value in metres. By default the resulting PNG is assumed to contain depth values in millimetres.
Returns
0 on success, nonzero on error.
Warning
The memory for the image buffer is allocated inside this function. delete[] *depth_image_data must be called to free the memory. width * height * sizeof(float) bytes are allocated.

◆ load_depth_png() [2/2]

int se::load_depth_png ( uint16_t **  depth_image_data,
Eigen::Vector2i &  depth_image_res,
const std::string &  filename 
)

Load a PNG depth image into a buffer with depth values in millimetres.

Parameters
[in]depth_image_dataPointer to the loaded 16-bit image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PNG file to load.
Returns
0 on success, nonzero on error.
Warning
The memory for the image buffer is allocated inside this function. delete[] *depth_image_data must be called to free the memory. width * height * sizeof(uint16_t) bytes are allocated.

◆ save_depth_pgm() [1/2]

int se::save_depth_pgm ( const float depth_image_data,
const Eigen::Vector2i &  depth_image_res,
const std::string &  filename,
const float  scale = 1000.0f 
)

Save a depth image with depth values in metres to a P2 PGM.

The data is saved in a 16-bit image with the depth values scaled by scale.

Note
For documentation on the structure of P2 PGM images see here https://en.wikipedia.org/wiki/Netpbm_format
Parameters
[in]depth_image_dataPointer to the float image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PGM file to create.
[in]scaleThe number each float depth value is multiplied with before being converted to a uint16_t. By default the resulting PNG contains depth values in millimetres.
Returns
0 on success, nonzero on error.

◆ save_depth_pgm() [2/2]

int se::save_depth_pgm ( const uint16_t depth_image_data,
const Eigen::Vector2i &  depth_image_res,
const std::string &  filename 
)

Save a depth image with depth values in millimetres to a P2 PGM.

Note
For documentation on the structure of P2 PGM images see here https://en.wikipedia.org/wiki/Netpbm_format
Parameters
[in]depth_image_dataPointer to the 16-bit image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PGM file to create.
Returns
0 on success, nonzero on error.

◆ load_depth_pgm() [1/2]

int se::load_depth_pgm ( float **  depth_image_data,
Eigen::Vector2i &  depth_image_res,
const std::string &  filename,
const float  inverse_scale = 1.0f/1000.0f 
)

Load a P2 PGM depth image into a buffer with depth values in metres.

Parameters
[in]depth_image_dataPointer to the loaded float image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PGM file to load.
[in]inverse_scaleThe number each uint16_t depth value is multiplied with in order to convert it to a float value in metres. By default the resulting PNG is assumed to contain depth values in millimetres.
Returns
0 on success, nonzero on error.
Warning
The memory for the image buffer is allocated inside this function. delete[] *depth_image_data must be called to free the memory. width * height * sizeof(float) bytes are allocated.

◆ load_depth_pgm() [2/2]

int se::load_depth_pgm ( uint16_t **  depth_image_data,
Eigen::Vector2i &  depth_image_res,
const std::string &  filename 
)

Load a P2 PGM depth image into a buffer with depth values in millimeters.

Parameters
[in]depth_image_dataPointer to the loaded 16-bit image data.
[in]depth_image_resResolution of the depth image in pixels (width and height).
[in]filenameThe name of the PGM file to load.
Returns
0 on success, nonzero on error.
Warning
The memory for the image buffer is allocated inside this function. delete[] *depth_image_data must be called to free the memory. width * height * sizeof(uint16_t) bytes are allocated.

◆ round_pixel()

static Eigen::Vector2i se::round_pixel ( const Eigen::Vector2f &  pixel_f)
inlinestatic

◆ convert_to_output_depth_img() [1/2]

static void se::convert_to_output_depth_img ( const se::Image< float > &  input_depth_img,
RGBA output_depth_img_data 
)
inlinestatic

◆ convert_to_output_depth_img() [2/2]

static void se::convert_to_output_depth_img ( const se::Image< float > &  input_depth_img,
const float  min_depth,
const float  max_depth,
RGBA output_depth_img_data 
)
inlinestatic

◆ Measurement()

template<typename SensorT , typename T >
se::Measurement ( const Image< T > &  ,
const SensorT ,
const Eigen::Isometry3f &   
) -> Measurement< SensorT, T >

◆ Measurements() [1/3]

◆ Measurements() [2/3]

◆ Measurements() [3/3]

◆ compute_three_sigma()

template<typename ConfigT >
float se::compute_three_sigma ( const field_t  depth_value,
const float  sigma_min,
const float  sigma_max,
const ConfigT  config 
)

Compute the estimated uncertainty boundary for a given depth measurement.

Parameters
[in]depth_valueThe measured depth of the depth image.
Returns
Three sigma uncertainty.

◆ compute_tau()

template<typename ConfigT >
float se::compute_tau ( const field_t  depth_value,
const float  tau_min,
const float  tau_max,
const ConfigT  config 
)

Compute the estimated wall thickness tau for a given depth measurement.

Parameters
[in]depth_valueThe measured depth of the depth image.
Returns
The estimated wall thickness.

◆ quad_to_triangle_mesh()

template<Colour ColB, Semantics SemB>
TriangleMesh< ColB, SemB > se::quad_to_triangle_mesh ( const QuadMesh< ColB, SemB > &  quad_mesh)

Return a triangle mesh containig two triangles for each face of quad_mesh.

◆ octree_structure_mesh()

template<typename OctreeT >
OctreeT::StructureMesh se::octree_structure_mesh ( OctreeT octree,
const bool  only_leaves = true 
)

Return a mesh of the octants of octree.

Only leaf octants will be contained in the mesh if only_leaves is true.

◆ set_invalid() [1/3]

template<Field FldT, Colour ColB, Semantics SemB>
void se::set_invalid ( Data< FldT, ColB, SemB > &  data)
inline

◆ set_invalid() [2/3]

template<Colour ColB, Semantics SemB>
void se::set_invalid ( Data< Field::TSDF, ColB, SemB > &  data)
inline

◆ set_invalid() [3/3]

template<Colour ColB, Semantics SemB>
void se::set_invalid ( Data< Field::Occupancy, ColB, SemB > &  data)
inline

◆ is_valid()

template<Field FldT, Colour ColB, Semantics SemB>
bool se::is_valid ( const Data< FldT, ColB, SemB > &  data)
inline

◆ get_field() [1/3]

template<Field FldT, Colour ColB, Semantics SemB>
field_t se::get_field ( const Data< FldT, ColB, SemB > &  data)
inline

◆ get_field() [2/3]

template<Colour ColB, Semantics SemB>
field_t se::get_field ( const Data< Field::TSDF, ColB, SemB > &  data)
inline

◆ get_field() [3/3]

template<Colour ColB, Semantics SemB>
field_t se::get_field ( const Data< Field::Occupancy, ColB, SemB > &  data)
inline

◆ is_inside() [1/3]

template<Field FldT, Colour ColB, Semantics SemB>
bool se::is_inside ( const Data< FldT, ColB, SemB > &  data)
inline

◆ is_inside() [2/3]

template<Colour ColB, Semantics SemB>
bool se::is_inside ( const Data< Field::TSDF, ColB, SemB > &  data)
inline

◆ is_inside() [3/3]

template<Colour ColB, Semantics SemB>
bool se::is_inside ( const Data< Field::Occupancy, ColB, SemB > &  data)
inline

◆ operator<<() [1/14]

std::ostream & se::operator<< ( std::ostream &  os,
const ColourData< Colour::Off >::Config &  c 
)

◆ operator<<() [2/14]

std::ostream & se::operator<< ( std::ostream &  os,
const ColourData< Colour::On >::Config &  c 
)

◆ operator<<() [3/14]

std::ostream & se::operator<< ( std::ostream &  os,
const FieldData< Field::Occupancy >::Config &  c 
)

◆ operator<<() [4/14]

std::ostream & se::operator<< ( std::ostream &  os,
const FieldData< Field::TSDF >::Config &  c 
)

◆ operator<<() [5/14]

std::ostream & se::operator<< ( std::ostream &  os,
const SemanticData< Semantics::Off >::Config &  c 
)

◆ operator<<() [6/14]

std::ostream & se::operator<< ( std::ostream &  os,
const SemanticData< Semantics::On >::Config &  c 
)

◆ operator<<() [7/14]

std::ostream & se::operator<< ( std::ostream &  os,
const LeicaLidar::Config c 
)

◆ operator<<() [8/14]

std::ostream & se::operator<< ( std::ostream &  os,
const OusterLidar::Config c 
)

◆ operator<<() [9/14]

std::ostream & se::operator<< ( std::ostream &  os,
const PinholeCamera::Config c 
)

◆ operator<<() [10/14]

std::ostream & se::operator<< ( std::ostream &  os,
const TrackerConfig c 
)

◆ operator<<() [11/14]

std::ostream & se::operator<< ( std::ostream &  os,
const AppConfig c 
)

◆ operator<<() [12/14]

template<typename MapT , typename SensorT >
std::ostream & se::operator<< ( std::ostream &  os,
const Config< MapT, SensorT > &  c 
)

◆ montage()

cv::Mat se::montage ( int  montage_width,
int  montage_height,
const std::vector< cv::Mat > &  images,
const std::vector< std::string > &  labels 
)

Create a montage of several images and overlay labels.

The montage image is filled with images in row-major order. If fewer than montage_width * montage_height images are supplied then the montage image will have some transparent regions. If fewer labels than images are provided then the last images won't have a label.

For montage_width = 3, montage_height = 2, 5 images and 3 labels the following montage will be created

Warning
It is assumed that the dimensions of all images are the same and that their type is CV_8UC4.
Parameters
[in]montage_widthThe width of the montage image in images.
[in]montage_heightThe height of the montage image in images.
[in]imagesThe images to montage.
[in]labelsThe labels corresponding to the images to montage.
Returns
A montage image from the supplied images and labels.

◆ create_reader()

Reader * se::create_reader ( const se::Reader::Config config)

Create the appropriate reader instance based on the configuration.

Parameters
[in]configThe pipeline configuration.
Returns
A pointer to an instance of a class derived from Reader.

◆ string_to_reader_type()

ReaderType se::string_to_reader_type ( const std::string &  s)

◆ reader_type_to_string()

std::string se::reader_type_to_string ( ReaderType  t)

◆ operator<<() [13/14]

std::ostream & se::operator<< ( std::ostream &  os,
const ReaderStatus s 
)

◆ operator<<() [14/14]

std::ostream & se::operator<< ( std::ostream &  os,
const Reader::Config c 
)

Variable Documentation

◆ perfstats

PerfStats se::perfstats
extern

◆ CODE_MASK

constexpr uint64_t se::CODE_MASK[]
constexpr
Initial value:
= {0x1ffffffffffffff,
0x1fffffffffffff8,
0x1ffffffffffffc0,
0x1fffffffffffe00,
0x1fffffffffff000,
0x1ffffffffff8000,
0x1fffffffffc0000,
0x1ffffffffe00000,
0x1ffffffff000000,
0x1fffffff8000000,
0x1ffffffc0000000,
0x1fffffe00000000,
0x1fffff000000000,
0x1ffff8000000000,
0x1fffc0000000000,
0x1ffe00000000000,
0x1ff000000000000,
0x1f8000000000000,
0x1c0000000000000}

The code mask for a given scale.

Generated using the following code:

MASK[0] = 0x1c0000000000000;
for (int i = 1; i < 19; ++i) {
MASK[i] = MASK[i-1] | (MASK[0] >> (i*3));
}
for (int i = 18; i >= 0; --i) {
std::bitset<64> b(MASK[i]);
std::cout << "0x" << std::hex << b.to_ullong() << "," << std::endl;
}

◆ SCALE_MASK

constexpr uint64_t se::SCALE_MASK = 0x1F
constexpr

11 111

◆ sample_offset_frac

Eigen::Vector3f se::sample_offset_frac = Eigen::Vector3f::Constant(0.5f)
inlinestatic

◆ e_delta

constexpr float se::e_delta = 0.1f
constexpr