obj_learn.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <ros/package.h>
00003 
00004 #include <iostream>
00005 #include <fstream>
00006 
00007 #include "Modules/ORLearningModule.h"
00008 
00009 #include "Architecture/Config/Config.h"
00010 
00011 int main(int argc, char **argv)
00012 {
00013     ros::init(argc, argv, "obj_learn");
00014     ros::NodeHandle nh;
00015 
00016     // load config
00017     std::string path = ros::package::getPath("or_nodes");
00018     std::vector<std::string> fileNames;
00019     std::vector<std::string> profilesToLoad;
00020     // read params from parameter server
00021     if(ros::param::has("/OrNodes/sConfigFile") && ros::param::has("/OrNodes/sProfile"))
00022     {
00023         std::string configFile;
00024         ros::param::get("/OrNodes/sConfigFile", configFile);
00025         fileNames.push_back(path + configFile);
00026 
00027         std::string profile;
00028         ros::param::get("/OrNodes/sProfile", profile);
00029         profilesToLoad.push_back(profile);
00030     }
00031     else
00032     {
00033         std::string defaultConf = path + "/config/custom.xml";
00034         std::string defaultProfile = "drinks";
00035         ROS_WARN_STREAM("No Parameter \"/OrNodes/sConfigFile\" or \"/OrNodes/sProfile\" found.\nLoading default config file: \""+defaultConf+"\" and default profile: \""+defaultProfile+"\"");
00036         fileNames.push_back(defaultConf);
00037         profilesToLoad.push_back(defaultProfile);
00038     }
00039     Config::loadConfig(fileNames, profilesToLoad, path);
00040 
00041     // read input image topic
00042     std::string inputTopic;
00043     if(ros::param::has("/OrNodes/sInputImageTopic"))
00044     {
00045         ros::param::get("/OrNodes/sInputImageTopic", inputTopic);
00046         ROS_INFO_STREAM("Using topic " + inputTopic + " for image input.");
00047     }
00048     else
00049     {
00050         inputTopic = "/camera/rgb/image_color";
00051         ROS_WARN_STREAM("No parameter \"/OrNodes/sInputImageTopic\" found. Using default topic " + inputTopic + " for image input.");
00052     }
00053 
00054 
00055     ORLearningModule* objRecLearningModule = new ORLearningModule(&nh, inputTopic);
00056 
00057     ros::Rate loop_rate(10);
00058     while (ros::ok())
00059     {
00060         ros::spinOnce();
00061         loop_rate.sleep();
00062     }
00063 
00064     delete objRecLearningModule;
00065 
00066     return 0;
00067 }


or_nodes
Author(s): Viktor Seib
autogenerated on Tue Jan 7 2014 11:24:09