Go to the documentation of this file.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
00028
00029
00030
00031 #ifndef IMAGE_ALGOS_PCD_TO_IMAGE_PROJECTOR_H
00032 #define IMAGE_ALGOS_PCD_TO_IMAGE_PROJECTOR_H
00033 #include <fstream>
00034 #include <image_algos/image_algos.h>
00035 #include <ros/ros.h>
00036 #include <ros/node_handle.h>
00037 #include <image_transport/image_transport.h>
00038 #include <opencv/cv.h>
00039 #include <opencv/highgui.h>
00040 #include <cv_bridge/CvBridge.h>
00041 #include <image_geometry/pinhole_camera_model.h>
00042 #include <tf/transform_listener.h>
00043 #include <boost/foreach.hpp>
00044 #include <tf/transform_broadcaster.h>
00045 #include <angles/angles.h>
00046 #include <sensor_msgs/PointCloud.h>
00047 #include <geometry_msgs/Polygon.h>
00048
00049 #include <boost/thread/mutex.hpp>
00050
00051 namespace image_algos
00052 {
00053
00054 class PCDToImageProjector : public ImageAlgo
00055 {
00056 public:
00057 PCDToImageProjector ()
00058 {
00059 };
00060 typedef sensor_msgs::Image InputType;
00061 typedef sensor_msgs::PointCloud InputTypeII;
00062
00063 typedef IplImage* OutputType;
00064
00065 static std::string default_input_topic ()
00066 {return std::string ("image");}
00067
00068 static std::string default_output_topic ()
00069 {return std::string ("roi");};
00070
00071 static std::string default_node_name ()
00072 {return std::string ("pcd_to_image_projector_node");};
00073
00074 void init (ros::NodeHandle&);
00075 void pre ();
00076 void post ();
00077 std::vector<std::string> requires ();
00078 std::vector<std::string> provides ();
00079
00080 void project_3D_point(const double &x, const double &y, const double &z, int &row, int &column);
00081 std::string process (sensor_msgs::PointCloud &cloud_in, IplImage *image);
00082 std::string process (geometry_msgs::Polygon &cloud_in, IplImage *image);
00083 OutputType output ();
00084
00085
00086
00087 ros::NodeHandle nh_;
00088 image_transport::Publisher image_pub_;
00089 image_transport::Subscriber image_sub_;
00090 ros::Subscriber cloud_sub_;
00091
00092 tf::TransformListener tf_listener_;
00093
00094
00095 sensor_msgs::CvBridge bridge_;
00096
00097 OutputType subimage_;
00098 std::string input_image_topic_, input_cloud_topic_, output_cluster_topic_, output_image_topic_;
00099
00100 double focal_length_, proj_center_x_, proj_center_y_, pix_size_x_, pix_size_y_;
00101
00102
00103
00104 std::string origin_, interim_, child_;
00105 boost::mutex cloud_lock_;
00106 std::vector <sensor_msgs::PointCloud> cloud_queue_;
00107 };
00108
00109 }
00110 #endif
00111
00112