|
void | compareDists (const std::vector< double > &imageDists, const std::vector< double > &depthDists) const |
|
double | computeDistance (const cv::Point &pointImage, const cv::Mat &normal, const double distance) const |
|
void | computePointDists (const cv::Mat &normal, const double distance, const cv::Mat ®ion, const cv::Rect &roi, std::vector< double > &depthDists, std::vector< double > &imageDists) |
|
void | computeROI (const cv::Mat &depth, const std::vector< cv::Point2f > &points, cv::Mat ®ion, cv::Rect &roi) const |
|
void | getPlane (const size_t index, cv::Mat &normal, double &distance) const |
|
bool | loadCalibration () |
|
bool | readFiles (const std::vector< std::string > &files) |
|
void | storeCalibration (const double depthShift) const |
|
Definition at line 816 of file kinect2_calibration.cpp.
DepthCalibration::DepthCalibration |
( |
const std::string & |
path, |
|
|
const cv::Size & |
boardDims, |
|
|
const float |
boardSize |
|
) |
| |
|
inline |
DepthCalibration::~DepthCalibration |
( |
| ) |
|
|
inline |
void DepthCalibration::calibrate |
( |
| ) |
|
|
inline |
void DepthCalibration::compareDists |
( |
const std::vector< double > & |
imageDists, |
|
|
const std::vector< double > & |
depthDists |
|
) |
| const |
|
inlineprivate |
double DepthCalibration::computeDistance |
( |
const cv::Point & |
pointImage, |
|
|
const cv::Mat & |
normal, |
|
|
const double |
distance |
|
) |
| const |
|
inlineprivate |
void DepthCalibration::computePointDists |
( |
const cv::Mat & |
normal, |
|
|
const double |
distance, |
|
|
const cv::Mat & |
region, |
|
|
const cv::Rect & |
roi, |
|
|
std::vector< double > & |
depthDists, |
|
|
std::vector< double > & |
imageDists |
|
) |
| |
|
inlineprivate |
void DepthCalibration::computeROI |
( |
const cv::Mat & |
depth, |
|
|
const std::vector< cv::Point2f > & |
points, |
|
|
cv::Mat & |
region, |
|
|
cv::Rect & |
roi |
|
) |
| const |
|
inlineprivate |
void DepthCalibration::getPlane |
( |
const size_t |
index, |
|
|
cv::Mat & |
normal, |
|
|
double & |
distance |
|
) |
| const |
|
inlineprivate |
bool DepthCalibration::loadCalibration |
( |
| ) |
|
|
inlineprivate |
bool DepthCalibration::readFiles |
( |
const std::vector< std::string > & |
files | ) |
|
|
inlineprivate |
bool DepthCalibration::restore |
( |
| ) |
|
|
inline |
void DepthCalibration::storeCalibration |
( |
const double |
depthShift | ) |
const |
|
inlineprivate |
std::vector<cv::Point3f> DepthCalibration::board |
|
private |
cv::Mat DepthCalibration::cameraMatrix |
|
private |
double DepthCalibration::cx |
|
private |
double DepthCalibration::cy |
|
private |
cv::Mat DepthCalibration::distortion |
|
private |
double DepthCalibration::fx |
|
private |
double DepthCalibration::fy |
|
private |
std::vector<std::string> DepthCalibration::images |
|
private |
cv::Mat DepthCalibration::mapX |
|
private |
cv::Mat DepthCalibration::mapY |
|
private |
const std::string DepthCalibration::path |
|
private |
std::ofstream DepthCalibration::plot |
|
private |
std::vector<std::vector<cv::Point2f> > DepthCalibration::points |
|
private |
cv::Mat DepthCalibration::rotation |
|
private |
cv::Size DepthCalibration::size |
|
private |
cv::Mat DepthCalibration::translation |
|
private |
The documentation for this class was generated from the following file: