bagloader.h
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00015  */
00016 
00017 
00018 #ifndef OPENNI_LISTENER_H
00019 #define OPENNI_LISTENER_H
00020 #include "ros/ros.h"
00021 #include "parameter_server.h"
00022 #include <tf/transform_broadcaster.h>
00023 //#include <pcl_tf/transforms.h>
00024 #include <message_filters/subscriber.h>
00025 #include <sensor_msgs/PointCloud2.h>
00026 #include <qtconcurrentrun.h>
00027 #include <QImage> //for cvMat2QImage not listet here but defined in cpp file
00028 #include <QStringList> 
00029 #include <QMatrix4x4> 
00030 #include <rosbag/bag.h>
00031 
00032 //forward-declare to avoid including tf
00034 namespace tf{
00035   class TransformListener;
00036 }
00038 
00039 
00041 
00048 class BagLoader : public QObject {
00050   Q_OBJECT
00051   Q_SIGNALS:
00052     void setPointCloud(pointcloud_type * pc, QMatrix4x4 transformation);
00054     void setGUIInfo(QString message);
00055     void setGUIInfo2(QString message);
00057     void setGUIStatus(QString message);
00058     void bagFinished();
00059 
00060   public Q_SLOTS:
00062     void togglePause();
00063     void loadBagFileAsync(QString);
00064     void loadBagFileAsync(std::string);
00065     void clearPointCloud(pointcloud_type*);
00066 
00067   public:
00069 
00073     BagLoader();
00074 
00076     ~BagLoader();
00077     void callback(const sensor_msgs::PointCloud2ConstPtr& point_cloud);
00078 
00079   protected:
00080     void loadBag(std::string filename);
00082     void sendWithTransformation(pointcloud_type* cloud);
00083 
00084     rosbag::Bag bag;
00085     
00086     //ros::Publisher pc_pub; 
00087     /*unsigned int callback_counter_;*/
00088     bool pause_;
00089     tf::TransformListener* tflistener_; 
00090     ros::Publisher tf_pub_;
00091     int data_id_;
00092 };
00093 
00094 #endif


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45