ros1/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 <ros1/CameraROS.h>
29 #include <ros1/FindObjectROS.h>
30 #include <QApplication>
31 #include <QDir>
32 #include "find_object/MainWindow.h"
33 #include "ParametersToolBox.h"
34 #include "find_object/Settings.h"
35 #include <signal.h>
36 
37 using namespace find_object;
38 
39 bool gui;
40 std::string settingsPath;
41 
42 void my_handler_gui(int s){
43  QApplication::closeAllWindows();
44  QApplication::quit();
45 }
46 void my_handler(int s){
47  QCoreApplication::quit();
48 }
49 
50 void setupQuitSignal(bool gui)
51 {
52  // Catch ctrl-c to close the gui
53  struct sigaction sigIntHandler;
54  if(gui)
55  {
56  sigIntHandler.sa_handler = my_handler_gui;
57  }
58  else
59  {
60  sigIntHandler.sa_handler = my_handler;
61  }
62  sigemptyset(&sigIntHandler.sa_mask);
63  sigIntHandler.sa_flags = 0;
64  sigaction(SIGINT, &sigIntHandler, NULL);
65 }
66 
67 int main(int argc, char** argv)
68 {
69  ros::init(argc, argv, "find_object_2d");
70 
71  gui = true;
72  std::string objectsPath;
73  std::string sessionPath;
74  settingsPath = QDir::homePath().append("/.ros/find_object_2d.ini").toStdString();
75  bool subscribeDepth = false;
76 
77  ros::NodeHandle nh("~");
78 
79  nh.param("gui", gui, gui);
80  nh.param("objects_path", objectsPath, objectsPath);
81  nh.param("session_path", sessionPath, sessionPath);
82  nh.param("settings_path", settingsPath, settingsPath);
83  nh.param("subscribe_depth", subscribeDepth, subscribeDepth);
84 
85  ROS_INFO("gui=%d", (int)gui);
86  ROS_INFO("objects_path=%s", objectsPath.c_str());
87  ROS_INFO("session_path=%s", sessionPath.c_str());
88  ROS_INFO("settings_path=%s", settingsPath.c_str());
89  ROS_INFO("subscribe_depth = %s", subscribeDepth?"true":"false");
90 
91  if(settingsPath.empty())
92  {
93  settingsPath = QDir::homePath().append("/.ros/find_object_2d.ini").toStdString();
94  }
95  else
96  {
97  if(!sessionPath.empty())
98  {
99  ROS_WARN("\"settings_path\" parameter is ignored when \"session_path\" is set.");
100  }
101 
102  QString path = settingsPath.c_str();
103  if(path.contains('~'))
104  {
105  path.replace('~', QDir::homePath());
106  settingsPath = path.toStdString();
107  }
108  }
109 
110  // Load settings, should be loaded before creating other objects
111  Settings::init(settingsPath.c_str());
112 
113  FindObjectROS * findObjectROS = new FindObjectROS();
114  if(!sessionPath.empty())
115  {
116  if(!objectsPath.empty())
117  {
118  ROS_WARN("\"objects_path\" parameter is ignored when \"session_path\" is set.");
119  }
120  if(!findObjectROS->loadSession(sessionPath.c_str()))
121  {
122  ROS_ERROR("Failed to load session \"%s\"", sessionPath.c_str());
123  }
124  }
125  else if(!objectsPath.empty())
126  {
127  QString path = objectsPath.c_str();
128  if(path.contains('~'))
129  {
130  path.replace('~', QDir::homePath());
131  }
132  if(!findObjectROS->loadObjects(path))
133  {
134  ROS_ERROR("No objects loaded from path \"%s\"", path.toStdString().c_str());
135  }
136  }
137 
138  CameraROS * camera = new CameraROS(subscribeDepth);
139 
140  // Catch ctrl-c to close the gui
141  setupQuitSignal(gui);
142 
143  if(gui)
144  {
145  QApplication app(argc, argv);
146  MainWindow mainWindow(findObjectROS, camera); // take ownership
147 
148  QObject::connect(
149  &mainWindow,
150  SIGNAL(objectsFound(const find_object::DetectionInfo &, const find_object::Header &, const cv::Mat &, float)),
151  findObjectROS,
152  SLOT(publish(const find_object::DetectionInfo &, const find_object::Header &, const cv::Mat &, float)));
153 
154  QStringList topics = camera->subscribedTopics();
155  if(topics.size() == 1)
156  {
157  mainWindow.setSourceImageText(mainWindow.tr(
158  "<qt>Find-Object subscribed to <b>%1</b> topic.<br/>"
159  "You can remap the topic when starting the node: <br/>\"rosrun find_object_2d find_object_2d image:=your/image/topic\".<br/>"
160  "</qt>").arg(topics.first()));
161  }
162  else if(topics.size() == 3)
163  {
164  mainWindow.setSourceImageText(mainWindow.tr(
165  "<qt>Find-Object subscribed to : <br/> <b>%1</b> <br/> <b>%2</b> <br/> <b>%3</b><br/>"
166  "</qt>").arg(topics.at(0)).arg(topics.at(1)).arg(topics.at(2)));
167  }
168  mainWindow.show();
169  app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) );
170 
171  // loop
172  mainWindow.startProcessing();
173  app.exec();
175  }
176  else
177  {
178  QCoreApplication app(argc, argv);
179 
180  // connect stuff:
181  QObject::connect(camera, SIGNAL(imageReceived(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), findObjectROS, SLOT(detect(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)));
182 
183  //loop
184  camera->start();
185  app.exec();
186 
187  delete camera;
188  delete findObjectROS;
189  }
190  return 0;
191 }
app
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
std::string settingsPath
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void setSourceImageText(const QString &text)
Definition: MainWindow.cpp:364
void my_handler_gui(int s)
#define ROS_INFO(...)
void setupQuitSignal(bool gui)
int main(int argc, char **argv)
static ParametersMap init(const QString &fileName)
Definition: Settings.cpp:101
#define ROS_ERROR(...)
static void saveSettings(const QString &fileName=QString())
Definition: Settings.cpp:288
void my_handler(int s)


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09