Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
clams::DiscreteDepthDistortionModel Class Reference

#include <discrete_depth_distortion_model.h>

List of all members.

Public Member Functions

size_t accumulate (const cv::Mat &ground_truth, const cv::Mat &measurement)
void addExample (int v, int u, double ground_truth, double measurement)
void deserialize (std::istream &in, bool ascii)
 DiscreteDepthDistortionModel ()
 DiscreteDepthDistortionModel (int width, int height, int bin_width=8, int bin_height=6, double bin_depth=2.0, int smoothing=1, double max_depth=10.0)
 DiscreteDepthDistortionModel (const DiscreteDepthDistortionModel &other)
int getHeight () const
size_t getTrainingSamples () const
int getWidth () const
bool isValid () const
void load (const std::string &path)
DiscreteDepthDistortionModeloperator= (const DiscreteDepthDistortionModel &other)
void save (const std::string &path) const
void serialize (std::ostream &out, bool ascii) const
void undistort (cv::Mat &depth) const
cv::Mat visualize (const std::string &path="") const
virtual ~DiscreteDepthDistortionModel ()

Static Public Member Functions

static void getBinSize (const size_t &width, const size_t &height, size_t &bin_width, size_t &bin_height)
static size_t getClosestToRef (const std::set< size_t > &divisors, const double &ref)
static std::set< size_t > getDivisors (const size_t &num)

Protected Member Functions

void deleteFrustums ()
DiscreteFrustumfrustum (int y, int x)
const DiscreteFrustumfrustum (int y, int x) const

Protected Attributes

double bin_depth_
 Depth of each bin in meters.
int bin_height_
 Height of each bin in pixels.
int bin_width_
 Width of each bin in pixels.
std::vector< std::vector
< DiscreteFrustum * > > 
frustums_
 frustums_[y][x]
int height_
 Image height.
UMutex mutex_
int num_bins_x_
int num_bins_y_
size_t training_samples_
int width_
 Image width.

Detailed Description

Definition at line 68 of file discrete_depth_distortion_model.h.


Constructor & Destructor Documentation

Definition at line 81 of file discrete_depth_distortion_model.h.

Definition at line 271 of file discrete_depth_distortion_model.cpp.

clams::DiscreteDepthDistortionModel::DiscreteDepthDistortionModel ( int  width,
int  height,
int  bin_width = 8,
int  bin_height = 6,
double  bin_depth = 2.0,
int  smoothing = 1,
double  max_depth = 10.0 
)

Definition at line 234 of file discrete_depth_distortion_model.cpp.

Definition at line 210 of file discrete_depth_distortion_model.cpp.


Member Function Documentation

size_t clams::DiscreteDepthDistortionModel::accumulate ( const cv::Mat &  ground_truth,
const cv::Mat &  measurement 
)

Returns the number of training examples it used from this pair. Thread-safe.

Definition at line 316 of file discrete_depth_distortion_model.cpp.

void clams::DiscreteDepthDistortionModel::addExample ( int  v,
int  u,
double  ground_truth,
double  measurement 
)

Definition at line 311 of file discrete_depth_distortion_model.cpp.

Definition at line 261 of file discrete_depth_distortion_model.cpp.

void clams::DiscreteDepthDistortionModel::deserialize ( std::istream &  in,
bool  ascii 
)

Definition at line 408 of file discrete_depth_distortion_model.cpp.

DiscreteFrustum & clams::DiscreteDepthDistortionModel::frustum ( int  y,
int  x 
) [protected]

Definition at line 458 of file discrete_depth_distortion_model.cpp.

const DiscreteFrustum & clams::DiscreteDepthDistortionModel::frustum ( int  y,
int  x 
) const [protected]

Definition at line 467 of file discrete_depth_distortion_model.cpp.

void clams::DiscreteDepthDistortionModel::getBinSize ( const size_t &  width,
const size_t &  height,
size_t &  bin_width,
size_t &  bin_height 
) [static]

Definition at line 199 of file discrete_depth_distortion_model.cpp.

size_t clams::DiscreteDepthDistortionModel::getClosestToRef ( const std::set< size_t > &  divisors,
const double &  ref 
) [static]

Definition at line 172 of file discrete_depth_distortion_model.cpp.

std::set< size_t > clams::DiscreteDepthDistortionModel::getDivisors ( const size_t &  num) [static]

Definition at line 159 of file discrete_depth_distortion_model.cpp.

Definition at line 107 of file discrete_depth_distortion_model.h.

Definition at line 108 of file discrete_depth_distortion_model.h.

Definition at line 106 of file discrete_depth_distortion_model.h.

Definition at line 109 of file discrete_depth_distortion_model.h.

void clams::DiscreteDepthDistortionModel::load ( const std::string &  path)

Definition at line 350 of file discrete_depth_distortion_model.cpp.

DiscreteDepthDistortionModel & clams::DiscreteDepthDistortionModel::operator= ( const DiscreteDepthDistortionModel other)

Definition at line 215 of file discrete_depth_distortion_model.cpp.

void clams::DiscreteDepthDistortionModel::save ( const std::string &  path) const

Definition at line 363 of file discrete_depth_distortion_model.cpp.

void clams::DiscreteDepthDistortionModel::serialize ( std::ostream &  out,
bool  ascii 
) const

Definition at line 376 of file discrete_depth_distortion_model.cpp.

void clams::DiscreteDepthDistortionModel::undistort ( cv::Mat &  depth) const

Definition at line 276 of file discrete_depth_distortion_model.cpp.

cv::Mat clams::DiscreteDepthDistortionModel::visualize ( const std::string &  path = "") const

Definition at line 42 of file discrete_depth_distortion_model_helpers.cpp.


Member Data Documentation

Depth of each bin in meters.

Definition at line 124 of file discrete_depth_distortion_model.h.

Height of each bin in pixels.

Definition at line 122 of file discrete_depth_distortion_model.h.

Width of each bin in pixels.

Definition at line 120 of file discrete_depth_distortion_model.h.

std::vector< std::vector<DiscreteFrustum*> > clams::DiscreteDepthDistortionModel::frustums_ [protected]

frustums_[y][x]

Definition at line 128 of file discrete_depth_distortion_model.h.

Image height.

Definition at line 118 of file discrete_depth_distortion_model.h.

Definition at line 136 of file discrete_depth_distortion_model.h.

Definition at line 125 of file discrete_depth_distortion_model.h.

Definition at line 126 of file discrete_depth_distortion_model.h.

Definition at line 130 of file discrete_depth_distortion_model.h.

Image width.

Definition at line 116 of file discrete_depth_distortion_model.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:40