Public Member Functions | |
| void | addCentroid (const SpectralProfile &other) |
| float | getAngleDiffInRadians (const SpectralProfile &other) |
| float | getAngleWithVerticalInRadians () const |
| pcl::PointXYZ | getCentroid () |
| PointT | getCentroidSL () |
| int | getConvexity (const SpectralProfile &other, float mindistance) |
| float | getCoplanarity (const SpectralProfile &other) |
| float | getDescendingLambda (int index) const |
| float | getDistanceSqrBwCentroids (const SpectralProfile &other) const |
| float | getHDiffAbs (const SpectralProfile &other) |
| float | getHorzDistanceBwCentroids (const SpectralProfile &other) const |
| float | getInnerness (const SpectralProfile &other) |
| float | getLinearNess () const |
| float | getNormalDotProduct (const SpectralProfile &other) |
| float | getNormalZComponent () const |
| float | getPlanarNess () const |
| float | getScatter () const |
| float | getSDiff (const SpectralProfile &other) |
| float | getVDiff (const SpectralProfile &other) |
| float | getVertDispCentroids (const SpectralProfile &other) |
| float | pushHogDiffFeats (const SpectralProfile &other, vector< float > &feats) |
| void | setAvgCentroid () |
| void | setCentroid (const SpectralProfile &other) |
| void | setEigValues (Eigen::Vector3d eigenValues_) |
| void | transformCentroid (TransformG &trans) |
Public Attributes | |
| float | avgH |
| HOGFeaturesOfBlock | avgHOGFeatsOfSegment |
| float | avgS |
| float | avgV |
| geometry_msgs::Point32 | centroid |
| pcl::PointCloud< PointT >::Ptr | cloudPtr |
| int | count |
| Eigen::Vector3d | normal |
Private Attributes | |
| vector< float > | eigenValues |
Definition at line 71 of file openni_listener.cpp.
| void SpectralProfile::addCentroid | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 99 of file openni_listener.cpp.
| float SpectralProfile::getAngleDiffInRadians | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 185 of file openni_listener.cpp.
| float SpectralProfile::getAngleWithVerticalInRadians | ( | ) | const [inline] |
Definition at line 157 of file openni_listener.cpp.
| pcl::PointXYZ SpectralProfile::getCentroid | ( | ) | [inline] |
Definition at line 125 of file openni_listener.cpp.
| PointT SpectralProfile::getCentroidSL | ( | ) | [inline] |
Definition at line 133 of file openni_listener.cpp.
| int SpectralProfile::getConvexity | ( | const SpectralProfile & | other, |
| float | mindistance | ||
| ) | [inline] |
Definition at line 216 of file openni_listener.cpp.
| float SpectralProfile::getCoplanarity | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 203 of file openni_listener.cpp.
| float SpectralProfile::getDescendingLambda | ( | int | index | ) | const [inline] |
Definition at line 95 of file openni_listener.cpp.
| float SpectralProfile::getDistanceSqrBwCentroids | ( | const SpectralProfile & | other | ) | const [inline] |
Definition at line 165 of file openni_listener.cpp.
| float SpectralProfile::getHDiffAbs | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 173 of file openni_listener.cpp.
| float SpectralProfile::getHorzDistanceBwCentroids | ( | const SpectralProfile & | other | ) | const [inline] |
Definition at line 161 of file openni_listener.cpp.
| float SpectralProfile::getInnerness | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 193 of file openni_listener.cpp.
| float SpectralProfile::getLinearNess | ( | ) | const [inline] |
Definition at line 145 of file openni_listener.cpp.
| float SpectralProfile::getNormalDotProduct | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 189 of file openni_listener.cpp.
| float SpectralProfile::getNormalZComponent | ( | ) | const [inline] |
Definition at line 153 of file openni_listener.cpp.
| float SpectralProfile::getPlanarNess | ( | ) | const [inline] |
Definition at line 149 of file openni_listener.cpp.
| float SpectralProfile::getScatter | ( | ) | const [inline] |
Definition at line 141 of file openni_listener.cpp.
| float SpectralProfile::getSDiff | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 177 of file openni_listener.cpp.
| float SpectralProfile::getVDiff | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 181 of file openni_listener.cpp.
| float SpectralProfile::getVertDispCentroids | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 169 of file openni_listener.cpp.
| float SpectralProfile::pushHogDiffFeats | ( | const SpectralProfile & | other, |
| vector< float > & | feats | ||
| ) | [inline] |
Definition at line 199 of file openni_listener.cpp.
| void SpectralProfile::setAvgCentroid | ( | ) | [inline] |
Definition at line 118 of file openni_listener.cpp.
| void SpectralProfile::setCentroid | ( | const SpectralProfile & | other | ) | [inline] |
Definition at line 112 of file openni_listener.cpp.
| void SpectralProfile::setEigValues | ( | Eigen::Vector3d | eigenValues_ | ) | [inline] |
Definition at line 84 of file openni_listener.cpp.
| void SpectralProfile::transformCentroid | ( | TransformG & | trans | ) | [inline] |
Definition at line 107 of file openni_listener.cpp.
| float SpectralProfile::avgH |
Definition at line 76 of file openni_listener.cpp.
| HOGFeaturesOfBlock SpectralProfile::avgHOGFeatsOfSegment |
Definition at line 75 of file openni_listener.cpp.
| float SpectralProfile::avgS |
Definition at line 77 of file openni_listener.cpp.
| float SpectralProfile::avgV |
Definition at line 78 of file openni_listener.cpp.
| geometry_msgs::Point32 SpectralProfile::centroid |
Definition at line 81 of file openni_listener.cpp.
Definition at line 74 of file openni_listener.cpp.
Definition at line 79 of file openni_listener.cpp.
vector<float> SpectralProfile::eigenValues [private] |
Definition at line 72 of file openni_listener.cpp.
| Eigen::Vector3d SpectralProfile::normal |
Definition at line 82 of file openni_listener.cpp.