find_object_2d_node.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "CameraROS.h"
29 #include "FindObjectROS.h"
30 
31 #include <QApplication>
32 #include <QDir>
33 #include "find_object/MainWindow.h"
34 #include "ParametersToolBox.h"
35 #include "find_object/Settings.h"
36 #include <signal.h>
37 
38 using namespace find_object;
39 
40 bool gui;
41 std::string settingsPath;
42 
43 void my_handler_gui(int s){
44  QApplication::closeAllWindows();
45  QApplication::quit();
46 }
47 void my_handler(int s){
48  QCoreApplication::quit();
49 }
50 
51 void setupQuitSignal(bool gui)
52 {
53  // Catch ctrl-c to close the gui
54  struct sigaction sigIntHandler;
55  if(gui)
56  {
57  sigIntHandler.sa_handler = my_handler_gui;
58  }
59  else
60  {
61  sigIntHandler.sa_handler = my_handler;
62  }
63  sigemptyset(&sigIntHandler.sa_mask);
64  sigIntHandler.sa_flags = 0;
65  sigaction(SIGINT, &sigIntHandler, NULL);
66 }
67 
68 int main(int argc, char** argv)
69 {
70  ros::init(argc, argv, "find_object_2d");
71 
72  gui = true;
73  std::string objectsPath;
74  std::string sessionPath;
75  settingsPath = QDir::homePath().append("/.ros/find_object_2d.ini").toStdString();
76  bool subscribeDepth = false;
77 
78  ros::NodeHandle nh("~");
79 
80  nh.param("gui", gui, gui);
81  nh.param("objects_path", objectsPath, objectsPath);
82  nh.param("session_path", sessionPath, sessionPath);
83  nh.param("settings_path", settingsPath, settingsPath);
84  nh.param("subscribe_depth", subscribeDepth, subscribeDepth);
85 
86  ROS_INFO("gui=%d", (int)gui);
87  ROS_INFO("objects_path=%s", objectsPath.c_str());
88  ROS_INFO("session_path=%s", sessionPath.c_str());
89  ROS_INFO("settings_path=%s", settingsPath.c_str());
90  ROS_INFO("subscribe_depth = %s", subscribeDepth?"true":"false");
91 
92  if(settingsPath.empty())
93  {
94  settingsPath = QDir::homePath().append("/.ros/find_object_2d.ini").toStdString();
95  }
96  else
97  {
98  if(!sessionPath.empty())
99  {
100  ROS_WARN("\"settings_path\" parameter is ignored when \"session_path\" is set.");
101  }
102 
103  QString path = settingsPath.c_str();
104  if(path.contains('~'))
105  {
106  path.replace('~', QDir::homePath());
107  settingsPath = path.toStdString();
108  }
109  }
110 
111  // Load settings, should be loaded before creating other objects
112  Settings::init(settingsPath.c_str());
113 
114  FindObjectROS * findObjectROS = new FindObjectROS();
115  if(!sessionPath.empty())
116  {
117  if(!objectsPath.empty())
118  {
119  ROS_WARN("\"objects_path\" parameter is ignored when \"session_path\" is set.");
120  }
121  if(!findObjectROS->loadSession(sessionPath.c_str()))
122  {
123  ROS_ERROR("Failed to load session \"%s\"", sessionPath.c_str());
124  }
125  }
126  else if(!objectsPath.empty())
127  {
128  QString path = objectsPath.c_str();
129  if(path.contains('~'))
130  {
131  path.replace('~', QDir::homePath());
132  }
133  if(!findObjectROS->loadObjects(path))
134  {
135  ROS_ERROR("No objects loaded from path \"%s\"", path.toStdString().c_str());
136  }
137  }
138 
139  CameraROS * camera = new CameraROS(subscribeDepth);
140 
141  QObject::connect(
142  camera,
143  SIGNAL(rosDataReceived(const std::string &, const ros::Time &, const cv::Mat &, float)),
144  findObjectROS,
145  SLOT(setDepthData(const std::string &, const ros::Time &, const cv::Mat &, float)));
146 
147  // Catch ctrl-c to close the gui
148  setupQuitSignal(gui);
149 
150  if(gui)
151  {
152  QApplication app(argc, argv);
153  MainWindow mainWindow(findObjectROS, camera); // take ownership
154 
155  QObject::connect(
156  &mainWindow,
157  SIGNAL(objectsFound(const find_object::DetectionInfo &)),
158  findObjectROS,
159  SLOT(publish(const find_object::DetectionInfo &)));
160 
161  QStringList topics = camera->subscribedTopics();
162  if(topics.size() == 1)
163  {
164  mainWindow.setSourceImageText(mainWindow.tr(
165  "<qt>Find-Object subscribed to <b>%1</b> topic.<br/>"
166  "You can remap the topic when starting the node: <br/>\"rosrun find_object_2d find_object_2d image:=your/image/topic\".<br/>"
167  "</qt>").arg(topics.first()));
168  }
169  else if(topics.size() == 3)
170  {
171  mainWindow.setSourceImageText(mainWindow.tr(
172  "<qt>Find-Object subscribed to : <br/> <b>%1</b> <br/> <b>%2</b> <br/> <b>%3</b><br/>"
173  "</qt>").arg(topics.at(0)).arg(topics.at(1)).arg(topics.at(2)));
174  }
175  mainWindow.show();
176  app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) );
177 
178  // loop
179  mainWindow.startProcessing();
180  app.exec();
182  }
183  else
184  {
185  QCoreApplication app(argc, argv);
186 
187  // connect stuff:
188  QObject::connect(camera, SIGNAL(imageReceived(const cv::Mat &)), findObjectROS, SLOT(detect(const cv::Mat &)));
189 
190  //loop
191  camera->start();
192  app.exec();
193 
194  delete camera;
195  delete findObjectROS;
196  }
197  return 0;
198 }
app
#define NULL
void setupQuitSignal(bool gui)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void my_handler(int s)
#define ROS_WARN(...)
std::string settingsPath
void setSourceImageText(const QString &text)
Definition: MainWindow.cpp:355
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
static void init(const QString &fileName)
Definition: Settings.cpp:97
bool gui
int main(int argc, char **argv)
void my_handler_gui(int s)
#define ROS_ERROR(...)
static void saveSettings(const QString &fileName=QString())
Definition: Settings.cpp:226


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Jun 10 2019 13:21:31