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
00032
00033
00034
00035
00036
00037
00038 #include "pcl/pcl_config.h"
00039
00040 #ifndef PCL_IO_ROBOT_EYE_GRABBER_H_
00041 #define PCL_IO_ROBOT_EYE_GRABBER_H_
00042
00043 #include <pcl/io/grabber.h>
00044 #include <pcl/io/impl/synchronized_queue.hpp>
00045 #include <pcl/point_types.h>
00046 #include <pcl/point_cloud.h>
00047 #include <boost/asio.hpp>
00048 #include <boost/thread/thread.hpp>
00049
00050 namespace pcl
00051 {
00052
00056 class PCL_EXPORTS RobotEyeGrabber : public Grabber
00057 {
00058 public:
00059
00064 typedef void (sig_cb_robot_eye_point_cloud_xyzi) (
00065 const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
00066
00068 RobotEyeGrabber ();
00069
00071 RobotEyeGrabber (const boost::asio::ip::address& ipAddress, unsigned short port=443);
00072
00074 virtual ~RobotEyeGrabber () throw ();
00075
00078 virtual void start ();
00079
00081 virtual void stop ();
00082
00086 virtual std::string getName () const;
00087
00091 virtual bool isRunning () const;
00092
00095 virtual float getFramesPerSecond () const;
00096
00100 void setSensorAddress (const boost::asio::ip::address& ipAddress);
00101 const boost::asio::ip::address& getSensorAddress () const;
00102
00106 void setDataPort (unsigned short port);
00107 unsigned short getDataPort () const;
00108
00112 void setSignalPointCloudSize (std::size_t numerOfPoints);
00113 std::size_t getSignalPointCloudSize () const;
00114
00119 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> > getPointCloud() const;
00120
00121 private:
00122
00123 bool terminate_thread_;
00124 size_t signal_point_cloud_size_;
00125 unsigned short data_port_;
00126 unsigned char receive_buffer_[500];
00127
00128 boost::asio::ip::address sensor_address_;
00129 boost::asio::ip::udp::endpoint sender_endpoint_;
00130 boost::asio::io_service io_service_;
00131 boost::shared_ptr<boost::asio::ip::udp::socket> socket_;
00132 boost::shared_ptr<boost::thread> socket_thread_;
00133 boost::shared_ptr<boost::thread> consumer_thread_;
00134
00135 pcl::SynchronizedQueue<boost::shared_array<unsigned char> > packet_queue_;
00136 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> > point_cloud_xyzi_;
00137 boost::signals2::signal<sig_cb_robot_eye_point_cloud_xyzi>* point_cloud_signal_;
00138
00139 void consumerThreadLoop ();
00140 void socketThreadLoop ();
00141 void asyncSocketReceive ();
00142 void resetPointCloud ();
00143 void socketCallback (const boost::system::error_code& error, std::size_t numberOfBytes);
00144 void convertPacketData (unsigned char *dataPacket, size_t length);
00145 void computeXYZI (pcl::PointXYZI& pointXYZI, unsigned char* pointData);
00146 };
00147 }
00148
00149 #endif