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) |