| Classes | |
| class | AbstractFeature | 
| class | AffineFlowMeasure | 
| class | AttributeLearningBaseFeature | 
| class | CannyEdges | 
| class | CenterSurroundMapper | 
| class | ColorCell | 
| class | ColorHistogram | 
| class | DenseLKFlow | 
| class | EdgeDensity | 
| class | FeatureTracker | 
| class | GaborFilterBank | 
| class | Homogeneity | 
| class | HSVColorHistogram | 
| class | LabColorHistogram | 
| class | LinkEdges | 
| class | LMFilterBank | 
| class | MyHOG | 
| class | NormalizedSum | 
| class | SIFTDes | 
| class | SlidingWindowDetector | 
| Typedefs | |
| typedef std::deque < AffineFlowMeasure > | AffineFlowMeasures | 
| typedef std::vector< float > | Descriptor | 
| typedef std::vector< Descriptor > | Descriptors | 
| typedef float(* | kernel )(const float &, const float &) | 
| typedef std::vector< cv::KeyPoint > | KeyPoints | 
| typedef int | LapCol | 
| typedef float | LapCost | 
| typedef int | LapRow | 
| typedef std::vector< int > | Path | 
| typedef std::vector< cv::Point > | Samples | 
| typedef std::vector< cv::Point2f > | Samples2f | 
| typedef std::vector< double > | ShapeDescriptor | 
| typedef std::vector < ShapeDescriptor > | ShapeDescriptors | 
| typedef std::vector< float > | SIFTFeature | 
| typedef std::vector< SIFTFeature > | SIFTFeatures | 
| typedef std::vector< float > | TextonFeature | 
| Functions | |
| void | checklap (int dim, LapCost **assigncost, LapCol *rowsol, LapRow *colsol, LapCost *u, LapCost *v) | 
| double | chiSqaureKernel (std::vector< double > x, std::vector< double > y) | 
| std::vector< std::vector < double > > | chiSquareKernelBatch (std::vector< std::vector< double > > &X, std::vector< std::vector< double > > &Y, double gamma) | 
| double | compareShapes (cv::Mat &imageA, cv::Mat &imageB, double epsilonCost=9e5, bool write_images=false, std::string filePath=".", int max_displacement=30, std::string filePostFix="") | 
| cv::Mat | computeCostMatrix (ShapeDescriptors &descriptorsA, ShapeDescriptors &descriptorsB, double epsilonCost=9e5, bool write_images=false, std::string filePath=".", std::string filePostFix="") | 
| ShapeDescriptors | constructDescriptors (Samples2f &samples, cv::Point2f ¢er, bool use_center=false, int radius_bins=5, int theta_bins=12, double max_radius=0, double scale=100.0) | 
| ShapeDescriptors | constructDescriptors (Samples2f &samples, unsigned int radius_bins=5, unsigned int theta_bins=12) | 
| template<class sample_type > | |
| ShapeDescriptors | constructDescriptors (sample_type &samples, unsigned int radius_bins=5, unsigned int theta_bins=12) | 
| void | Contributions (const unsigned int &in_length, const unsigned int &out_length, const float &scale, kernel KernelFoo, const float &kernel_scale, float kernel_width, const bool antialiasing, boost::shared_array< float > &weights, boost::shared_array< int > &indices, unsigned int &P) | 
| float | Cubic (const float &x, const float &scale) | 
| void | displayMatch (cv::Mat &edge_imgA, cv::Mat &edge_imgB, Samples &samplesA, Samples &samplesB, Path &path, int max_displacement=30, std::string filePath=".", std::string filePostFix="") | 
| void | displayOpticalFlow (cv::Mat &color_frame, cv::Mat &flow_u, cv::Mat &flow_v, float mag_thresh, bool display_uv=false) | 
| static double | dist (pcl16::PointXYZ a, pcl16::PointXYZ b) | 
| static double | dist (pcl16::PointXYZ a, geometry_msgs::Point b) | 
| static double | dist (geometry_msgs::Point b, pcl16::PointXYZ a) | 
| cv::Mat | downSample (cv::Mat data_in, int scales) | 
| ShapeDescriptors | extractDescriptors (cv::Mat &image) | 
| int | getHistogramIndex (double radius, double theta, int radius_bins, int theta_bins) | 
| double | getMinimumCostPath (cv::Mat &cost_matrix, Path &path) | 
| void | imResize (const cv::Mat &in_im, const float &scale, cv::Mat &out_im) | 
| LapCost | lap (int dim, LapCost **assigncost, LapCol *rowsol, LapRow *colsol, LapCost *u, LapCost *v) | 
| bool | lineLineIntersection2D (pcl16::PointXYZ a1, pcl16::PointXYZ a2, pcl16::PointXYZ b1, pcl16::PointXYZ b2, pcl16::PointXYZ &intersection) | 
| bool | lineSegmentIntersection2D (pcl16::PointXYZ a1, pcl16::PointXYZ a2, pcl16::PointXYZ b1, pcl16::PointXYZ b2, pcl16::PointXYZ &intersection) | 
| bool | pointIsBetweenOthers (pcl16::PointXYZ &pt, pcl16::PointXYZ &x1, pcl16::PointXYZ &x2) | 
| double | pointLineDistance2D (pcl16::PointXYZ &pt, pcl16::PointXYZ &a, pcl16::PointXYZ &b) | 
| template<class T > | |
| void | ResizeAlongDim (const cv::Mat &in, const unsigned int &dim, const boost::shared_array< float > &weights, const boost::shared_array< int > &indices, const unsigned int &out_length, const unsigned int &P, cv::Mat &out) | 
| std::vector< cv::Point > | samplePoints (cv::Mat &edge_image, double percentage=0.3) | 
| static double | sqrDist (Eigen::Vector3f &a, pcl16::PointXYZ &b) | 
| static double | sqrDist (Eigen::Vector4f &a, Eigen::Vector4f &b) | 
| static double | sqrDist (pcl16::PointXYZ a, pcl16::PointXYZ b) | 
| static double | sqrDistXY (pcl16::PointXYZ a, pcl16::PointXYZ b) | 
| double | subPIAngle (double theta) | 
| void | swapImages (cv::Mat &a, cv::Mat &b) | 
| void | swapSamples (Samples &a, Samples &b) | 
| cv::Mat | upSample (cv::Mat data_in, int scales) | 
| typedef std::deque<AffineFlowMeasure> cpl_visual_features::AffineFlowMeasures | 
Definition at line 80 of file flow_types.h.
| typedef std::vector<float> cpl_visual_features::Descriptor | 
Definition at line 51 of file feature_tracker.h.
Definition at line 52 of file feature_tracker.h.
| typedef float(* cpl_visual_features::kernel)(const float &, const float &) | 
| typedef std::vector<cv::KeyPoint> cpl_visual_features::KeyPoints | 
Definition at line 53 of file feature_tracker.h.
| typedef int cpl_visual_features::LapCol | 
| typedef float cpl_visual_features::LapCost | 
| typedef int cpl_visual_features::LapRow | 
| typedef std::vector<int> cpl_visual_features::Path | 
Definition at line 17 of file shape_context.h.
Definition at line 18 of file shape_context.h.
| typedef std::vector<cv::Point2f> cpl_visual_features::Samples2f | 
Definition at line 19 of file shape_context.h.
| typedef std::vector<double> cpl_visual_features::ShapeDescriptor | 
Definition at line 15 of file shape_context.h.
Definition at line 16 of file shape_context.h.
| typedef std::vector<float> cpl_visual_features::SIFTFeature | 
Definition at line 52 of file sift_des.h.
Definition at line 53 of file sift_des.h.
| typedef std::vector<float> cpl_visual_features::TextonFeature | 
Definition at line 49 of file lm_filter_bank.h.
| void cpl_visual_features::checklap | ( | int | dim, | 
| LapCost ** | assigncost, | ||
| LapCol * | rowsol, | ||
| LapRow * | colsol, | ||
| LapCost * | u, | ||
| LapCost * | v | ||
| ) | 
| double cpl_visual_features::chiSqaureKernel | ( | std::vector< double > | x, | 
| std::vector< double > | y | ||
| ) | 
Definition at line 41 of file kernels.cpp.
| std::vector< std::vector< double > > cpl_visual_features::chiSquareKernelBatch | ( | std::vector< std::vector< double > > & | X, | 
| std::vector< std::vector< double > > & | Y, | ||
| double | gamma | ||
| ) | 
Definition at line 56 of file kernels.cpp.
| double cpl_visual_features::compareShapes | ( | cv::Mat & | imageA, | 
| cv::Mat & | imageB, | ||
| double | epsilonCost = 9e5, | ||
| bool | write_images = false, | ||
| std::string | filePath = ".", | ||
| int | max_displacement = 30, | ||
| std::string | filePostFix = "" | ||
| ) | 
Definition at line 25 of file shape_context.cpp.
| cv::Mat cpl_visual_features::computeCostMatrix | ( | ShapeDescriptors & | descriptorsA, | 
| ShapeDescriptors & | descriptorsB, | ||
| double | epsilonCost = 9e5, | ||
| bool | write_images = false, | ||
| std::string | filePath = ".", | ||
| std::string | filePostFix = "" | ||
| ) | 
Definition at line 356 of file shape_context.cpp.
| ShapeDescriptors cpl_visual_features::constructDescriptors | ( | Samples2f & | samples, | 
| cv::Point2f & | center, | ||
| bool | use_center = false, | ||
| int | radius_bins = 5, | ||
| int | theta_bins = 12, | ||
| double | max_radius = 0, | ||
| double | scale = 100.0 | ||
| ) | 
Definition at line 179 of file shape_context.cpp.
| ShapeDescriptors cpl_visual_features::constructDescriptors | ( | Samples2f & | samples, | 
| unsigned int | radius_bins = 5, | ||
| unsigned int | theta_bins = 12 | ||
| ) | 
| ShapeDescriptors cpl_visual_features::constructDescriptors | ( | sample_type & | samples, | 
| unsigned int | radius_bins = 5, | ||
| unsigned int | theta_bins = 12 | ||
| ) | 
Definition at line 58 of file shape_context.h.
| void cpl_visual_features::Contributions | ( | const unsigned int & | in_length, | 
| const unsigned int & | out_length, | ||
| const float & | scale, | ||
| kernel | KernelFoo, | ||
| const float & | kernel_scale, | ||
| float | kernel_width, | ||
| const bool | antialiasing, | ||
| boost::shared_array< float > & | weights, | ||
| boost::shared_array< int > & | indices, | ||
| unsigned int & | P | ||
| ) | 
| float cpl_visual_features::Cubic | ( | const float & | x, | 
| const float & | scale | ||
| ) | 
| void cpl_visual_features::displayMatch | ( | cv::Mat & | edge_imgA, | 
| cv::Mat & | edge_imgB, | ||
| Samples & | samplesA, | ||
| Samples & | samplesB, | ||
| Path & | path, | ||
| int | max_displacement = 30, | ||
| std::string | filePath = ".", | ||
| std::string | filePostFix = "" | ||
| ) | 
Definition at line 461 of file shape_context.cpp.
| void cpl_visual_features::displayOpticalFlow | ( | cv::Mat & | color_frame, | 
| cv::Mat & | flow_u, | ||
| cv::Mat & | flow_v, | ||
| float | mag_thresh, | ||
| bool | display_uv = false | ||
| ) | 
Definition at line 79 of file dense_lk.h.
| static double cpl_visual_features::dist | ( | pcl16::PointXYZ | a, | 
| pcl16::PointXYZ | b | ||
| ) |  [inline, static] | 
Definition at line 55 of file comp_geometry.h.
| static double cpl_visual_features::dist | ( | pcl16::PointXYZ | a, | 
| geometry_msgs::Point | b | ||
| ) |  [inline, static] | 
Definition at line 63 of file comp_geometry.h.
| static double cpl_visual_features::dist | ( | geometry_msgs::Point | b, | 
| pcl16::PointXYZ | a | ||
| ) |  [inline, static] | 
Definition at line 71 of file comp_geometry.h.
| cv::Mat cpl_visual_features::downSample | ( | cv::Mat | data_in, | 
| int | scales | ||
| ) | 
| ShapeDescriptors cpl_visual_features::extractDescriptors | ( | cv::Mat & | image | ) | 
Definition at line 119 of file shape_context.cpp.
| int cpl_visual_features::getHistogramIndex | ( | double | radius, | 
| double | theta, | ||
| int | radius_bins, | ||
| int | theta_bins | ||
| ) | 
Definition at line 168 of file shape_context.cpp.
| double cpl_visual_features::getMinimumCostPath | ( | cv::Mat & | cost_matrix, | 
| Path & | path | ||
| ) | 
Definition at line 414 of file shape_context.cpp.
| void cpl_visual_features::imResize | ( | const cv::Mat & | in_im, | 
| const float & | scale, | ||
| cv::Mat & | out_im | ||
| ) | 
| LapCost cpl_visual_features::lap | ( | int | dim, | 
| LapCost ** | assigncost, | ||
| LapCol * | rowsol, | ||
| LapRow * | colsol, | ||
| LapCost * | u, | ||
| LapCost * | v | ||
| ) | 
| bool cpl_visual_features::lineLineIntersection2D | ( | pcl16::PointXYZ | a1, | 
| pcl16::PointXYZ | a2, | ||
| pcl16::PointXYZ | b1, | ||
| pcl16::PointXYZ | b2, | ||
| pcl16::PointXYZ & | intersection | ||
| ) | 
Definition at line 50 of file comp_geometry.cpp.
| bool cpl_visual_features::lineSegmentIntersection2D | ( | pcl16::PointXYZ | a1, | 
| pcl16::PointXYZ | a2, | ||
| pcl16::PointXYZ | b1, | ||
| pcl16::PointXYZ | b2, | ||
| pcl16::PointXYZ & | intersection | ||
| ) | 
Definition at line 39 of file comp_geometry.cpp.
| bool cpl_visual_features::pointIsBetweenOthers | ( | pcl16::PointXYZ & | pt, | 
| pcl16::PointXYZ & | x1, | ||
| pcl16::PointXYZ & | x2 | ||
| ) | 
Definition at line 65 of file comp_geometry.cpp.
| double cpl_visual_features::pointLineDistance2D | ( | pcl16::PointXYZ & | pt, | 
| pcl16::PointXYZ & | a, | ||
| pcl16::PointXYZ & | b | ||
| ) | 
Definition at line 71 of file comp_geometry.cpp.
| void cpl_visual_features::ResizeAlongDim | ( | const cv::Mat & | in, | 
| const unsigned int & | dim, | ||
| const boost::shared_array< float > & | weights, | ||
| const boost::shared_array< int > & | indices, | ||
| const unsigned int & | out_length, | ||
| const unsigned int & | P, | ||
| cv::Mat & | out | ||
| ) | 
| Samples cpl_visual_features::samplePoints | ( | cv::Mat & | edge_image, | 
| double | percentage = 0.3 | ||
| ) | 
Definition at line 136 of file shape_context.cpp.
| static double cpl_visual_features::sqrDist | ( | Eigen::Vector3f & | a, | 
| pcl16::PointXYZ & | b | ||
| ) |  [inline, static] | 
Definition at line 76 of file comp_geometry.h.
| static double cpl_visual_features::sqrDist | ( | Eigen::Vector4f & | a, | 
| Eigen::Vector4f & | b | ||
| ) |  [inline, static] | 
Definition at line 85 of file comp_geometry.h.
| static double cpl_visual_features::sqrDist | ( | pcl16::PointXYZ | a, | 
| pcl16::PointXYZ | b | ||
| ) |  [inline, static] | 
Definition at line 93 of file comp_geometry.h.
| static double cpl_visual_features::sqrDistXY | ( | pcl16::PointXYZ | a, | 
| pcl16::PointXYZ | b | ||
| ) |  [inline, static] | 
Definition at line 101 of file comp_geometry.h.
| double cpl_visual_features::subPIAngle | ( | double | theta | ) | 
| void cpl_visual_features::swapImages | ( | cv::Mat & | a, | 
| cv::Mat & | b | ||
| ) | 
Definition at line 11 of file shape_context.cpp.
| void cpl_visual_features::swapSamples | ( | Samples & | a, | 
| Samples & | b | ||
| ) | 
Definition at line 18 of file shape_context.cpp.
| cv::Mat cpl_visual_features::upSample | ( | cv::Mat | data_in, | 
| int | scales | ||
| ) |