30 #include <QApplication>    43         QApplication::closeAllWindows();
    47         QCoreApplication::quit();
    53         struct sigaction sigIntHandler;
    62         sigemptyset(&sigIntHandler.sa_mask);
    63         sigIntHandler.sa_flags = 0;
    64         sigaction(SIGINT, &sigIntHandler, NULL);
    67 int main(
int argc, 
char** argv)
    72         std::string objectsPath;
    73         std::string sessionPath;
    74         settingsPath = QDir::homePath().append(
"/.ros/find_object_2d.ini").toStdString();
    75         bool subscribeDepth = 
false;
    80         nh.
param(
"objects_path", objectsPath, objectsPath);
    81         nh.
param(
"session_path", sessionPath, sessionPath);
    83         nh.
param(
"subscribe_depth", subscribeDepth, subscribeDepth);
    86         ROS_INFO(
"objects_path=%s", objectsPath.c_str());
    87         ROS_INFO(
"session_path=%s", sessionPath.c_str());
    89         ROS_INFO(
"subscribe_depth = %s", subscribeDepth?
"true":
"false");
    93                 settingsPath = QDir::homePath().append(
"/.ros/find_object_2d.ini").toStdString();
    97                 if(!sessionPath.empty())
    99                         ROS_WARN(
"\"settings_path\" parameter is ignored when \"session_path\" is set.");
   103                 if(path.contains(
'~'))
   105                         path.replace(
'~', QDir::homePath());
   114         if(!sessionPath.empty())
   116                 if(!objectsPath.empty())
   118                         ROS_WARN(
"\"objects_path\" parameter is ignored when \"session_path\" is set.");
   120                 if(!findObjectROS->loadSession(sessionPath.c_str()))
   122                         ROS_ERROR(
"Failed to load session \"%s\"", sessionPath.c_str());
   125         else if(!objectsPath.empty())
   127                 QString path = objectsPath.c_str();
   128                 if(path.contains(
'~'))
   130                         path.replace(
'~', QDir::homePath());
   132                 if(!findObjectROS->loadObjects(path))
   134                         ROS_ERROR(
"No objects loaded from path \"%s\"", path.toStdString().c_str());
   145                 QApplication 
app(argc, argv);
   154                 QStringList topics = camera->subscribedTopics();
   155                 if(topics.size() == 1)
   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()));
   162                 else if(topics.size() == 3)
   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)));
   169                 app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) );
   178                 QCoreApplication 
app(argc, argv);
   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)));
   188                 delete findObjectROS;
 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void setSourceImageText(const QString &text)
void my_handler_gui(int s)
void setupQuitSignal(bool gui)
int main(int argc, char **argv)
static ParametersMap init(const QString &fileName)
static void saveSettings(const QString &fileName=QString())