Namespaces | Defines | Typedefs | Functions
SRUtils.h File Reference
#include "shape_reconstruction/RangeImagePlanar.h"
#include "omip_common/OMIPUtils.h"
#include "omip_common/OMIPTypeDefs.h"
#include <opencv2/core/core.hpp>
#include <camera_info_manager/camera_info_manager.h>
#include <pcl/range_image/range_image_planar.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/common/transforms.h>
#include <pcl/search/search.h>
#include <pcl/search/organized.h>
#include <pcl/search/kdtree.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/approximate_voxel_grid.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/normal_3d.h>
#include <pcl/surface/gp3.h>
#include <pcl/io/vtk_lib_io.h>
#include <boost/circular_buffer.hpp>
Include dependency graph for SRUtils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  omip

Defines

#define IMG_HEIGHT   480
#define IMG_WIDTH   640
#define NUM_SCALES   3

Typedefs

typedef pcl::PointXYZRGB omip::SRPoint
typedef pcl::PointCloud< SRPoint > omip::SRPointCloud

Functions

void omip::cbf (uint8_t *depth, uint8_t *intensity, bool *mask, uint8_t *result, double *sigma_s, double *sigma_r)
void omip::DepthImage2CvImage (const cv::Mat &depth_image_raw, sensor_msgs::ImagePtr &depth_msg)
void omip::drawOptFlowMap (const cv::Mat &flow, cv::Mat &cflowmap, int step, double scale, const cv::Scalar &color)
void omip::drawOpticalFlowModule (const cv::Mat &optical_flow, cv::Mat &optical_flow_module)
cv::Mat omip::fill_depth_cbf (cv::Mat imgRgb, cv::Mat imgDepthAbs, double *spaceSigmas, double *rangeSigmas)
void omip::fillNaNsCBF (const sensor_msgs::Image &color_img, const cv::Mat &depth_img, cv::Mat &filled_depth_img, ros::Time query_time)
void omip::Image8u2Indices (const cv::Mat &image_8u, pcl::PointIndices::Ptr indices_ptr)
void omip::Indices2Image8u (const std::vector< int > &indices, cv::Mat &image_8u)
void omip::OrganizedPC2ColorMap (const SRPointCloud::Ptr organized_pc, cv::Mat &color_map_mat)
void omip::OrganizedPC2DepthMap (const SRPointCloud::Ptr organized_pc, cv::Mat &depth_map_mat)
void omip::OrganizedPC2DepthMapAlternative (const SRPointCloud::Ptr organized_pc, const cv::Ptr< cv::Mat > &depth_map_mat_ptr)
void omip::RangeImagePlanar2DepthMap (const pcl::RangeImagePlanar::Ptr &rip, cv::Mat &depth_map_mat)
void omip::RangeImagePlanar2PointCloud (const pcl::RangeImagePlanar::Ptr &rip, SRPointCloud::Ptr &pc)
void omip::removeDuplicateIndices (std::vector< int > &vec)
void omip::UnorganizedPC2DepthMap (const SRPointCloud::Ptr &organized_pc, const int &width, const int &height, cv::Mat &depth_map,::shape_reconstruction::RangeImagePlanar::Ptr &rip, const float &noiseLevel=0.f, const float &minRange=0.5f)

Define Documentation

#define IMG_HEIGHT   480

Definition at line 88 of file SRUtils.h.

#define IMG_WIDTH   640

Definition at line 87 of file SRUtils.h.

#define NUM_SCALES   3

Definition at line 91 of file SRUtils.h.



shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:38:55