Main Page
Namespaces
Classes
Files
File List
File Members
src
gauges.cpp
Go to the documentation of this file.
1
2
#include <
mainwindow.h
>
3
#include <QApplication>
4
5
namespace
gauges
6
{
7
QcNeedleItem
*
theNeedle
;
// Get access to this Qt member
8
}
9
10
void
newDataCallback
(
const
std_msgs::Float64& msg);
11
12
int
main
(
int
argc,
char
** argv) {
13
ros::init
(argc, argv,
"gauge_node"
);
14
ros::NodeHandle
nh;
15
ros::AsyncSpinner
* spinner;
16
spinner =
new
ros::AsyncSpinner
(1);
17
spinner->
start
();
18
19
// Subscribe to new data
20
std::string topicName;
21
nh.
getParam
(
"topic"
, topicName);
22
ros::Subscriber
listener = nh.
subscribe
(topicName, 1,
newDataCallback
);
23
24
QApplication qtApp(argc, argv);
25
MainWindow
window(0, &nh);
26
window.show();
27
gauges::theNeedle
= window.
mSpeedNeedle
;
// Get access to this Qt member
28
29
// Show the graphic. This is blocking and it must be in the main thread,
30
// so I used multithreaded ROS spinners to get around it.
31
qtApp.exec();
32
33
// Multithreaded spinner
34
ros::waitForShutdown
();
35
36
ros::shutdown
();
37
return
0;
38
}
39
40
void
newDataCallback
(
const
std_msgs::Float64& msg)
41
{
42
gauges::theNeedle
-> setCurrentValue(msg.data);
43
}
ros::NodeHandle
QcNeedleItem
Definition:
qcgaugewidget.h:271
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
newDataCallback
void newDataCallback(const std_msgs::Float64 &msg)
Definition:
gauges.cpp:40
gauges
Definition:
gauges.cpp:5
ros::AsyncSpinner::start
void start()
mainwindow.h
ros::Subscriber
main
int main(int argc, char **argv)
Definition:
gauges.cpp:12
ros::NodeHandle::getParam
bool getParam(const std::string &key, std::string &s) const
ros::shutdown
ROSCPP_DECL void shutdown()
MainWindow::mSpeedNeedle
QcNeedleItem * mSpeedNeedle
Definition:
mainwindow.h:52
gauges::theNeedle
QcNeedleItem * theNeedle
Definition:
gauges.cpp:7
MainWindow
Definition:
mainwindow.h:45
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
ros::AsyncSpinner
gauges
Author(s): alexvs
autogenerated on Mon Nov 14 2016 03:55:02