ORLoaderModule.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  ORLoaderModule.cpp
00003  *
00004  *  (C) 2006 AG Aktives Sehen <agas@uni-koblenz.de>
00005  *           Universitaet Koblenz-Landau
00006  *
00007  *******************************************************************************/
00008 
00009 #include "ORLoaderModule.h"
00010 #include "ORControlModule.h"
00011 #include "ORMatchingModule.h"
00012 
00013 #include "Architecture/Config/Config.h"
00014 
00015 #include "ObjectRecognition/ObjectProperties.h"
00016 #include "Workers/String/String.h"
00017 
00018 #include <sstream>
00019 #include <fstream>
00020 
00021 
00022 #define THIS ORLoaderModule
00023 
00024 THIS::THIS(ros::NodeHandle *nh, ORMatchingModule* objRecMatchingModule)
00025 {
00026     m_ORMatchingModule = objRecMatchingModule;
00027 
00028     // subscribe to messages
00029     m_ORCommandSubscriber = nh->subscribe<or_msgs::OrCommand>("/or/commands", 10, &ORLoaderModule::callbackOrCommand, this);
00030 
00031     loadDefaultObjects();
00032 }
00033 
00034 THIS::~THIS()
00035 {}
00036 
00037 
00038 void THIS::callbackOrCommand( const or_msgs::OrCommand::ConstPtr& or_command_msg )
00039 {
00040     switch( or_command_msg->command )
00041     {
00042       case ORControlModule::LoadObject:
00043         loadObjectProperties( or_command_msg->string_value );
00044         break;
00045 
00046       default:
00047         break;
00048     }
00049 }
00050 
00051 void THIS::loadDefaultObjects( )
00052 {
00053   std::string objectListStr = Config::getString( "ObjectRecognition.sLoadObjects" );
00054   ROS_INFO_STREAM( "Loading ObjectRecognition.sLoadObjects: " <<objectListStr <<"\n");
00055 
00056   std::vector<std::string> objectList = String::explode( objectListStr, ",;" );
00057   for ( unsigned i=0; i<objectList.size(); i++ )
00058   {
00059     loadObjectProperties( objectList[i] );
00060   }
00061 }
00062 
00063 
00064 void THIS::loadObjectProperties( std::string filename )
00065 {
00066 //    std::string dir = Config::getString( "ObjectRecognition.sDataPath" );
00067 //    filename = dir + filename + ".objprop";
00068 
00069   // Return if file does not exist
00070   if(!fileExists(filename))
00071   {
00072       ROS_ERROR_STREAM("Loading object properties. File not found: " + filename);
00073       return;
00074   }
00075 
00076   ObjectProperties* objectProperties;
00077 
00078   try
00079   {
00080     ROS_INFO_STREAM( "Loading " + filename );
00081     std::ifstream ifs( filename.c_str() );
00082     boost::archive::text_iarchive ia(ifs);
00083     objectProperties = new ObjectProperties();
00084     ia >> objectProperties;
00085     ifs.close();
00086   }
00087   catch ( const char* c )
00088   {
00089     ROS_ERROR_STREAM( "Cannot load object: " << c );
00090     return;
00091   }
00092 
00093   m_ORMatchingModule->addObjectProperties(objectProperties);
00094 }
00095 
00096 
00097 
00098 bool THIS::fileExists(const std::string& file)
00099 {
00100     struct stat buf;
00101     if (stat(file.c_str(), &buf) != -1)
00102     {
00103         return true;
00104     }
00105     return false;
00106 }
00107 
00108 
00109 
00110 #undef THIS


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