ros_source_backend.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2015, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE
21 // FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22 // DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23 // SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
25 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
26 // OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
27 // DAMAGE.
28 //
29 // *****************************************************************************
30 
32 #include <QCoreApplication>
33 #include <QStringList>
34 #include <ros/ros.h>
35 
36 namespace swri_profiler_tools
37 {
39  :
40  is_connected_(false)
41 {
42  int argc = QCoreApplication::arguments().size();
43  std::vector<char*> argv;
44  // This is so ugly, but ros::init expects a "char**", so...
45  for (const auto& arg : QCoreApplication::arguments())
46  {
47  auto* temp_str = new char[arg.size()];
48  strcpy(temp_str, arg.toStdString().c_str());
49  argv.push_back(temp_str);
50  }
51  ros::init(argc, &argv[0],
52  "profiler",
54  for (const auto& arg : argv)
55  {
56  delete[] arg;
57  }
58 
59  startTimer(50);
60 }
61 
63 {
64  if (ros::isStarted()) {
65  ros::shutdown();
67  }
68 }
69 
71 {
72  ros::start();
73  is_connected_ = true;
74 
75  ros::NodeHandle nh;
76  index_sub_ = nh.subscribe("/profiler/index", 1000, &RosSourceBackend::handleIndex, this);
77  data_sub_ = nh.subscribe("/profiler/data", 1000, &RosSourceBackend::handleData, this);
78 
79  std::string uri = ros::master::getURI();
80  Q_EMIT connected(true, QString::fromStdString(uri));
81 }
82 
84 {
85  ros::shutdown();
86  is_connected_ = false;
87  Q_EMIT connected(false, QString());
88 }
89 
90 void RosSourceBackend::timerEvent(QTimerEvent *event)
91 {
92  bool master_status = ros::master::check();
93 
94  if (!is_connected_ && master_status) {
95  startRos();
96  } else if (is_connected_ && !master_status) {
97  stopRos();
98  } else if (is_connected_ && master_status) {
99  ros::spinOnce();
100  }
101 }
102 
103 void RosSourceBackend::handleIndex(const swri_profiler_msgs::ProfileIndexArray &msg)
104 {
105  Q_EMIT indexReceived(msg);
106 }
107 
108 void RosSourceBackend::handleData(const swri_profiler_msgs::ProfileDataArray &msg)
109 {
110  Q_EMIT dataReceived(msg);
111 }
112 
113 } // namespace swri_profiler_tools
ROSCPP_DECL const std::string & getURI()
ROSCPP_DECL bool check()
void handleData(const swri_profiler_msgs::ProfileDataArray &msg)
ROSCPP_DECL void start()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void indexReceived(swri_profiler_msgs::ProfileIndexArray)
void dataReceived(swri_profiler_msgs::ProfileDataArray)
void handleIndex(const swri_profiler_msgs::ProfileIndexArray &msg)
ROSCPP_DECL bool isStarted()
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()
void connected(bool connected, QString uri)
ROSCPP_DECL void waitForShutdown()


swri_profiler_tools
Author(s):
autogenerated on Fri Nov 27 2020 03:44:18