Public Member Functions | |
void | cloud_cb (const sensor_msgs::PointCloudConstPtr &cloud_in) |
void | cloud_cb (const PointCloudConstPtr &cloud_in) |
void | computeConcaveHull (const sensor_msgs::PointCloud &points, const vector< int > &indices, const vector< double > &coeff, const vector< vector< int > > &neighbors, geometry_msgs::Polygon &poly) |
void | findClusters (const sensor_msgs::PointCloud &points, const vector< int > &indices, double tolerance, vector< Region > &clusters, int nx_idx, int ny_idx, int nz_idx, unsigned int min_pts_per_cluster=1) |
Decompose a region of space into clusters based on the euclidean distance between points. | |
int | fitSACPlane (sensor_msgs::PointCloud *points, vector< int > *indices, vector< vector< int > > &inliers, vector< vector< double > > &coeff) |
void | fitSACPlane (PointCloud *points, vector< int > *indices, vector< vector< int > > &inliers, vector< vector< double > > &coeff) |
void | getObjectClassForParallel (sensor_msgs::PointCloud *points, vector< int > *indices, vector< double > *coeff, geometry_msgs::PointStamped map_origin, double &rgb) |
void | getObjectClassForPerpendicular (sensor_msgs::PointCloud *points, vector< int > *indices, double &rgb) |
SemanticPointAnnotator (ros::NodeHandle &anode) | |
SemanticPointAnnotator (ros::NodeHandle &anode) | |
void | sortConcaveHull2D (const sensor_msgs::PointCloud &points, const vector< int > &indices, geometry_msgs::Polygon &poly) |
Public Attributes | |
double | boundary_angle_threshold_ |
sensor_msgs::PointCloud | cloud_ |
PointCloud | cloud_ |
sensor_msgs::PointCloud | cloud_annotated_ |
PointCloud | cloud_annotated_ |
ros::Subscriber | cloud_normal_subscriber_ |
ros::Publisher | cloud_publisher_ |
ros::Subscriber | cloud_subscriber_ |
bool | concave_ |
double | eps_angle_ |
int | min_cluster_pts_ |
PolygonalMap | pmap_ |
bool | polygonal_map_ |
ros::Publisher | polygonal_map_publisher_ |
double | region_angle_threshold_ |
double | region_growing_tolerance_ |
double | rule_ceiling_ |
double | rule_floor_ |
double | rule_table_max_ |
double | rule_table_min_ |
double | rule_wall_ |
double | sac_distance_threshold_ |
int | sac_min_points_left_ |
int | sac_min_points_per_model_ |
tf::TransformListener | tf_ |
geometry_msgs::Point32 | z_axis_ |
Point32 | z_axis_ |
Protected Attributes | |
ros::NodeHandle & | node_ |
Definition at line 69 of file semantic_point_annotator.cpp.
SemanticPointAnnotator::SemanticPointAnnotator | ( | ros::NodeHandle & | anode | ) | [inline] |
Definition at line 93 of file semantic_point_annotator.cpp.
SemanticPointAnnotator::SemanticPointAnnotator | ( | ros::NodeHandle & | anode | ) | [inline] |
Definition at line 108 of file semantic_point_annotator_omp.cpp.
void SemanticPointAnnotator::cloud_cb | ( | const sensor_msgs::PointCloudConstPtr & | cloud_in | ) | [inline] |
ROS_INFO ("Found %d clusters.", clusters.size ());
note: the clusters are in the z_axis_indices space so instead of points[clusters[j]] we need to do points[z_axis_indices[clusters[j]] nr_p = 0; for (unsigned int cc = 0; cc < clusters.size (); cc++) { double r, g, b; r = rand () / (RAND_MAX + 1.0); g = rand () / (RAND_MAX + 1.0); b = rand () / (RAND_MAX + 1.0); for (unsigned int j = 0; j < clusters[cc].size (); j++) { cloud_annotated_.points[nr_p].x = cloud_.points[xy_axis_indices[clusters[cc].at (j)]].x; cloud_annotated_.points[nr_p].y = cloud_.points[xy_axis_indices[clusters[cc].at (j)]].y; cloud_annotated_.points[nr_p].z = cloud_.points[xy_axis_indices[clusters[cc].at (j)]].z; cloud_annotated_.channels[0].values[i] = intensity_value; cloud_annotated_.channels[0].values[nr_p] = rgb; nr_p++; } }
Definition at line 452 of file semantic_point_annotator_omp.cpp.
void SemanticPointAnnotator::cloud_cb | ( | const PointCloudConstPtr & | cloud_in | ) | [inline] |
Definition at line 161 of file semantic_point_annotator.cpp.
void SemanticPointAnnotator::computeConcaveHull | ( | const sensor_msgs::PointCloud & | points, | |
const vector< int > & | indices, | |||
const vector< double > & | coeff, | |||
const vector< vector< int > > & | neighbors, | |||
geometry_msgs::Polygon & | poly | |||
) | [inline] |
Definition at line 428 of file semantic_point_annotator_omp.cpp.
void SemanticPointAnnotator::findClusters | ( | const sensor_msgs::PointCloud & | points, | |
const vector< int > & | indices, | |||
double | tolerance, | |||
vector< Region > & | clusters, | |||
int | nx_idx, | |||
int | ny_idx, | |||
int | nz_idx, | |||
unsigned int | min_pts_per_cluster = 1 | |||
) | [inline] |
Decompose a region of space into clusters based on the euclidean distance between points.
points | the point cloud message | |
indices | a list of point indices | |
tolerance | the spatial tolerance as a measure in the L2 Euclidean space | |
clusters | the resultant clusters | |
nx_idx | ||
ny_idx | ||
nz_idx | ||
min_pts_per_cluster | minimum number of points that a cluster may contain (default = 1) |
Definition at line 181 of file semantic_point_annotator_omp.cpp.
int SemanticPointAnnotator::fitSACPlane | ( | sensor_msgs::PointCloud * | points, | |
vector< int > * | indices, | |||
vector< vector< int > > & | inliers, | |||
vector< vector< double > > & | coeff | |||
) | [inline] |
Definition at line 300 of file semantic_point_annotator_omp.cpp.
void SemanticPointAnnotator::fitSACPlane | ( | PointCloud * | points, | |
vector< int > * | indices, | |||
vector< vector< int > > & | inliers, | |||
vector< vector< double > > & | coeff | |||
) | [inline] |
Definition at line 121 of file semantic_point_annotator.cpp.
void SemanticPointAnnotator::getObjectClassForParallel | ( | sensor_msgs::PointCloud * | points, | |
vector< int > * | indices, | |||
vector< double > * | coeff, | |||
geometry_msgs::PointStamped | map_origin, | |||
double & | rgb | |||
) | [inline] |
Definition at line 358 of file semantic_point_annotator_omp.cpp.
void SemanticPointAnnotator::getObjectClassForPerpendicular | ( | sensor_msgs::PointCloud * | points, | |
vector< int > * | indices, | |||
double & | rgb | |||
) | [inline] |
Definition at line 403 of file semantic_point_annotator_omp.cpp.
void SemanticPointAnnotator::sortConcaveHull2D | ( | const sensor_msgs::PointCloud & | points, | |
const vector< int > & | indices, | |||
geometry_msgs::Polygon & | poly | |||
) | [inline] |
Definition at line 254 of file semantic_point_annotator_omp.cpp.
Definition at line 94 of file semantic_point_annotator_omp.cpp.
sensor_msgs::PointCloud SemanticPointAnnotator::cloud_ |
Definition at line 86 of file semantic_point_annotator_omp.cpp.
PointCloud SemanticPointAnnotator::cloud_ |
Definition at line 77 of file semantic_point_annotator.cpp.
sensor_msgs::PointCloud SemanticPointAnnotator::cloud_annotated_ |
Definition at line 86 of file semantic_point_annotator_omp.cpp.
PointCloud SemanticPointAnnotator::cloud_annotated_ |
Definition at line 77 of file semantic_point_annotator.cpp.
ros::Subscriber SemanticPointAnnotator::cloud_normal_subscriber_ |
Definition at line 81 of file semantic_point_annotator.cpp.
ros::Publisher SemanticPointAnnotator::cloud_publisher_ |
Definition at line 80 of file semantic_point_annotator.cpp.
ros::Subscriber SemanticPointAnnotator::cloud_subscriber_ |
Definition at line 105 of file semantic_point_annotator_omp.cpp.
Definition at line 101 of file semantic_point_annotator_omp.cpp.
Definition at line 87 of file semantic_point_annotator.cpp.
Definition at line 102 of file semantic_point_annotator_omp.cpp.
ros::NodeHandle & SemanticPointAnnotator::node_ [protected] |
Definition at line 72 of file semantic_point_annotator.cpp.
PolygonalMap SemanticPointAnnotator::pmap_ |
Definition at line 88 of file semantic_point_annotator_omp.cpp.
Definition at line 101 of file semantic_point_annotator_omp.cpp.
ros::Publisher SemanticPointAnnotator::polygonal_map_publisher_ |
Definition at line 104 of file semantic_point_annotator_omp.cpp.
Definition at line 94 of file semantic_point_annotator_omp.cpp.
Definition at line 99 of file semantic_point_annotator_omp.cpp.
Definition at line 89 of file semantic_point_annotator.cpp.
Definition at line 89 of file semantic_point_annotator.cpp.
Definition at line 90 of file semantic_point_annotator.cpp.
Definition at line 90 of file semantic_point_annotator.cpp.
Definition at line 89 of file semantic_point_annotator.cpp.
Definition at line 87 of file semantic_point_annotator.cpp.
Definition at line 86 of file semantic_point_annotator.cpp.
Definition at line 86 of file semantic_point_annotator.cpp.
tf::TransformListener SemanticPointAnnotator::tf_ |
Definition at line 83 of file semantic_point_annotator.cpp.
geometry_msgs::Point32 SemanticPointAnnotator::z_axis_ |
Definition at line 87 of file semantic_point_annotator_omp.cpp.
Point32 SemanticPointAnnotator::z_axis_ |
Definition at line 78 of file semantic_point_annotator.cpp.