#include <hector_stair_detection.h>
Public Member Functions | |
HectorStairDetection () | |
void | PclCallback (const sensor_msgs::PointCloud2::ConstPtr &pc_msg) |
virtual | ~HectorStairDetection () |
Private Member Functions | |
bool | checkExtentionDirection (Eigen::Vector2f directionStairs, Eigen::Vector2f directionExtend) |
void | getFinalStairsCloud_and_position (std::string frameID, Eigen::Vector3f directionS, pcl::PointCloud< pcl::PointNormal >::Ptr &input_surface_cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &planeCloud, pcl::IndicesClustersPtr cluster_indices, std::vector< int > final_cluster_idx, pcl::PointCloud< pcl::PointXYZ >::Ptr &final_stairsCloud, visualization_msgs::MarkerArray &stairs_boarder_marker, Eigen::Vector3f base) |
void | getPreprocessedCloud (pcl::PointCloud< pcl::PointXYZ >::Ptr &input_cloud, pcl::PointCloud< pcl::PointNormal >::Ptr &output_cloud) |
void | getStairsPositionAndOrientation (Eigen::Vector3f &base, Eigen::Vector3f point, std::string frameID, Eigen::Vector3f &direction, geometry_msgs::PoseStamped &position_and_orientaion) |
int | getZComponent (Eigen::Vector2f directionStairs, Eigen::Vector2f minXminY, Eigen::Vector2f maxXminY, Eigen::Vector2f minXmaxY) |
float | maxDistBetweenPoints (pcl::PointCloud< pcl::PointXYZI >::Ptr input_cloud) |
float | minHightDistBetweenPoints (pcl::PointCloud< pcl::PointXYZI >::Ptr input_cloud) |
bool | pointInCloud (pcl::PointCloud< pcl::PointXYZI >::Ptr cloud, pcl::PointXYZ point) |
void | projectStairsToFloor (Eigen::Vector3f direction, visualization_msgs::MarkerArray &stairs_boarder_marker) |
void | publishResults (pcl::PointCloud< pcl::PointNormal >::Ptr &input_surface_cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &planeCloud, pcl::IndicesClustersPtr cluster_indices, std::vector< int > final_cluster_idx, Eigen::Vector3f base, Eigen::Vector3f point) |
void | refineOrientaion (Eigen::Vector2f directionStairs, Eigen::Vector2f minXminY, Eigen::Vector2f maxXminY, Eigen::Vector2f minXmaxY, geometry_msgs::PoseStamped &position_and_orientaion) |
void | stairsSreachPlaneDetection (pcl::PointCloud< pcl::PointNormal >::Ptr &input_surface_cloud, pcl::PointCloud< pcl::PointXYZI >::Ptr points_on_line, Eigen::Vector3f base, Eigen::Vector3f dir, pcl::PointCloud< pcl::PointXYZ >::Ptr &planeCloud) |
Private Attributes | |
double | clusterHeightTresh_ |
int | clusterMaxSize_ |
int | clusterMinSize_ |
double | clusterTolerance_ |
double | distanceToLineTresh_ |
double | distTrashSegmentation_ |
double | hesseTresh_ |
double | maxClusterXYDimension_ |
double | maxDistBetweenStairsPoints_ |
double | minHightDistBetweenAllStairsPoints_ |
int | minRequiredPointsOnLine_ |
double | passThroughZMax_ |
double | passThroughZMin_ |
double | planeSegAngleEps_ |
double | planeSegDistTresh_ |
bool | refineSurfaceRequired_ |
std::string | setup_ |
double | voxelGridX_ |
double | voxelGridY_ |
double | voxelGridZ_ |
std::string | worldFrame_ |
Definition at line 57 of file hector_stair_detection.h.
hector_stair_detection::HectorStairDetection::HectorStairDetection | ( | ) |
Definition at line 5 of file hector_stair_detection.cpp.
|
virtual |
Definition at line 79 of file hector_stair_detection.cpp.
|
private |
|
private |
Definition at line 151 of file hector_stair_detection.cpp.
|
private |
Definition at line 379 of file hector_stair_detection.cpp.
|
private |
Definition at line 127 of file hector_stair_detection.cpp.
|
private |
Definition at line 346 of file hector_stair_detection.cpp.
|
private |
Definition at line 920 of file hector_stair_detection.cpp.
|
private |
Definition at line 934 of file hector_stair_detection.cpp.
void hector_stair_detection::HectorStairDetection::PclCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | pc_msg | ) |
Definition at line 465 of file hector_stair_detection.cpp.
|
private |
|
private |
Definition at line 318 of file hector_stair_detection.cpp.
|
private |
Definition at line 82 of file hector_stair_detection.cpp.
|
private |
|
private |
Definition at line 789 of file hector_stair_detection.cpp.
|
protected |
Definition at line 71 of file hector_stair_detection.h.
|
protected |
Definition at line 69 of file hector_stair_detection.h.
|
protected |
Definition at line 73 of file hector_stair_detection.h.
|
private |
Definition at line 96 of file hector_stair_detection.h.
|
private |
Definition at line 100 of file hector_stair_detection.h.
|
private |
Definition at line 99 of file hector_stair_detection.h.
|
private |
Definition at line 98 of file hector_stair_detection.h.
|
private |
Definition at line 93 of file hector_stair_detection.h.
|
private |
Definition at line 102 of file hector_stair_detection.h.
|
protected |
Definition at line 68 of file hector_stair_detection.h.
|
private |
Definition at line 107 of file hector_stair_detection.h.
|
protected |
Definition at line 74 of file hector_stair_detection.h.
|
protected |
Definition at line 82 of file hector_stair_detection.h.
|
private |
Definition at line 97 of file hector_stair_detection.h.
|
private |
Definition at line 103 of file hector_stair_detection.h.
|
private |
Definition at line 104 of file hector_stair_detection.h.
|
private |
Definition at line 92 of file hector_stair_detection.h.
|
private |
Definition at line 88 of file hector_stair_detection.h.
|
private |
Definition at line 87 of file hector_stair_detection.h.
|
protected |
Definition at line 81 of file hector_stair_detection.h.
|
private |
Definition at line 106 of file hector_stair_detection.h.
|
private |
Definition at line 105 of file hector_stair_detection.h.
|
protected |
Definition at line 66 of file hector_stair_detection.h.
|
protected |
Definition at line 65 of file hector_stair_detection.h.
|
private |
Definition at line 94 of file hector_stair_detection.h.
|
private |
Definition at line 101 of file hector_stair_detection.h.
|
protected |
Definition at line 70 of file hector_stair_detection.h.
|
protected |
Definition at line 72 of file hector_stair_detection.h.
|
protected |
Definition at line 67 of file hector_stair_detection.h.
|
protected |
Definition at line 79 of file hector_stair_detection.h.
|
protected |
Definition at line 77 of file hector_stair_detection.h.
|
protected |
Definition at line 78 of file hector_stair_detection.h.
|
protected |
Definition at line 76 of file hector_stair_detection.h.
|
protected |
Definition at line 83 of file hector_stair_detection.h.
|
private |
Definition at line 89 of file hector_stair_detection.h.
|
private |
Definition at line 90 of file hector_stair_detection.h.
|
private |
Definition at line 91 of file hector_stair_detection.h.
|
private |
Definition at line 95 of file hector_stair_detection.h.