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
00036 #ifndef _extract_polygon_primitives_H_
00037 #define _extract_polygon_primitives_H_
00038
00039
00040
00041
00042
00043
00044
00046 #include <ros/ros.h>
00047 #include <sensor_msgs/PointCloud2.h>
00048 #include <tf/transform_listener.h>
00049
00051 #include <pcl/ros/conversions.h>
00052 #include <pcl/point_cloud.h>
00053 #include <pcl/point_types.h>
00054 #include <pcl/segmentation/sac_segmentation.h>
00055
00057 #include <visualization_msgs/Marker.h>
00058 #include <visualization_msgs/MarkerArray.h>
00059
00061 #include <wrapper_collada.h>
00062
00064 #include "polygon_primitive.h"
00065
00066
00067
00068
00069
00070 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
00071 #define _MAX_NUM_POLYGONS_ 270
00072
00073
00075
00077
00079
00081
00082
00083 void create_publish_marker_array(std::vector<c_polygon_primitive> *plg, visualization_msgs::MarkerArray *marker_array_msg);
00084 visualization_msgs::Marker create_visualization_marker_header(
00085 std::string frame_id, ros::Time stamp, std::string name,
00086 int action, int id, int type,
00087 double px, double py, double pz,
00088 double qx, double qy, double qz, double qw,
00089 double sx, double sy, double sz,
00090 double cr, double cg, double cb, double alpha);
00091
00092
00093 void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& input);
00094 void VehiclePoseHandler(const geometry_msgs::PoseStamped& lpose);
00095
00096
00097
00098
00099 void filter_uncoherent_points(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ> *pcout, pcl::PointCloud<pcl::PointXYZ> *pcelim,pcl::PointCloud<pcl::Normal>::Ptr n ,double radius, float vx, float vy, float vz);
00100 void filter_uncoherent_points(pcl::PointCloud<pcl::PointNormal>::Ptr pc, double radius, pcl::PointCloud<pcl::PointNormal>::Ptr pcout, pcl::PointCloud<pcl::PointNormal>::Ptr pcelim,float vx, float vy, float vz);
00101 void draw_markers(int k, Eigen::Vector4f* q_avg, std::vector<Eigen::Vector4f>* qv, pcl::PointCloud<pcl::PointNormal>::Ptr pc, std::vector<int>* pointIdxRadiusSearch, Eigen::Vector4f* q_avg0, std::vector<bool>* is_fliped);
00102 int compute_normals(pcl::PointCloud<pcl::PointXYZ>* pc_in, float vx, float vy, float vz, float radius, int K, pcl::PointCloud<pcl::Normal>* pc_out);
00103 int save_pc_PointNormal_to_pcd(pcl::PointCloud<pcl::PointXYZ>* pc_in, pcl::PointCloud<pcl::Normal>* normals_in, std::string name);
00104 int get_vehicle_position(ros::NodeHandle *pn, tf::TransformListener* listener, tf::StampedTransform* vehicle_tf, ros::Time* t);
00105
00107
00109 #ifdef _extract_polygon_primitives_CPP_
00110
00111 #define _EXTERN_
00112 unsigned char cr[16]={0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
00113 unsigned char g[16]={0, 16, 32, 49, 65, 81, 97, 113, 130, 146, 162, 178, 194, 210, 227, 243};
00114 unsigned char b[16]={255, 247, 239, 231, 223, 215, 206, 198, 190, 182, 174, 166, 158, 150, 142, 134};
00115
00116 #else
00117
00118 #define _EXTERN_ extern
00119 extern unsigned char cr[16];
00120 extern unsigned char g[16];
00121 extern unsigned char b[16];
00122
00123 #endif
00124
00125 _EXTERN_ std::vector<boost::shared_ptr<ros::Publisher> > publishers;
00126 _EXTERN_ pcl::PointCloud<pcl::PointXYZ> cloud;
00127 _EXTERN_ ros::Time laser_ts;
00128 _EXTERN_ int flag_msg_received;
00129 _EXTERN_ ros::NodeHandle *pn;
00130 #endif
00131