comthread.h
Go to the documentation of this file.
00001 
00047 #ifndef COMTHREAD_H
00048 #define COMTHREAD_H
00049 
00050 #include <QThread>
00051 #include <QStringList>
00052 #include <sensor_msgs/PointCloud2.h>
00053 #include <pcl/point_cloud.h>
00054 #include <pcl/point_types.h>
00055 #include <ros/subscriber.h>
00056 #include <QMutex>
00057 #include <QDir>
00058 #include <tf/transform_listener.h>
00059 
00060 namespace pcl {
00061 namespace visualization {
00062 class CloudViewer;
00063 }
00064 };
00065 
00066 typedef pcl::PointXYZRGB PointType;
00067 
00071 class ComThread : public QThread
00072 {
00073     Q_OBJECT
00074 public:
00075     explicit ComThread(QObject *parent = 0);
00076 
00077     virtual ~ComThread();
00078 
00083     void pointCloudReceived(const sensor_msgs::PointCloud2ConstPtr& pcl_msg);
00084 
00089     void loadPointCloud(const QString& filename);
00090 
00096     bool createPreview(QDir& model_dir);
00097 
00098 Q_SIGNALS:
00103     void addStatusMessage(QString);
00108     void newCloudReceived(QString);
00109 
00110 public Q_SLOTS:
00111     void recording(bool startstop);
00115     void reset();
00120     void removeCloud(QStringList);
00125     void selectCloud(QStringList);
00126 
00131     void changedBoxSize(double);
00132 
00138     void createRe_visionModel(QDir& parent_dir, const QString& model_name);
00144     void createKinectModel(QDir& parent_dir, const QString& model_name);
00145 
00150     void maxScanNumberChanged(int);
00151 
00156     void markerSizeChanged(double value);
00157     
00162     void markerSpacingChanged(double value);
00163 
00164 protected:
00165     void run();
00166 
00171     void getMergedPointCloud(pcl::PointCloud<PointType>& merged_pcl);
00176     void saveMergedPCL(QString);
00181     void saveFaces(QDir);
00187     int addPointCloud(boost::shared_ptr<pcl::PointCloud<PointType> > cloud);
00188 
00189     tf::TransformListener tf;
00190     ros::Subscriber sub;
00191     bool isRecording;
00192     std::map<int, boost::shared_ptr< pcl::PointCloud<PointType> > > pcls;
00193     int npoints;
00194     pcl::visualization::CloudViewer* cloudViewer;
00195     QMutex mutex;
00196 
00198     unsigned int max_pointclouds;
00199 };
00200 
00201 #endif // COMTHREAD_H
00202 


re_object_recorder
Author(s): Andreas Koch
autogenerated on Sun Jan 5 2014 11:39:12