#include <svm_classification.h>

Public Types | |
| typedef pcl::PointCloud < GRSDSignature21 > | InputType |
| typedef pcl::PointCloud < GRSDSignature21 > | OutputType |
Public Member Functions | |
| ros::Publisher | createPublisher (ros::NodeHandle &nh) |
| void | init (ros::NodeHandle &nh) |
| boost::shared_ptr< const OutputType > | output () |
| void | post () |
| void | pre () |
| std::string | process (const boost::shared_ptr< const InputType > &) |
| std::vector< std::string > | provides () |
| std::vector< std::string > | requires () |
| SVMClassification () | |
Static Public Member Functions | |
| static double ** | computeScaleParameters (const boost::shared_ptr< const InputType > &cloud, int startIdx, int nr_values) |
| static std::string | default_input_topic () |
| static std::string | default_node_name () |
| static std::string | default_output_topic () |
| static double ** | parseScaleParameterFile (const char *fileName, double &lower, double &upper, int nr_values, bool verbose=true) |
| static double | scaleFeature (int index, double value, double **min_max_values, double lower, double upper) |
Public Attributes | |
| std::string | model_file_name_ |
| bool | scale_file_ |
| std::string | scale_file_name_ |
| bool | scale_self_ |
Private Attributes | |
| boost::shared_ptr < sensor_msgs::PointCloud > | cloud_svm_ |
| ros::NodeHandle | nh_ |
Definition at line 31 of file svm_classification.h.
| typedef pcl::PointCloud<GRSDSignature21> pcl_cloud_algos::SVMClassification::InputType |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 38 of file svm_classification.h.
| typedef pcl::PointCloud<GRSDSignature21> pcl_cloud_algos::SVMClassification::OutputType |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 39 of file svm_classification.h.
Definition at line 65 of file svm_classification.h.
| static double** pcl_cloud_algos::SVMClassification::computeScaleParameters | ( | const boost::shared_ptr< const InputType > & | cloud, |
| int | startIdx, | ||
| int | nr_values | ||
| ) | [inline, static] |
Definition at line 95 of file svm_classification.h.
| ros::Publisher pcl_cloud_algos::SVMClassification::createPublisher | ( | ros::NodeHandle & | nh | ) | [inline, virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 187 of file svm_classification.h.
| static std::string pcl_cloud_algos::SVMClassification::default_input_topic | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 48 of file svm_classification.h.
| static std::string pcl_cloud_algos::SVMClassification::default_node_name | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 52 of file svm_classification.h.
| static std::string pcl_cloud_algos::SVMClassification::default_output_topic | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 50 of file svm_classification.h.
| void SVMClassification::init | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 7 of file svm_classification.cpp.
| boost::shared_ptr< const SVMClassification::OutputType > SVMClassification::output | ( | ) |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 171 of file svm_classification.cpp.
| static double** pcl_cloud_algos::SVMClassification::parseScaleParameterFile | ( | const char * | fileName, |
| double & | lower, | ||
| double & | upper, | ||
| int | nr_values, | ||
| bool | verbose = true |
||
| ) | [inline, static] |
Definition at line 132 of file svm_classification.h.
| void SVMClassification::post | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 22 of file svm_classification.cpp.
| void SVMClassification::pre | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 12 of file svm_classification.cpp.
| std::string SVMClassification::process | ( | const boost::shared_ptr< const InputType > & | ) |
Load the SVM model
Definition at line 42 of file svm_classification.cpp.
| std::vector< std::string > SVMClassification::provides | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 35 of file svm_classification.cpp.
| std::vector< std::string > SVMClassification::requires | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 27 of file svm_classification.cpp.
| static double pcl_cloud_algos::SVMClassification::scaleFeature | ( | int | index, |
| double | value, | ||
| double ** | min_max_values, | ||
| double | lower, | ||
| double | upper | ||
| ) | [inline, static] |
Definition at line 75 of file svm_classification.h.
boost::shared_ptr<sensor_msgs::PointCloud> pcl_cloud_algos::SVMClassification::cloud_svm_ [private] |
Definition at line 199 of file svm_classification.h.
Definition at line 42 of file svm_classification.h.
Definition at line 195 of file svm_classification.h.
Definition at line 45 of file svm_classification.h.
Definition at line 43 of file svm_classification.h.
Definition at line 44 of file svm_classification.h.