qnode.cpp
Go to the documentation of this file.
1 #include "qnode.h"
2 #include <ros/master.h>
3 #include <QStringList>
4 
5 using namespace std;
6 
7 QNode::QNode(int argc, char** argv)
8  : argc(argc),
9  argv(argv)
10 {
11 }
12 
14 {
15  if(ros::isStarted())
16  {
17  ros::shutdown();
18  ros::waitForShutdown();
19  }
20  wait();
21 }
22 
24 {
25  ros::init(argc, argv,"dashboard");
26 
27  if(!ros::master::check()) {
28  return false;
29  }
30 
31  nh = unique_ptr<ros::NodeHandle>(new ros::NodeHandle);
32 
33  encoder_subscriber = nh->subscribe("encoders", 1, &QNode::encoderCallback, this);
34 
35  start();
36  return true;
37 }
38 
39 void QNode::run()
40 {
41  ros::Rate rate(1);
42  while(ros::ok())
43  {
44  ros::spinOnce();
45  ros::V_string nodes;
46  if(ros::master::getNodes(nodes))
47  {
48  QStringList nodesList;
49  for(auto node : nodes)
50  nodesList.append(QString(node.c_str()));
51  newNodesList(nodesList);
52  }
53  rate.sleep();
54  }
55  ros::spin();
56 
57  cout << "ROS shutting down. Closing dashboard GUI." << endl;
58  emit rosShutdown();
59 }
60 
61 void QNode::encoderCallback(const igvc_msgs::velocity_pair &msg)
62 {
63  emit newVelocityData(fabs((msg.left_velocity + msg.right_velocity) / 2.));
64 }
bool init()
Definition: qnode.cpp:23
void newNodesList(QStringList nodes)
void run()
Definition: qnode.cpp:39
int argc
Definition: qnode.h:35
ros::Subscriber encoder_subscriber
Definition: qnode.h:33
QNode(int argc, char **argv)
Definition: qnode.cpp:7
void rosShutdown()
virtual ~QNode()
Definition: qnode.cpp:13
std::unique_ptr< ros::NodeHandle > nh
Definition: qnode.h:31
char ** argv
Definition: qnode.h:36
void encoderCallback(const igvc_msgs::velocity_pair &msg)
Definition: qnode.cpp:61
void newVelocityData(float velocity)


igvc
Author(s): Matthew Barulic , Al Chaussee
autogenerated on Sun May 10 2015 16:18:45