38 using namespace Eigen;
43 DiscreteFrustum::DiscreteFrustum(
int smoothing,
double bin_depth,
double max_dist) :
59 double mult = ground_truth / measurement;
99 double coeff0 = 1.0 - coeff1;
161 std::set<size_t> divisors;
162 for(
size_t i = 1; i <= num; i++)
174 std::set<size_t>::iterator low, prev;
175 low = divisors.lower_bound(ref);
176 if(low == divisors.end())
178 return *(--divisors.end());
180 else if(low == divisors.begin())
188 if((ref - *prev) <= (*low - ref))
200 double ratio = width /
static_cast<double>(height);
201 std::set<size_t> divisors = getDivisors(width);
202 double ref_bin_width = 8;
203 bin_width = getClosestToRef(divisors, ref_bin_width);
204 divisors = getDivisors(height);
205 double ref_bin_height = ref_bin_width / ratio;
206 bin_height = getClosestToRef(divisors, ref_bin_height);
227 for(
size_t i = 0; i < frustums_.size(); ++i)
228 for(
size_t j = 0; j < frustums_[i].size(); ++j)
235 int bin_width,
int bin_height,
241 bin_width_(bin_width),
242 bin_height_(bin_height),
252 for(
size_t i = 0; i <
frustums_.size(); ++i) {
254 for(
size_t j = 0; j <
frustums_[i].size(); ++j)
264 for(
size_t y = 0; y <
frustums_.size(); ++y)
281 UASSERT(depth.type() == CV_16UC1 || depth.type() == CV_32FC1);
282 int factor =
width_ / depth.cols;
283 if(depth.type() == CV_32FC1)
285 #pragma omp parallel for 286 for(
int v = 0; v < depth.rows; ++v) {
287 for(
int u = 0; u < depth.cols; ++u) {
288 float & z = depth.at<
float>(v, u);
289 if(
uIsNan(z) || z == 0.0f)
299 #pragma omp parallel for 300 for(
int v = 0; v < depth.rows; ++v) {
301 for(
int u = 0; u < depth.cols; ++u) {
302 unsigned short & z = depth.at<
unsigned short>(v, u);
305 double zf = z * 0.001;
319 const cv::Mat& measurement)
325 UASSERT(ground_truth.type() == CV_16UC1 || ground_truth.type() == CV_32FC1);
326 UASSERT(measurement.type() == CV_16UC1 || measurement.type() == CV_32FC1);
328 bool isGroundTruthInMM = ground_truth.type()==CV_16UC1;
329 bool isMeasurementInMM = measurement.type()==CV_16UC1;
331 size_t num_training_examples = 0;
332 for(
int v = 0; v <
height_; ++v) {
333 for(
int u = 0; u <
width_; ++u) {
334 float gt = isGroundTruthInMM?float(ground_truth.at<
unsigned short>(v,u))*0.001:ground_truth.at<
float>(v,u);
337 float meas = isMeasurementInMM?float(measurement.at<
unsigned short>(v,u))*0.001:measurement.at<
float>(v,u);
343 ++num_training_examples;
349 return num_training_examples;
356 f.open(path.c_str(), ascii ? ios::in : ios::in | ios::binary);
358 cerr <<
"Failed to open " << path << endl;
369 f.open(path.c_str(), ascii?ios::out: ios::out | ios::binary);
371 cerr <<
"Failed to open " << path << endl;
380 out <<
"DiscreteDepthDistortionModel v01" << endl;
415 UDEBUG(
"buf=%s", buf.c_str());
416 assert(buf ==
"DiscreteDepthDistortionModel v01");
449 for(
size_t y = 0; y <
frustums_.size(); ++y) {
452 UDEBUG(
"Distortion Model: Frustum[%d][%d]", y,
x);
void serializeScalarASCII(T val, std::ostream &strm)
void deserializeASCII(std::istream &strm, Eigen::Matrix< S, T, U > *mat)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
void serialize(const Eigen::Matrix< S, T, U > &mat, std::ostream &strm)
void undistort(double *z) const
virtual ~DiscreteDepthDistortionModel()
DiscreteFrustum & frustum(int y, int x)
static size_t getClosestToRef(const std::set< size_t > &divisors, const double &ref)
Basic mathematics functions.
void deserialize(std::istream &in, bool ascii)
std::string getExtension()
std::vector< std::vector< DiscreteFrustum * > > frustums_
frustums_[y][x]
Eigen::VectorXf multipliers_
Eigen::VectorXf total_denominators_
void deserialize(std::istream &in, bool ascii)
#define UASSERT(condition)
void interpolatedUndistort(double *z) const
static void getBinSize(const size_t &width, const size_t &height, size_t &bin_width, size_t &bin_height)
GLM_FUNC_DECL genType floor(genType const &x)
void serializeScalar(T val, std::ostream &strm)
void save(const std::string &path) const
void addExample(int v, int u, double ground_truth, double measurement)
void load(const std::string &path)
DiscreteFrustum(int smoothing=1, double bin_depth=1.0, double max_dist=10.0)
void deserializeScalarASCII(std::istream &strm, T *val)
DiscreteDepthDistortionModel()
Eigen::VectorXf total_numerators_
void serializeASCII(const Eigen::Matrix< S, T, U > &mat, std::ostream &strm)
size_t accumulate(const cv::Mat &ground_truth, const cv::Mat &measurement)
void serialize(std::ostream &out, bool ascii) const
int bin_width_
Width of each bin in pixels.
int index(double z) const
int bin_height_
Height of each bin in pixels.
DiscreteDepthDistortionModel & operator=(const DiscreteDepthDistortionModel &other)
ULogger class and convenient macros.
void serialize(std::ostream &out, bool ascii) const
void undistort(cv::Mat &depth) const
bool uIsNan(const T &value)
void deserializeScalar(std::istream &strm, T *val)
static std::set< size_t > getDivisors(const size_t &num)
GLM_FUNC_DECL genType ceil(genType const &x)
double bin_depth_
Depth of each bin in meters.
void deserialize(std::istream &strm, Eigen::Matrix< S, T, U > *mat)
void addExample(double ground_truth, double measurement)