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 | 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. | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | RGBDFrame () |
Default (empty) constructor. | |
RGBDFrame (const ImageMsg::ConstPtr &rgb_msg, const ImageMsg::ConstPtr &depth_msg, const CameraInfoMsg::ConstPtr &info_msg) | |
Constructor from ROS messages. | |
Static Public Member Functions | |
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. | |
Public Attributes | |
cv::Mat | depth_img |
Depth image in mm (16UC1). 0 = invalid data. | |
cv::Mat | descriptors |
Feature descriptor vectors. | |
std_msgs::Header | header |
Header taken from rgb_msg. | |
KeypointVector | keypoints |
2D keypoint locations | |
Matrix3fVector | kp_covariances |
3x3 mat of covariances | |
Vector3fVector | kp_means |
1x3 mat of 3D locations | |
BoolVector | kp_valid |
Is the z data valid? | |
image_geometry::PinholeCameraModel | model |
The intrinsic matrix which applies to both images. | |
int | n_valid_keypoints |
How many keypoints have usable 3D data. | |
cv::Mat | rgb_img |
RGB image (8UC3) | |
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 | 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 | 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 50 of file rgbd_frame.h.
Default (empty) constructor.
Definition at line 28 of file rgbd_frame.cpp.
ccny_rgbd::RGBDFrame::RGBDFrame | ( | const ImageMsg::ConstPtr & | rgb_msg, |
const ImageMsg::ConstPtr & | depth_msg, | ||
const CameraInfoMsg::ConstPtr & | info_msg | ||
) |
Constructor from ROS messages.
rgb_msg | 8UC3 ROS image message |
depth_msg | 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 33 of file rgbd_frame.cpp.
void ccny_rgbd::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 122 of file rgbd_frame.cpp.
void ccny_rgbd::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 247 of file rgbd_frame.cpp.
void ccny_rgbd::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 235 of file rgbd_frame.cpp.
void ccny_rgbd::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 64 of file rgbd_frame.cpp.
void ccny_rgbd::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 77 of file rgbd_frame.cpp.
double ccny_rgbd::RGBDFrame::getStdDevZ | ( | double | z | ) | const [protected] |
Calculates the std_dev(z) from z.
z | the z depth, in meters |
Definition at line 53 of file rgbd_frame.cpp.
double ccny_rgbd::RGBDFrame::getVarZ | ( | double | z | ) | const [protected] |
Calculates the var(z) from z.
z | the z depth, in meters |
Definition at line 58 of file rgbd_frame.cpp.
bool ccny_rgbd::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 373 of file rgbd_frame.cpp.
bool ccny_rgbd::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 314 of file rgbd_frame.cpp.
cv::Mat ccny_rgbd::RGBDFrame::depth_img |
Depth image in mm (16UC1). 0 = invalid data.
Definition at line 71 of file rgbd_frame.h.
Feature descriptor vectors.
Definition at line 81 of file rgbd_frame.h.
Header taken from rgb_msg.
Definition at line 69 of file rgbd_frame.h.
2D keypoint locations
Definition at line 80 of file rgbd_frame.h.
3x3 mat of covariances
Definition at line 85 of file rgbd_frame.h.
1x3 mat of 3D locations
Definition at line 84 of file rgbd_frame.h.
Is the z data valid?
Definition at line 83 of file 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)
Definition at line 78 of file rgbd_frame.h.
How many keypoints have usable 3D data.
Definition at line 87 of file rgbd_frame.h.
cv::Mat ccny_rgbd::RGBDFrame::rgb_img |
RGB image (8UC3)
Definition at line 70 of file rgbd_frame.h.
const double ccny_rgbd::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 153 of file rgbd_frame.h.