Go to the documentation of this file.00001
00002
00003
00004
00005
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 #include <ros/package.h>
00022
00023
00024 #define THIS ORLoaderModule
00025
00026 THIS::THIS(ros::NodeHandle *nh, ORMatchingModule* objRecMatchingModule)
00027 {
00028 m_ORMatchingModule = objRecMatchingModule;
00029
00030
00031 m_ORCommandSubscriber = nh->subscribe<or_msgs::OrCommand>("/or/commands", 10, &ORLoaderModule::callbackOrCommand, this);
00032
00033 loadDefaultObjects();
00034 }
00035
00036 THIS::~THIS()
00037 {}
00038
00039
00040 void THIS::callbackOrCommand( const or_msgs::OrCommand::ConstPtr& or_command_msg )
00041 {
00042 switch( or_command_msg->command )
00043 {
00044 case ORControlModule::LoadObject:
00045 loadObjectProperties( or_command_msg->string_value );
00046 break;
00047
00048 default:
00049 break;
00050 }
00051 }
00052
00053 void THIS::loadDefaultObjects( )
00054 {
00055 std::string objectListStr = Config::getString( "ObjectRecognition.sLoadObjects" );
00056 ROS_INFO_STREAM( "Loading ObjectRecognition.sLoadObjects: " <<objectListStr <<"\n");
00057
00058 std::vector<std::string> objectList = String::explode( objectListStr, ",;" );
00059 for ( unsigned i=0; i<objectList.size(); i++ )
00060 {
00061 loadObjectProperties( objectList[i] );
00062 }
00063 }
00064
00065
00066 void THIS::loadObjectProperties( std::string filename )
00067 {
00068
00069
00070
00071 std::string dir = Config::getString( "ObjectRecognition.sDataPath" );
00072 std::string path = ros::package::getPath("or_nodes");
00073 filename = path + dir + filename + ".objprop";
00074
00075 ROS_INFO_STREAM("dir: " << dir);
00076 ROS_INFO_STREAM("path: " << path);
00077 ROS_INFO_STREAM("filename: " << filename);
00078
00079
00080 if(!fileExists(filename))
00081 {
00082 ROS_ERROR_STREAM("Loading object properties. File not found: " + filename);
00083 return;
00084 }
00085
00086 ObjectProperties* objectProperties;
00087
00088 try
00089 {
00090 ROS_INFO_STREAM( "Loading " + filename );
00091 std::ifstream ifs( filename.c_str() );
00092 boost::archive::text_iarchive ia(ifs);
00093 objectProperties = new ObjectProperties();
00094 ia >> objectProperties;
00095 ifs.close();
00096 }
00097 catch ( const char* c )
00098 {
00099 ROS_ERROR_STREAM( "Cannot load object: " << c );
00100 return;
00101 }
00102
00103 m_ORMatchingModule->addObjectProperties(objectProperties);
00104 }
00105
00106
00107
00108 bool THIS::fileExists(const std::string& file)
00109 {
00110 struct stat buf;
00111 if (stat(file.c_str(), &buf) != -1)
00112 {
00113 return true;
00114 }
00115 return false;
00116 }
00117
00118
00119
00120 #undef THIS