loadModelIntoVSlam.cpp
Go to the documentation of this file.
00001 
00041 #include "ros/ros.h"
00042 #include "std_msgs/String.h"
00043 
00044 #include <string>
00045 #include <stdlib.h>
00046 
00047 #include "../ObjectModel.h"
00048 
00049 using namespace std;
00050 
00051 // ---------------------------------------------------------------------------
00052 
00053 static const std::string topic_name = "re_vslam/load_model";
00054 
00055 int main(int argc, char *argv[])
00056 {
00057   ros::init(argc, argv, "loadModelIntoVSlam");
00058 
00059   if(argc < 2)
00060   {
00061     ROS_WARN("Usage: %s <model dir>", argv[0]);
00062     return 1;
00063   }
00064   
00065   string model_dir = argv[1];
00066   
00067   if(model_dir.empty())
00068   {
00069     ROS_ERROR("No model directory given");
00070     return 2;
00071   }
00072   
00073   char *c_abspath = realpath(model_dir.c_str(),  NULL);
00074   if(!c_abspath)
00075   {
00076     ROS_ERROR("Could not get the absolute path of \"%s\"", model_dir.c_str());
00077     return 3;
00078   }
00079   
00080   string abspath(c_abspath);
00081   free(c_abspath);
00082 
00083   ros::NodeHandle n;
00084   ros::Publisher pub = n.advertise<std_msgs::String>(topic_name.c_str(),
00085     10);
00086  
00087   sleep(1);
00088 
00089   if(ObjectModel::checkDirectory(abspath))
00090   {
00091     ObjectModel model(abspath, false);
00092     
00093     std_msgs::String msg;
00094     msg.data = abspath;
00095 
00096     ROS_INFO("Sending \"%s\" by topic %s", abspath.c_str(), topic_name.c_str());
00097 
00098     pub.publish(msg);
00099 
00100     ros::spinOnce();
00101     
00102     return 0;  
00103   }
00104   else
00105   {
00106     ROS_ERROR("The directory \"%s\" is not a valid object model. Nothing done.",
00107       model_dir.c_str());
00108     return 4;
00109   }
00110 }
00111 
00112 // ---------------------------------------------------------------------------
00113 
00114 


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:31:42