00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00033 #pragma once
00034 #ifndef BUT_PLANE_DET_DynModelExporter_H
00035 #define BUT_PLANE_DET_DynModelExporter_H
00036
00037
00038 #include <ros/ros.h>
00039 #include <tf/transform_listener.h>
00040 #include <tf/message_filter.h>
00041 #include <tf/tfMessage.h>
00042
00043
00044 #include <pcl/point_types.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/ModelCoefficients.h>
00047 #include <opencv2/highgui/highgui.hpp>
00048
00049 #include <visualization_msgs/Marker.h>
00050 #include <pcl/surface/convex_hull.h>
00051 #include <pcl/surface/concave_hull.h>
00052
00053 #include <srs_env_model_percp/but_segmentation/normals.h>
00054 #include <srs_env_model_percp/but_plane_detector/plane.h>
00055
00056 #include <cob_3d_mapping_msgs/Shape.h>
00057 #include <cob_3d_mapping_msgs/ShapeArray.h>
00058 #include <visualization_msgs/Marker.h>
00059 #include <visualization_msgs/MarkerArray.h>
00060
00061 namespace srs_env_model_percp
00062 {
00067 class ExportedPlane
00068 {
00069 public:
00070 ExportedPlane(): plane(but_plane_detector::Plane<float>(0.0, 0.0, 0.0, 0.0) ) {}
00071 int id;
00072 ros::Time update;
00073 bool is_deleted;
00074 bool to_be_deleted;
00075 srs_env_model_percp::PlaneExt plane;
00076 public:
00077 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00078 };
00079
00080 class PointError
00081 {
00082 public:
00083 PointError(int i_id, double i_error, bool i_deleted)
00084 {
00085 id = i_id;
00086 error = i_error;
00087 deleted = i_deleted;
00088 }
00089 int id;
00090 double error;
00091 bool deleted;
00092 public:
00093 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00094 };
00095
00096 class DynModelExporter
00097 {
00098 public:
00099 typedef but_plane_detector::Plane<float> tPlane;
00100 typedef std::vector<tPlane, Eigen::aligned_allocator<tPlane> > tPlanes;
00101 typedef std::vector<ExportedPlane, Eigen::aligned_allocator<ExportedPlane> > tExportedPlanes;
00102 public:
00106 DynModelExporter(ros::NodeHandle *node,
00107 const std::string& original_frame,
00108 const std::string& output_frame,
00109 int minOutputCount,
00110 double max_distance,
00111 double max_plane_normal_dev,
00112 double max_plane_shift_dev,
00113 int keep_tracking,
00114 int ttl,
00115 int max_poly_size
00116 );
00122 void update(tPlanes & planes, but_plane_detector::Normals &normals, std::string color_method = "plane_eq", cv::Mat rgb = cv::Mat());
00123
00124 void getMarkerArray(visualization_msgs::MarkerArray &message, std::string output_frame_id);
00125 void getShapeArray(cob_3d_mapping_msgs::ShapeArray &message, std::string output_frame_id);
00126
00127 void createMarkerForConcaveHull(pcl::PointCloud<pcl::PointXYZ>& plane_cloud, srs_env_model_percp::PlaneExt& plane);
00128 void addMarkerToConcaveHull(pcl::PointCloud<pcl::PointXYZ>& plane_cloud, srs_env_model_percp::PlaneExt& plane);
00129
00130 void xmlFileExport(std::string filename);
00131 void xmlFileImport(std::string filename);
00132
00133
00134 tExportedPlanes displayed_planes;
00135 private:
00136
00140 ros::NodeHandle *n;
00141
00146 int m_keep_tracking;
00147
00148 std::string original_frame_, output_frame_;
00149
00150 int m_minOutputCount;
00151 double m_max_distance;
00152 double m_max_plane_normal_dev;
00153 double m_max_plane_shift_dev;
00154 int m_max_poly_size;
00155
00156 int m_plane_ttl;
00157 };
00158 }
00159
00160 #endif