#include <polygon_primitive_with_texture.h>
Public Member Functions | |
int | add_camera_projection (cv::Mat *m, ros::Time t, double fx, double fy, double cx, double cy, tf::StampedTransform tf, double k1, double k2, double p1, double p2, double k3, double sd_cx, double sd_cy, double param, double scale, std::string projection_name, cv::Scalar color) |
int | add_camera_projection_known_camera (cv::Mat *m, ros::Time t, tf::StampedTransform tf, std::string cam_name, std::string projection_name, cv::Scalar color) |
int | add_camera_projection_to_triangle_mesh (int projection_index, ros::Publisher *p_marker_pub) |
size_t | ask_for_number (void) |
int | build_global_mesh (ros::Publisher *p_marker_pub) |
int | build_global_texture_set (ros::Publisher *p_marker_pub) |
c_polygon_primitive_with_texture (ros::NodeHandle *n) | |
int | compute_mean_and_std (std::vector< float > *v, float *mean, float *std) |
int | compute_projection_union (void) |
int | create_textures_vizualization_msg (visualization_msgs::MarkerArray *marker_vec, bool reset_id=false) |
int | erase_old_markers (visualization_msgs::MarkerArray *marker_vec, unsigned int from, unsigned int to, std::string namesp) |
int | get_mesh_statistics (void) |
int | publish_to_rviz (ros::Publisher *p_marker_pub) |
int | readapt_to_new_plane (polygon_primitive_msg::polygon_primitive *new_plg) |
![]() | |
c_polygon_primitive (ros::NodeHandle *node, const char *name="unamed", unsigned char r=0, unsigned char g=0, unsigned char b=0) | |
Constructor. Allocates space for the required objecs. More... | |
void | compute_concave_hull (pcl::PointCloud< pcl::PointXYZ >::Ptr pcin, pcl::PointCloud< pcl::PointXYZ >::Ptr pcout, const pcl::ModelCoefficients::Ptr coeff) |
Computes the concave_hull of a given point cloud. More... | |
void | compute_convex_hull (const pcl::PointCloud< pcl::PointXYZ >::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud< pcl::PointXYZ >::Ptr pcout) |
Uses pcl library to compute the convex hull of a set of points in pcin, by projecting them first to the plane defined by coeff. More... | |
void | compute_convex_hull_cgal (const pcl::PointCloud< pcl::PointXYZ >::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud< pcl::PointXYZ >::Ptr pcout, tf::Transform *tr, double &area, double &solidity, bool flg=false) |
void | compute_convex_hull_cgal (const pcl::PointCloud< pcl::PointXYZ >::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud< pcl::PointXYZ >::Ptr pcout, tf::Transform *tr) |
Uses cgal to compute the convex hull of the points in pcin. First, points are projected to the plane defined by coeff. Outputs the area and solidity of the hull. More... | |
int | compute_supporting_perpendicular_plane_ransac (pcl::PointCloud< pcl::PointXYZ > *pc_in, pcl::PointCloud< pcl::Normal > *n_in, double DistanceThreshold, double NormalDistanceWeight, int MaxIterations, pcl::PointIndices::Ptr ind_out, pcl::ModelCoefficients::Ptr coeff_out) |
int | compute_supporting_plane_ransac (pcl::PointCloud< pcl::PointXYZ > *input_cloud, pcl::PointCloud< pcl::Normal > *input_normals, double DistanceThreshold, double NormalDistanceWeight, int MaxIterations, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients) |
visualization_msgs::Marker | create_visualization_marker_header (std::string frame_id, ros::Time stamp, std::string name, int action, int id, int type, double px, double py, double pz, double qx, double qy, double qz, double qw, double sx, double sy, double sz, double cr, double cg, double cb, double alpha) |
int | create_vizualization_msgs (visualization_msgs::MarkerArray *marker_vec, unsigned int id_start=0) |
int | export_to_polygon_primitive_msg (polygon_primitive_msg::polygon_primitive *msg) |
int | import_from_polygon_primitive_msg (polygon_primitive_msg::polygon_primitive *msg) |
int | indices_extraction (pcl::PointIndices::Ptr ind, pcl::PointCloud< pcl::PointXYZ > *input_cloud, pcl::PointCloud< pcl::PointXYZ > *remove_cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr copy_cloud, pcl::PointCloud< pcl::Normal > *input_normals, pcl::PointCloud< pcl::Normal > *remove_normals, int compute_normals=1) |
Extracts points from input pc and copies them to copy_cloud. Does the same with normals. More... | |
int | polygon_create (pcl::PointCloud< pcl::PointXYZ > *input_cloud, pcl::PointCloud< pcl::Normal > *input_normals, double DistanceThreshold=0.5, double NormalDistanceWeight=0.5, int MaxIterations=1000, int do_spatial_division=0) |
Computes a polygon primitive candidate from an input point cloud and its normals. More... | |
int | polygon_expansion (pcl::PointCloud< pcl::PointXYZ > *input_cloud, double longitudinal_offset=0.2, double perpendicular_offset=0.3, pcl::PointCloud< pcl::Normal > *input_normals=NULL) |
Grows polygon by adding points from the input pc that are close to the plane and inside the convex hull. First perfoms a longitudinal expansion of the convex hull, and then selects points which are in the prisma defined by the perpeddicular -/+ offset of the extended convex hull. More... | |
void | polygon_split (pcl::PointCloud< pcl::PointXYZ >::Ptr pcin, pcl::PointCloud< pcl::PointXYZ >::Ptr pcdumpster, pcl::ModelCoefficients::Ptr coeff) |
int | print_polygon_information (void) |
void | project_pc_to_plane (pcl::PointCloud< pcl::PointXYZ >::Ptr pcin, pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud< pcl::PointXYZ >::Ptr pcout) |
Projects all the points in pcin to a plane (along the normal to that plane) defined by coeff and stores the projected points in pcout. More... | |
~c_polygon_primitive () | |
Destructor. Frees the space of objects. More... | |
Public Attributes | |
class_colormap * | colormap |
std::vector < class_camera_projection > | cp |
class_constrained_delaunay_triangulation | dp |
pthread_mutex_t | mutex |
pcl::PointCloud< pcl::PointXYZ > | next_triangle |
pthread_t | thread |
class_texture_set | ts |
![]() | |
t_polygon_primitive_data | data |
struct { | |
pcl::PointCloud< pcl::PointXYZ > ::Ptr additional | |
A point cloud with all supporting points. More... | |
pcl::PointCloud< pcl::PointXYZ > ::Ptr all | |
pcl::PointCloud< pcl::PointXYZ > ::Ptr growed | |
The points that are to be added to the point cloud after an expand operation. More... | |
pcl::PointCloud< pcl::PointXYZ > ::Ptr projected | |
A point cloud with all supporting points. More... | |
pcl::PointCloud< pcl::PointXYZ > ::Ptr tmp | |
Dont know. More... | |
} | pointclouds |
A structure containing all the point clouds needed to represent the polygon primitive. More... | |
ros::NodeHandle * | rosnode |
Definition at line 54 of file polygon_primitive_with_texture.h.
|
inline |
Definition at line 61 of file polygon_primitive_with_texture.h.
int c_polygon_primitive_with_texture::add_camera_projection_to_triangle_mesh | ( | int | projection_index, |
ros::Publisher * | p_marker_pub | ||
) |
int c_polygon_primitive_with_texture::build_global_texture_set | ( | ros::Publisher * | p_marker_pub | ) |
class_colormap* c_polygon_primitive_with_texture::colormap |
Definition at line 113 of file polygon_primitive_with_texture.h.
std::vector<class_camera_projection> c_polygon_primitive_with_texture::cp |
Definition at line 109 of file polygon_primitive_with_texture.h.
class_constrained_delaunay_triangulation c_polygon_primitive_with_texture::dp |
Definition at line 106 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 143 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 149 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 151 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 145 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 139 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 129 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 131 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 133 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 141 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 135 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 147 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 159 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 161 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 137 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 164 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 153 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 155 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 157 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 127 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 125 of file polygon_primitive_with_texture.h.
pthread_mutex_t c_polygon_primitive_with_texture::mutex |
Definition at line 114 of file polygon_primitive_with_texture.h.
pcl::PointCloud<pcl::PointXYZ> c_polygon_primitive_with_texture::next_triangle |
Definition at line 111 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 144 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 150 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 152 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 146 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 140 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 130 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 132 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 134 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 142 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 136 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 148 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 160 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 162 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 138 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 154 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 156 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 158 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 128 of file polygon_primitive_with_texture.h.
|
private |
Definition at line 126 of file polygon_primitive_with_texture.h.
pthread_t c_polygon_primitive_with_texture::thread |
Definition at line 115 of file polygon_primitive_with_texture.h.
class_texture_set c_polygon_primitive_with_texture::ts |
Definition at line 112 of file polygon_primitive_with_texture.h.