Namespaces | Enumerations | Functions
rgbd_util.h File Reference
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/filters/voxel_grid.h>
#include <opencv2/opencv.hpp>
#include "rgbdtools/types.h"
Include dependency graph for rgbdtools_git/include/rgbdtools/rgbd_util.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  rgbdtools

Enumerations

enum  rgbdtools::DepthFitMode {
  rgbdtools::DEPTH_FIT_LINEAR, rgbdtools::DEPTH_FIT_LINEAR_ZERO, rgbdtools::DEPTH_FIT_QUADRATIC, rgbdtools::DEPTH_FIT_QUADRATIC_ZERO,
  rgbdtools::DEPTH_FIT_LINEAR, rgbdtools::DEPTH_FIT_LINEAR_ZERO, rgbdtools::DEPTH_FIT_QUADRATIC, rgbdtools::DEPTH_FIT_QUADRATIC_ZERO
}
 Polynomial fit modes for depth unwarping. More...

Functions

Pose rgbdtools::AffineFromTRPY (double xoffset, double yoffset, double zoffset, double roll, double pitch, double yaw)
void rgbdtools::buildPointCloud (const cv::Mat &depth_img_rect, const cv::Mat &intr_rect_ir, PointCloudT &cloud)
 Constructs a point cloud, a depth image and intrinsic matrix.
void rgbdtools::buildPointCloud (const cv::Mat &depth_img_rect_reg, const cv::Mat &rgb_img_rect, const cv::Mat &intr_rect_rgb, PointCloudT &cloud)
 Constructs a point cloud with color.
void rgbdtools::buildRegisteredDepthImage (const cv::Mat &intr_rect_ir, const cv::Mat &intr_rect_rgb, const cv::Mat &ir2rgb, const cv::Mat &depth_img_rect, cv::Mat &depth_img_rect_reg)
 reprojects a depth image to another depth image, registered in the rgb camera's frame.
void rgbdtools::depthImageFloatTo16bit (const cv::Mat &depth_image_in, cv::Mat &depth_image_out)
 converts a 32FC1 depth image (in meters) to a 16UC1 depth image (in mm).
void rgbdtools::eigenAffineToOpenCVRt (const AffineTransform &transform, cv::Mat &R, cv::Mat &t)
void rgbdtools::eigenAffineToXYZRPY (const AffineTransform &transform, float &x, float &y, float &z, float &roll, float &pitch, float &yaw)
void rgbdtools::getTfDifference (const AffineTransform &transform, double &dist, double &angle)
Eigen::Matrix4d rgbdtools::m4dfromPose (Pose pose)
void rgbdtools::openCVRtToEigenAffine (const cv::Mat &R, const cv::Mat &t, AffineTransform &eigen_affine)
void rgbdtools::pointCloudFromMeans (const Vector3fVector &means, PointCloudFeature &cloud)
 Creates a pcl point cloud form a vector of eigen matrix means.
void rgbdtools::removeInvalidDistributions (const Vector3fVector &means, const Matrix3fVector &covariances, const BoolVector &valid, Vector3fVector &means_f, Matrix3fVector &covariances_f)
 Filters out a vector of means and a vector of covariances given a mask of valid entries.
void rgbdtools::removeInvalidMeans (const Vector3fVector &means, const BoolVector &valid, Vector3fVector &means_f)
 Filters out a vector of means given a mask of valid entries.
void rgbdtools::setRPY (float roll, float pitch, float yaw, Matrix3f &m)
void rgbdtools::transformDistributions (Vector3fVector &means, Matrix3fVector &covariances, const AffineTransform &transform)
 Transforms a vector of means and covariances.
void rgbdtools::transformMeans (Vector3fVector &means, const AffineTransform &transform)
 Transforms a vector of means.
void rgbdtools::unwarpDepthImage (cv::Mat &depth_img_in, const cv::Mat &coeff0, const cv::Mat &coeff1, const cv::Mat &coeff2, int fit_mode=DEPTH_FIT_QUADRATIC)
 Given a depth image, uwarps it according to a polynomial model.
void rgbdtools::XYZRPYToEigenAffine (float x, float y, float z, float roll, float pitch, float yaw, AffineTransform &t)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:54