30 #ifndef DISCRETE_DEPTH_DISTORTION_MODEL_H 31 #define DISCRETE_DEPTH_DISTORTION_MODEL_H 37 #include <opencv2/opencv.hpp> 46 DiscreteFrustum(
int smoothing = 1,
double bin_depth = 1.0,
double max_dist = 10.0);
49 void addExample(
double ground_truth,
double measurement);
50 int index(
double z)
const;
51 void undistort(
double* z)
const;
52 void interpolatedUndistort(
double* z)
const;
53 void serialize(std::ostream& out,
bool ascii)
const;
72 static std::set<size_t> getDivisors(
const size_t &num);
75 static size_t getClosestToRef(
const std::set<size_t> &divisors,
const double &
ref);
78 static void getBinSize(
const size_t &width,
const size_t &height,
size_t &bin_width,
size_t &bin_height);
92 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);
95 void undistort(cv::Mat & depth)
const;
98 size_t accumulate(
const cv::Mat& ground_truth,
const cv::Mat& measurement);
99 void addExample(
int v,
int u,
double ground_truth,
double measurement);
100 void save(
const std::string& path)
const;
101 void load(
const std::string& path);
102 void serialize(std::ostream& out,
bool ascii)
const;
104 cv::Mat visualize(
const std::string& path =
"")
const;
111 return !frustums_.empty();
132 void deleteFrustums();
141 #endif // DISCRETE_DEPTH_DISTORTION_MODEL_H
void serialize(const Eigen::Matrix< S, T, U > &mat, std::ostream &strm)
std::vector< std::vector< DiscreteFrustum * > > frustums_
frustums_[y][x]
Eigen::VectorXf multipliers_
Eigen::VectorXf total_denominators_
DiscreteDepthDistortionModel()
Eigen::VectorXf total_numerators_
int bin_width_
Width of each bin in pixels.
int bin_height_
Height of each bin in pixels.
size_t getTrainingSamples() const
NearestNeighbourSearch< T >::Matrix load(const char *fileName)
double bin_depth_
Depth of each bin in meters.
void deserialize(std::istream &strm, Eigen::Matrix< S, T, U > *mat)