Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
MovingObjectFilter Class Reference

#include <moving_object_filter.h>

Inheritance diagram for MovingObjectFilter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 MovingObjectFilter (int argc, char **argv)
void processData (const cv::Mat &image, const cv::Mat &depth, float fx, float fy, float cx, float cy)
void setFrameId (std::string rgb_frame, std::string depth_frame)

Public Attributes

std::string depth_frame_id
std::string rgb_frame_id

Private Member Functions

cv::Mat bgrFromCloud (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, bool bgrOrder)
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
cloudFromDepthRGB (const cv::Mat &imageRgb, const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation)
void computeHomography (cv::Mat &grayImage)
cv::Mat depthFromCloud (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, float &fx, float &fy, bool depth16U)
cv::Mat getDepth (cloud_type::ConstPtr cloud, const cv::Mat &depthImage, float cx, float cy, float fx, float fy)
void getImage (cloud_type::ConstPtr cloud, const cv::Mat &image, float cx, float cy, float fx, float fy)
void image_diff (const cv::Mat &image, cloud_type::ConstPtr cloud)
bool image_extract_cluster (cloud_type::ConstPtr cluster_cloud, cloud_type::ConstPtr cloud, const cv::Mat &image, float cx, float cy, float fx, float fy, int num, int j)
pcl::PointCloud< pcl::PointXYZRGB > objectFromOriginalCloud (cloud_type::ConstPtr clusterCloud, cloud_type::ConstPtr cloud)
cv::Mat pcl_segmentation (cloud_type::ConstPtr cloud, const cv::Mat &image, const cv::Mat &depthImage, float cx, float cy, float fx, float fy)
pcl::PointXYZ projectDepthTo3D (const cv::Mat &depthImage, float x, float y, float cx, float cy, float fx, float fy, bool smoothing, float maxZError=0.02f)

Private Attributes

pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
cloud
ros::Publisher cloudPub_
cv::Mat currentFrame
ros::Publisher depthPub_
cv::Mat dynamicImage
cv::Mat Homography
cv::Mat lastBlurImage
cloud_type lastCloud
cv::Mat lastDepth
cv::Mat lastFrame
cv::Mat lastImage
int num1
ros::Publisher rgbPub_
double threshod

Detailed Description

Definition at line 70 of file moving_object_filter.h.


Constructor & Destructor Documentation

MovingObjectFilter::MovingObjectFilter ( int  argc,
char **  argv 
)

Definition at line 18 of file moving_object_filter.cpp.


Member Function Documentation

cv::Mat MovingObjectFilter::bgrFromCloud ( const pcl::PointCloud< pcl::PointXYZRGB > &  cloud,
bool  bgrOrder 
) [private]

Definition at line 1245 of file moving_object_filter.cpp.

pcl::PointCloud< pcl::PointXYZRGB >::Ptr MovingObjectFilter::cloudFromDepthRGB ( const cv::Mat &  imageRgb,
const cv::Mat &  imageDepth,
float  cx,
float  cy,
float  fx,
float  fy,
int  decimation 
) [private]

Definition at line 609 of file moving_object_filter.cpp.

void MovingObjectFilter::computeHomography ( cv::Mat &  grayImage) [private]

Definition at line 182 of file moving_object_filter.cpp.

cv::Mat MovingObjectFilter::depthFromCloud ( const pcl::PointCloud< pcl::PointXYZRGB > &  cloud,
float &  fx,
float &  fy,
bool  depth16U 
) [private]

Definition at line 1273 of file moving_object_filter.cpp.

cv::Mat MovingObjectFilter::getDepth ( cloud_type::ConstPtr  cloud,
const cv::Mat &  depthImage,
float  cx,
float  cy,
float  fx,
float  fy 
) [private]

Definition at line 1139 of file moving_object_filter.cpp.

void MovingObjectFilter::getImage ( cloud_type::ConstPtr  cloud,
const cv::Mat &  image,
float  cx,
float  cy,
float  fx,
float  fy 
) [private]

Definition at line 1179 of file moving_object_filter.cpp.

void MovingObjectFilter::image_diff ( const cv::Mat &  image,
cloud_type::ConstPtr  cloud 
) [private]

Definition at line 302 of file moving_object_filter.cpp.

bool MovingObjectFilter::image_extract_cluster ( cloud_type::ConstPtr  cluster_cloud,
cloud_type::ConstPtr  cloud,
const cv::Mat &  image,
float  cx,
float  cy,
float  fx,
float  fy,
int  num,
int  j 
) [private]

Definition at line 967 of file moving_object_filter.cpp.

pcl::PointCloud< pcl::PointXYZRGB > MovingObjectFilter::objectFromOriginalCloud ( cloud_type::ConstPtr  clusterCloud,
cloud_type::ConstPtr  cloud 
) [private]

Definition at line 1077 of file moving_object_filter.cpp.

cv::Mat MovingObjectFilter::pcl_segmentation ( cloud_type::ConstPtr  cloud,
const cv::Mat &  image,
const cv::Mat &  depthImage,
float  cx,
float  cy,
float  fx,
float  fy 
) [private]

Definition at line 674 of file moving_object_filter.cpp.

void MovingObjectFilter::processData ( const cv::Mat &  image,
const cv::Mat &  depth,
float  fx,
float  fy,
float  cx,
float  cy 
)

Definition at line 33 of file moving_object_filter.cpp.

pcl::PointXYZ MovingObjectFilter::projectDepthTo3D ( const cv::Mat &  depthImage,
float  x,
float  y,
float  cx,
float  cy,
float  fx,
float  fy,
bool  smoothing,
float  maxZError = 0.02f 
) [private]

Definition at line 512 of file moving_object_filter.cpp.

void MovingObjectFilter::setFrameId ( std::string  rgb_frame,
std::string  depth_frame 
)

Definition at line 28 of file moving_object_filter.cpp.


Member Data Documentation

pcl::PointCloud<pcl::PointXYZRGB>::Ptr MovingObjectFilter::cloud [private]

Definition at line 101 of file moving_object_filter.h.

Definition at line 84 of file moving_object_filter.h.

Definition at line 94 of file moving_object_filter.h.

Definition at line 78 of file moving_object_filter.h.

Definition at line 83 of file moving_object_filter.h.

Definition at line 96 of file moving_object_filter.h.

cv::Mat MovingObjectFilter::Homography [private]

Definition at line 95 of file moving_object_filter.h.

Definition at line 92 of file moving_object_filter.h.

Definition at line 104 of file moving_object_filter.h.

cv::Mat MovingObjectFilter::lastDepth [private]

Definition at line 91 of file moving_object_filter.h.

cv::Mat MovingObjectFilter::lastFrame [private]

Definition at line 93 of file moving_object_filter.h.

cv::Mat MovingObjectFilter::lastImage [private]

Definition at line 90 of file moving_object_filter.h.

int MovingObjectFilter::num1 [private]

Definition at line 115 of file moving_object_filter.h.

Definition at line 77 of file moving_object_filter.h.

Definition at line 82 of file moving_object_filter.h.

double MovingObjectFilter::threshod [private]

Definition at line 114 of file moving_object_filter.h.


The documentation for this class was generated from the following files:


micros_dynamic_objects_filter
Author(s):
autogenerated on Thu Jun 6 2019 17:55:18