Header of the extract polygon primitives binary. More...
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_listener.h>
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <wrapper_collada.h>
#include "polygon_primitive.h"
Go to the source code of this file.
Defines | |
#define | _EXTERN_ extern |
#define | _MAX_NUM_POLYGONS_ 270 |
#define | PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);} |
Ros includes. | |
Functions | |
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) |
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) |
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) |
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) |
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) |
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. | |
void | PointCloudHandler (const sensor_msgs::PointCloud2ConstPtr &input) |
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 <filename> -normal 10 -normal_scale 1" to view the normals. | |
void | VehiclePoseHandler (const geometry_msgs::PoseStamped &lpose) |
Variables | |
unsigned char | b [16] |
_EXTERN_ pcl::PointCloud < pcl::PointXYZ > | cloud |
unsigned char | cr [16] |
_EXTERN_ int | flag_msg_received |
unsigned char | g [16] |
_EXTERN_ ros::Time | laser_ts |
_EXTERN_ ros::NodeHandle * | pn |
_EXTERN_ std::vector < boost::shared_ptr < ros::Publisher > > | publishers |
Header of the extract polygon primitives binary.
Definition in file extract_polygon_primitives.h.