19 #ifndef RQT_MULTIPLOT_BAG_READER_H 20 #define RQT_MULTIPLOT_BAG_READER_H 25 #include <QStringList> 43 void read(
const QString& fileName);
46 bool subscribe(
const QString& topic, QObject* receiver,
48 Qt::ConnectionType type = Qt::AutoConnection);
49 bool unsubscribe(
const QString& topic, QObject* receiver,
50 const char* method = 0);
65 Impl(QObject* parent = 0);
void read(const QString &fileName)
void readingFailed(const QString &error)
bool unsubscribe(const QString &topic, QObject *receiver, const char *method=0)
QMap< int, QVariant > PropertyMap
bool subscribe(const QString &topic, QObject *receiver, const char *method, const PropertyMap &properties=PropertyMap(), Qt::ConnectionType type=Qt::AutoConnection)
void queryAboutToBeDestroyed()
QString getFileName() const
bool event(QEvent *event)
void readingProgressChanged(double progress)
BagReader(QObject *parent=0)
QMap< QString, BagQuery * > queries_
void messageRead(const QString &topic, const Message &message)