36 #ifndef _polygon_primitive_with_texture_H_
37 #define _polygon_primitive_with_texture_H_
40 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
50 #include <colormap/colormap.h>
82 std::string str=
"hot";
83 colormap = (class_colormap*)
new class_colormap(str,8, 1,
false);
84 mutex = PTHREAD_MUTEX_INITIALIZER;
96 int erase_old_markers(visualization_msgs::MarkerArray* marker_vec,
unsigned int from,
unsigned int to, std::string namesp);
101 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);
109 std::vector<class_camera_projection>
cp;
int readapt_to_new_plane(polygon_primitive_msg::polygon_primitive *new_plg)
std::string ns_next_triangle
unsigned int id_camera_position
std::string ns_visited_faces
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 build_global_texture_set(ros::Publisher *p_marker_pub)
int publish_to_rviz(ros::Publisher *p_marker_pub)
std::string ns_camera_intersection
unsigned int id_camera_canvas
pcl::PointCloud< pcl::PointXYZ > next_triangle
std::vector< class_camera_projection > cp
The polygon_primitive class. Defines methods for polygon extraction and expansion from a point cloud...
unsigned int id_constraints
unsigned int id_projection_union_vertices
unsigned int id_next_triangle
std::string ns_camera_intersection_vertices
int add_camera_projection_to_triangle_mesh(int projection_index, ros::Publisher *p_marker_pub)
std::string ns_triangle_vertices
std::string ns_projection_union_vertices
unsigned int id_camera_intersection_vertices
std::string ns_local_mesh
int compute_mean_and_std(std::vector< float > *v, float *mean, float *std)
Header for constrained delaunay triangulation.
unsigned int id_local_mesh
unsigned int id_visited_faces
unsigned int id_vertices_indices
std::string ns_camera_position
unsigned int id_triangle_edges
class_colormap * colormap
std::string ns_textured_triangles
int erase_old_markers(visualization_msgs::MarkerArray *marker_vec, unsigned int from, unsigned int to, std::string namesp)
std::string ns_projection_union
unsigned int id_textured_triangles
size_t ask_for_number(void)
std::string ns_camera_canvas
int create_textures_vizualization_msg(visualization_msgs::MarkerArray *marker_vec, bool reset_id=false)
unsigned int id_projection_union
std::string ns_projection_name
class_constrained_delaunay_triangulation dp
std::string ns_vertices_indices
header for textured triangle
A class c_polygon_primitive that contains information about a detected polygon primitive as well as t...
unsigned int id_proveniences
c_polygon_primitive_with_texture(ros::NodeHandle *n)
The class camera_projection performs the projection of an image into a polygon plane.
int build_global_mesh(ros::Publisher *p_marker_pub)
unsigned int id_triangle_vertices
int get_mesh_statistics(void)
std::string ns_constraints
std::string ns_triangle_edges
std::string ns_proveniences
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)
unsigned int id_camera_intersection
unsigned int id_projection_name
int compute_projection_union(void)