Auxiliarry class that holds together rgb and depth images. More...
#include <rgbd_frame.h>
Public Member Functions | |
void | computeDistributions (double max_z=5.5, double max_stdev_z=0.03) |
Computes the 3D means and covariances for all the detected keypoints. | |
void | computeDistributions (double max_z=5.5, double max_stdev_z=0.03) |
Computes the 3D means and covariances for all the detected keypoints. | |
void | constructDensePointCloud (PointCloudT &cloud, double max_z=5.5, double max_stdev_z=0.03) const |
constructs a point cloud from the RGB and depth images | |
void | constructDensePointCloud (PointCloudT &cloud, double max_z=5.5, double max_stdev_z=0.03) const |
constructs a point cloud from the RGB and depth images | |
void | constructFeaturePointCloud (PointCloudFeature &cloud) |
Computes the 3D means and covariances for all the valid detected keypoints. | |
void | constructFeaturePointCloud (PointCloudFeature &cloud) |
Computes the 3D means and covariances for all the valid detected keypoints. | |
void | getPointsDist (std::vector< std::vector< float > > points, std::vector< std::vector< double > > *dists) |
void | getPointsDist (std::vector< std::vector< float > > points, std::vector< std::vector< double > > *dists) |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | RGBDFrame () |
Default (empty) constructor. | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | RGBDFrame () |
Default (empty) constructor. | |
RGBDFrame (const RGBDFrame &other) | |
RGBDFrame (const RGBDFrame &other) | |
RGBDFrame (const cv::Mat &rgb_img_in, const cv::Mat &depth_img_in, const cv::Mat &intr_in, const Header &header_in) | |
Constructor from ROS messages. | |
RGBDFrame (const cv::Mat &rgb_img_in, const cv::Mat &depth_img_in, const cv::Mat &intr_in, const Header &header_in) | |
Constructor from ROS messages. | |
RGBDFrame (const cv::Mat &rgb_img_in, const cv::Mat &depth_img_in, const cv::Mat &intr_in, const cv::Mat &dist_in, const Header &header_in) | |
RGBDFrame (const cv::Mat &rgb_img_in, const cv::Mat &depth_img_in, const cv::Mat &intr_in, const cv::Mat &dist_in, const Header &header_in) | |
Static Public Member Functions | |
static bool | load (RGBDFrame &frame, const std::string &path) |
Loads the RGBD frame from disk. | |
static bool | load (RGBDFrame &frame, const std::string &path) |
Loads the RGBD frame from disk. | |
static bool | save (const RGBDFrame &frame, const std::string &path) |
Saves the RGBD frame to disk. | |
static bool | save (const RGBDFrame &frame, const std::string &path) |
Saves the RGBD frame to disk. | |
Public Attributes | |
cv::Mat | depth_img |
Depth image in mm (16UC1). 0 = invalid data. | |
cv::Mat | descriptors |
Feature descriptor vectors. | |
cv::Mat | dist |
Header | header |
Header taken from rgb_msg. | |
int | index |
cv::Mat | intr |
KeypointVector | keypoints |
The intrinsic matrix which applies to both images. | |
Matrix3fVector | kp_covariances |
3x3 mat of covariances | |
Vector3fVector | kp_means |
1x3 mat of 3D locations | |
BoolVector | kp_valid |
Is the z data valid? | |
int | n_valid_keypoints |
How many keypoints have usable 3D data. | |
cv::Mat | rgb_img |
RGB image (8UC3) | |
bool | used |
Protected Member Functions | |
void | getGaussianDistribution (int u, int v, double &z_mean, double &z_var) const |
Calculates the z distribution (mean and variance) for a given pixel. | |
void | getGaussianDistribution (int u, int v, double &z_mean, double &z_var) const |
Calculates the z distribution (mean and variance) for a given pixel. | |
void | getGaussianMixtureDistribution (int u, int v, double &z_mean, double &z_var) const |
Calculates the GMM z distribution (mean and variance) for a given pixel. | |
void | getGaussianMixtureDistribution (int u, int v, double &z_mean, double &z_var) const |
Calculates the GMM z distribution (mean and variance) for a given pixel. | |
double | getStdDevZ (double z) const |
Calculates the std_dev(z) from z. | |
double | getStdDevZ (double z) const |
Calculates the std_dev(z) from z. | |
double | getVarZ (double z) const |
Calculates the var(z) from z. | |
double | getVarZ (double z) const |
Calculates the var(z) from z. | |
Static Protected Attributes | |
static const double | Z_STDEV_CONSTANT = 0.001425 |
Constant for calculating std_dev(z) |
Auxiliarry class that holds together rgb and depth images.
The class also holds the detected keypoints and their 3D distributions. Keypoints, descriptos, and kp_* are indexed the same way and may include invalid points. An invalid keypoint occurs when:
Definition at line 47 of file include/rgbdtools/rgbd_frame.h.
Default (empty) constructor.
Definition at line 28 of file rgbd_frame.cpp.
rgbdtools::RGBDFrame::RGBDFrame | ( | const RGBDFrame & | other | ) |
Definition at line 33 of file rgbd_frame.cpp.
rgbdtools::RGBDFrame::RGBDFrame | ( | const cv::Mat & | rgb_img_in, |
const cv::Mat & | depth_img_in, | ||
const cv::Mat & | intr_in, | ||
const Header & | header_in | ||
) |
Constructor from ROS messages.
rgb_img_in | 8UC3 image message |
depth_img_in | 16UC1 ROS depth message (in mm, 0 = invalid data) |
info_msg | ROS camera info message, assumed no distortion, applies to both images |
Definition at line 54 of file rgbd_frame.cpp.
rgbdtools::RGBDFrame::RGBDFrame | ( | const cv::Mat & | rgb_img_in, |
const cv::Mat & | depth_img_in, | ||
const cv::Mat & | intr_in, | ||
const cv::Mat & | dist_in, | ||
const Header & | header_in | ||
) |
Definition at line 79 of file rgbd_frame.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW rgbdtools::RGBDFrame::RGBDFrame | ( | ) |
Default (empty) constructor.
rgbdtools::RGBDFrame::RGBDFrame | ( | const RGBDFrame & | other | ) |
rgbdtools::RGBDFrame::RGBDFrame | ( | const cv::Mat & | rgb_img_in, |
const cv::Mat & | depth_img_in, | ||
const cv::Mat & | intr_in, | ||
const Header & | header_in | ||
) |
Constructor from ROS messages.
rgb_img_in | 8UC3 image message |
depth_img_in | 16UC1 ROS depth message (in mm, 0 = invalid data) |
info_msg | ROS camera info message, assumed no distortion, applies to both images |
rgbdtools::RGBDFrame::RGBDFrame | ( | const cv::Mat & | rgb_img_in, |
const cv::Mat & | depth_img_in, | ||
const cv::Mat & | intr_in, | ||
const cv::Mat & | dist_in, | ||
const Header & | header_in | ||
) |
void rgbdtools::RGBDFrame::computeDistributions | ( | double | max_z = 5.5 , |
double | max_stdev_z = 0.03 |
||
) |
Computes the 3D means and covariances for all the detected keypoints.
Some features will be marked as invalid.
max_z | [m] features with z bigger than this will be marked as invalid |
max_stdev_z | [m] features with std_dev(z) bigger than this will be marked as invalid |
Definition at line 195 of file rgbd_frame.cpp.
void rgbdtools::RGBDFrame::computeDistributions | ( | double | max_z = 5.5 , |
double | max_stdev_z = 0.03 |
||
) |
Computes the 3D means and covariances for all the detected keypoints.
Some features will be marked as invalid.
max_z | [m] features with z bigger than this will be marked as invalid |
max_stdev_z | [m] features with std_dev(z) bigger than this will be marked as invalid |
void rgbdtools::RGBDFrame::constructDensePointCloud | ( | PointCloudT & | cloud, |
double | max_z = 5.5 , |
||
double | max_stdev_z = 0.03 |
||
) | const |
constructs a point cloud from the RGB and depth images
cloud | the reference to the point cloud to be constructed |
max_z | [m] points with z bigger than this will be marked as NaN |
max_stdev_z | [m] points with std_dev(z) bigger than this will be marked as NaN |
Definition at line 357 of file rgbd_frame.cpp.
void rgbdtools::RGBDFrame::constructDensePointCloud | ( | PointCloudT & | cloud, |
double | max_z = 5.5 , |
||
double | max_stdev_z = 0.03 |
||
) | const |
constructs a point cloud from the RGB and depth images
cloud | the reference to the point cloud to be constructed |
max_z | [m] points with z bigger than this will be marked as NaN |
max_stdev_z | [m] points with std_dev(z) bigger than this will be marked as NaN |
void rgbdtools::RGBDFrame::constructFeaturePointCloud | ( | PointCloudFeature & | cloud | ) |
Computes the 3D means and covariances for all the valid detected keypoints.
cloud | Reference to the point cloud to be constructed |
Definition at line 308 of file rgbd_frame.cpp.
void rgbdtools::RGBDFrame::constructFeaturePointCloud | ( | PointCloudFeature & | cloud | ) |
Computes the 3D means and covariances for all the valid detected keypoints.
cloud | Reference to the point cloud to be constructed |
void rgbdtools::RGBDFrame::getGaussianDistribution | ( | int | u, |
int | v, | ||
double & | z_mean, | ||
double & | z_var | ||
) | const [protected] |
Calculates the z distribution (mean and variance) for a given pixel.
Calculation is based on the standard quadratic model. See:
Khoshelham, K.; Elberink, S.O. Accuracy and Resolution of Kinect Depth Data for Indoor Mapping Applications. Sensors 2012, 12, 1437-1454.
u | the pixel u-coordinate |
v | the pixel v-coordinate |
z_mean | the mean of the distribution (will be the same az the z of the pixel), in meters |
z_var | var(z), will a quadratic function of the mean, in meters^2 |
Definition at line 137 of file rgbd_frame.cpp.
void rgbdtools::RGBDFrame::getGaussianDistribution | ( | int | u, |
int | v, | ||
double & | z_mean, | ||
double & | z_var | ||
) | const [protected] |
Calculates the z distribution (mean and variance) for a given pixel.
Calculation is based on the standard quadratic model. See:
Khoshelham, K.; Elberink, S.O. Accuracy and Resolution of Kinect Depth Data for Indoor Mapping Applications. Sensors 2012, 12, 1437-1454.
u | the pixel u-coordinate |
v | the pixel v-coordinate |
z_mean | the mean of the distribution (will be the same az the z of the pixel), in meters |
z_var | var(z), will a quadratic function of the mean, in meters^2 |
void rgbdtools::RGBDFrame::getGaussianMixtureDistribution | ( | int | u, |
int | v, | ||
double & | z_mean, | ||
double & | z_var | ||
) | const [protected] |
Calculates the GMM z distribution (mean and variance) for a given pixel.
Calculation is based on a Gaussian Mixture Model on top of the standard quadratic model. The neigboring pixels contribute different wights to the mixture. See:
Dryanovski et al ICRA2013 papaer
u | the pixel u-coordinate |
v | the pixel v-coordinate |
z_mean | the mean of the distribution (will be the same az the z of the pixel), in meters |
z_var | var(z), will a quadratic function of the mean, in meters^2 |
void rgbdtools::RGBDFrame::getGaussianMixtureDistribution | ( | int | u, |
int | v, | ||
double & | z_mean, | ||
double & | z_var | ||
) | const [protected] |
Calculates the GMM z distribution (mean and variance) for a given pixel.
Calculation is based on a Gaussian Mixture Model on top of the standard quadratic model. The neigboring pixels contribute different wights to the mixture. See:
Dryanovski et al ICRA2013 papaer
u | the pixel u-coordinate |
v | the pixel v-coordinate |
z_mean | the mean of the distribution (will be the same az the z of the pixel), in meters |
z_var | var(z), will a quadratic function of the mean, in meters^2 |
Definition at line 150 of file rgbd_frame.cpp.
void rgbdtools::RGBDFrame::getPointsDist | ( | std::vector< std::vector< float > > | points, |
std::vector< std::vector< double > > * | dists | ||
) |
Definition at line 324 of file rgbd_frame.cpp.
void rgbdtools::RGBDFrame::getPointsDist | ( | std::vector< std::vector< float > > | points, |
std::vector< std::vector< double > > * | dists | ||
) |
double rgbdtools::RGBDFrame::getStdDevZ | ( | double | z | ) | const [protected] |
Calculates the std_dev(z) from z.
z | the z depth, in meters |
Definition at line 126 of file rgbd_frame.cpp.
double rgbdtools::RGBDFrame::getStdDevZ | ( | double | z | ) | const [protected] |
Calculates the std_dev(z) from z.
z | the z depth, in meters |
double rgbdtools::RGBDFrame::getVarZ | ( | double | z | ) | const [protected] |
Calculates the var(z) from z.
z | the z depth, in meters |
double rgbdtools::RGBDFrame::getVarZ | ( | double | z | ) | const [protected] |
Calculates the var(z) from z.
z | the z depth, in meters |
Definition at line 131 of file rgbd_frame.cpp.
bool rgbdtools::RGBDFrame::load | ( | RGBDFrame & | frame, |
const std::string & | path | ||
) | [static] |
Loads the RGBD frame from disk.
Loands the RGB and depth images from png, and the header and intrinsic matrix from .yml files.
frame | Reference to the frame being loaded |
path | The path to the folder where everything was saved. |
true | Successfully loaded the data |
false | Loading failed - for example, directory not found |
Definition at line 486 of file rgbd_frame.cpp.
static bool rgbdtools::RGBDFrame::load | ( | RGBDFrame & | frame, |
const std::string & | path | ||
) | [static] |
Loads the RGBD frame from disk.
Loands the RGB and depth images from png, and the header and intrinsic matrix from .yml files.
frame | Reference to the frame being loaded |
path | The path to the folder where everything was saved. |
true | Successfully loaded the data |
false | Loading failed - for example, directory not found |
bool rgbdtools::RGBDFrame::save | ( | const RGBDFrame & | frame, |
const std::string & | path | ||
) | [static] |
Saves the RGBD frame to disk.
Saves the RGB and depth images as png, and the header and intrinsic matrix as .yml files. Parent directory must exist prior to calling this function, or function will fail.
frame | Reference to the frame being saved |
path | The path to the folder where everything will be stored |
true | Successfully saved the data |
false | Saving failed - for example, cannot create directory |
Definition at line 435 of file rgbd_frame.cpp.
static bool rgbdtools::RGBDFrame::save | ( | const RGBDFrame & | frame, |
const std::string & | path | ||
) | [static] |
Saves the RGBD frame to disk.
Saves the RGB and depth images as png, and the header and intrinsic matrix as .yml files. Parent directory must exist prior to calling this function, or function will fail.
frame | Reference to the frame being saved |
path | The path to the folder where everything will be stored |
true | Successfully saved the data |
false | Saving failed - for example, cannot create directory |
cv::Mat rgbdtools::RGBDFrame::depth_img |
Depth image in mm (16UC1). 0 = invalid data.
Definition at line 80 of file include/rgbdtools/rgbd_frame.h.
Feature descriptor vectors.
Definition at line 91 of file include/rgbdtools/rgbd_frame.h.
cv::Mat rgbdtools::RGBDFrame::dist |
Definition at line 82 of file include/rgbdtools/rgbd_frame.h.
Header taken from rgb_msg.
Definition at line 78 of file include/rgbdtools/rgbd_frame.h.
Definition at line 76 of file include/rgbdtools/rgbd_frame.h.
cv::Mat rgbdtools::RGBDFrame::intr |
Definition at line 81 of file include/rgbdtools/rgbd_frame.h.
The intrinsic matrix which applies to both images.
It's assumed that the images are already rectified and in the same camera frame(RGB) 2D keypoint locations
Definition at line 90 of file include/rgbdtools/rgbd_frame.h.
3x3 mat of covariances
Definition at line 95 of file include/rgbdtools/rgbd_frame.h.
1x3 mat of 3D locations
Definition at line 94 of file include/rgbdtools/rgbd_frame.h.
Is the z data valid?
Definition at line 93 of file include/rgbdtools/rgbd_frame.h.
How many keypoints have usable 3D data.
Definition at line 97 of file include/rgbdtools/rgbd_frame.h.
cv::Mat rgbdtools::RGBDFrame::rgb_img |
RGB image (8UC3)
Definition at line 79 of file include/rgbdtools/rgbd_frame.h.
Definition at line 98 of file include/rgbdtools/rgbd_frame.h.
static const double rgbdtools::RGBDFrame::Z_STDEV_CONSTANT = 0.001425 [static, protected] |
Constant for calculating std_dev(z)
Khoshelham, K.; Elberink, S.O. Accuracy and Resolution of Kinect Depth Data for Indoor Mapping Applications. Sensors 2012, 12, 1437-1454.
Definition at line 163 of file include/rgbdtools/rgbd_frame.h.