extract_polygon_primitives.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
36 #ifndef _extract_polygon_primitives_H_
37 #define _extract_polygon_primitives_H_
38 
39 
40 
41 // ___________________________________
42 // | |
43 // | INCLUDES |
44 // |_________________________________|
46 #include <ros/ros.h>
47 #include <sensor_msgs/PointCloud2.h>
48 #include <tf/transform_listener.h>
49 
51 #include <pcl/ros/conversions.h>
52 #include <pcl/point_cloud.h>
53 #include <pcl/point_types.h>
54 #include <pcl/segmentation/sac_segmentation.h>
55 
57 #include <visualization_msgs/Marker.h>
58 #include <visualization_msgs/MarkerArray.h>
59 
61 #include <wrapper_collada/wrapper_collada.h>
62 
64 #include "polygon_primitive.h"
65 
66 // ___________________________________
67 // | |
68 // | DEFINES |
69 // |_________________________________|
70 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
71 #define _MAX_NUM_POLYGONS_ 270
72 //#define _MAX_NUM_POLYGONS_ 2
73 
75 //TYPE DEFINITIONS
77 
79 //FUNCTIONS PROTOTYPES
81 
82 //defined in extract_polygon_primitives_rvizmarkers.cpp
83 void create_publish_marker_array(std::vector<c_polygon_primitive> *plg, visualization_msgs::MarkerArray *marker_array_msg);
84 visualization_msgs::Marker create_visualization_marker_header(
85  std::string frame_id, ros::Time stamp, std::string name,
86  int action, int id, int type,
87  double px, double py, double pz,
88  double qx, double qy, double qz, double qw,
89  double sx, double sy, double sz,
90  double cr, double cg, double cb, double alpha);
91 
92 //defined in extract_polygon_primitives_handlers.cpp
93 void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& input);
94 void VehiclePoseHandler(const geometry_msgs::PoseStamped& lpose);
95 
96 
97 //defined in extract_polygon_primitives_auxiliary.cpp
98 //void filter_uncoherent_points(pcl::PointCloud<pcl::PointNormal>::Ptr pc, double radius, pcl::PointCloud<pcl::PointNormal>::Ptr pcout);
99 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);
100 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);
101 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);
102 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);
103 int save_pc_PointNormal_to_pcd(pcl::PointCloud<pcl::PointXYZ>* pc_in, pcl::PointCloud<pcl::Normal>* normals_in, std::string name);
104 int get_vehicle_position(ros::NodeHandle *pn, tf::TransformListener* listener, tf::StampedTransform* vehicle_tf, ros::Time* t);
105 
107 //GLOBAL VARIABLES
109 #ifdef _extract_polygon_primitives_CPP_
110 
111 #define _EXTERN_
112 unsigned char cr[16]={0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
113 unsigned char g[16]={0, 16, 32, 49, 65, 81, 97, 113, 130, 146, 162, 178, 194, 210, 227, 243};
114 unsigned char b[16]={255, 247, 239, 231, 223, 215, 206, 198, 190, 182, 174, 166, 158, 150, 142, 134};
115 
116 #else
117 
118 #define _EXTERN_ extern
119 extern unsigned char cr[16];
120 extern unsigned char g[16];
121 extern unsigned char b[16];
122 
123 #endif
124 
125 _EXTERN_ std::vector<boost::shared_ptr<ros::Publisher> > publishers;
126 _EXTERN_ pcl::PointCloud<pcl::PointXYZ> cloud;
127 _EXTERN_ ros::Time laser_ts;
129 _EXTERN_ ros::NodeHandle *pn; //The node handle
130 #endif
131 
void VehiclePoseHandler(const geometry_msgs::PoseStamped &lpose)
_EXTERN_ ros::Time laser_ts
int get_vehicle_position(ros::NodeHandle *pn, tf::TransformListener *listener, tf::StampedTransform *vehicle_tf, ros::Time *t)
Gets the vehicle position by querying for the propper transform.
_EXTERN_ std::vector< boost::shared_ptr< ros::Publisher > > publishers
#define _EXTERN_
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)
_EXTERN_ int flag_msg_received
_EXTERN_ ros::NodeHandle * pn
unsigned char cr[16]
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)
Estimate normals for pc_in using either radius or K.
void create_publish_marker_array(std::vector< c_polygon_primitive > *plg, visualization_msgs::MarkerArray *marker_array_msg)
A class c_polygon_primitive that contains information about a detected polygon primitive as well as t...
unsigned char b[16]
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)
unsigned char g[16]
int save_pc_PointNormal_to_pcd(pcl::PointCloud< pcl::PointXYZ > *pc_in, pcl::PointCloud< pcl::Normal > *normals_in, std::string name)
Saves a composite point cloud with normals to a file. After saving you can use "rosrun pcl pcd_viewer...
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)
Definition: preh.h:63
void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr &input)
_EXTERN_ pcl::PointCloud< pcl::PointXYZ > cloud


polygon_primitives_extraction
Author(s): Miguel Oliveira
autogenerated on Mon Mar 2 2015 01:32:42