rosNodeThread.h 1.15 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
#ifndef ___ROSNODETHREAD_H___
#define ___ROSNODETHREAD_H___

#include <QtCore>
#include <QThread>
#include <QStringList>
#include <stdlib.h>
#include <QMutex>
#include <iostream>
#include "assert.h"

#include <ros/ros.h>
#include <ros/network.h>
#include "d_fall_pps/ViconData.h"
roangel's avatar
roangel committed
15
16
#include "d_fall_pps/UnlabeledMarker.h"
#include "d_fall_pps/UnlabeledMarkersArray.h"
17
18
19
20
21
22

using namespace d_fall_pps;

class rosNodeThread : public QObject {
	Q_OBJECT
public:
23
    explicit rosNodeThread(int argc, char **pArgv, const char * topic, QObject *parent = 0);
24
25
26
27
    virtual ~rosNodeThread();

    bool init();

roangel's avatar
roangel committed
28
29
    // void messageCallback(const ViconData& data);
    void messageCallback(const UnlabeledMarkersArray::ConstPtr& p_msg);
30

31
32
33

signals:
    // void newViconData(double, double, double, double, double, double);
roangel's avatar
roangel committed
34
35
36
    // void newViconData(double, double);

    void newViconData(const UnlabeledMarkersArray::ConstPtr& p_msg);
37
38
39
40

public slots:
    void run();

41
42
43
44
45
46
47
private:
    int m_Init_argc;
    char** m_pInit_argv;
    const char * m_topic;

    QThread * m_pThread;

48
49
50
    ViconData m_vicon_data;

    ros::Subscriber m_vicon_subscriber;
51
52
53
54
    // ros::Publisher  sim_velocity;
};
#endif