31 #include <QApplication> 44 QApplication::closeAllWindows();
48 QCoreApplication::quit();
54 struct sigaction sigIntHandler;
63 sigemptyset(&sigIntHandler.sa_mask);
64 sigIntHandler.sa_flags = 0;
65 sigaction(SIGINT, &sigIntHandler,
NULL);
68 int main(
int argc,
char** argv)
73 std::string objectsPath;
74 std::string sessionPath;
75 settingsPath = QDir::homePath().append(
"/.ros/find_object_2d.ini").toStdString();
76 bool subscribeDepth =
false;
81 nh.
param(
"objects_path", objectsPath, objectsPath);
82 nh.
param(
"session_path", sessionPath, sessionPath);
84 nh.
param(
"subscribe_depth", subscribeDepth, subscribeDepth);
87 ROS_INFO(
"objects_path=%s", objectsPath.c_str());
88 ROS_INFO(
"session_path=%s", sessionPath.c_str());
90 ROS_INFO(
"subscribe_depth = %s", subscribeDepth?
"true":
"false");
94 settingsPath = QDir::homePath().append(
"/.ros/find_object_2d.ini").toStdString();
98 if(!sessionPath.empty())
100 ROS_WARN(
"\"settings_path\" parameter is ignored when \"session_path\" is set.");
104 if(path.contains(
'~'))
106 path.replace(
'~', QDir::homePath());
115 if(!sessionPath.empty())
117 if(!objectsPath.empty())
119 ROS_WARN(
"\"objects_path\" parameter is ignored when \"session_path\" is set.");
121 if(!findObjectROS->loadSession(sessionPath.c_str()))
123 ROS_ERROR(
"Failed to load session \"%s\"", sessionPath.c_str());
126 else if(!objectsPath.empty())
128 QString path = objectsPath.c_str();
129 if(path.contains(
'~'))
131 path.replace(
'~', QDir::homePath());
133 if(!findObjectROS->loadObjects(path))
135 ROS_ERROR(
"No objects loaded from path \"%s\"", path.toStdString().c_str());
143 SIGNAL(rosDataReceived(
const std::string &,
const ros::Time &,
const cv::Mat &,
float)),
145 SLOT(setDepthData(
const std::string &,
const ros::Time &,
const cv::Mat &,
float)));
152 QApplication
app(argc, argv);
161 QStringList topics = camera->subscribedTopics();
162 if(topics.size() == 1)
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()));
169 else if(topics.size() == 3)
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)));
176 app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) );
185 QCoreApplication
app(argc, argv);
188 QObject::connect(camera, SIGNAL(imageReceived(
const cv::Mat &)), findObjectROS, SLOT(detect(
const cv::Mat &)));
195 delete findObjectROS;
void setupQuitSignal(bool gui)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setSourceImageText(const QString &text)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static void init(const QString &fileName)
int main(int argc, char **argv)
void my_handler_gui(int s)
static void saveSettings(const QString &fileName=QString())