27 #ifndef _c_trajectory_H_ 
   28 #define _c_trajectory_H_ 
   43 #include <visualization_msgs/Marker.h> 
   44 #include <visualization_msgs/MarkerArray.h> 
   45 #include <tf/transform_listener.h> 
   46 #include <pcl_ros/transforms.h> 
   47 #include <pcl/conversions.h> 
   48 #include <pcl/point_cloud.h> 
   49 #include <pcl/point_types.h> 
   50 #include <pcl/segmentation/extract_polygonal_prism_data.h> 
   51 #include <pcl/filters/extract_indices.h> 
   52 #include <pcl/filters/project_inliers.h> 
   53 #include <pcl/filters/voxel_grid.h> 
   58 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__); 
   59 #define _USE_MATH_DEFINES 
   60 #define _TRAJECTORY_LIB_DEBUG_ 1 
   92                         #if _TRAJECTORY_LIB_DEBUG_  
   93                                 printf(
"Constructor - Defining D...\n");
 
   99                         #if _TRAJECTORY_LIB_DEBUG_  
  100                                 printf(
"Destructor...\n");
 
  106                 vector<vector<t_lines> > v_lines;
 
  143                 void create_markers(std::vector<visualization_msgs::Marker>* marker_vec, 
int* marker_count, 
int num_traj);
 
vector< double > total_arc
boost::shared_ptr< c_trajectory > c_trajectoryPtr
vector< tf::Transform > ltrans
c_trajectory(double D_in)
vector< t_point > collision_pts