ndescs2disk.cpp
Go to the documentation of this file.
00001 #include "ndescs2disk.h"
00002 #include <dirent.h>
00003 //#include <sstream>
00004 
00005 bool DirectoryExists( const char* pzPath )
00006 {
00007   if ( pzPath == NULL) return false;
00008  
00009   DIR *pDir;
00010   bool bExists = false;
00011  
00012   pDir = opendir (pzPath);
00013  
00014   if (pDir != NULL)
00015   {
00016     bExists = true;    
00017     (void) closedir (pDir);
00018   }
00019  
00020   return bExists;
00021 }
00022 
00023 //Already defined in normaldescnode
00024 //template <class T>
00025 //inline std::string to_string (const T& t)
00026 //{
00027 //  std::stringstream ss;
00028 //  ss << t;
00029 //  return ss.str();
00030 //}
00031 
00032 void Ndescs2Disk::write_point(FILE *pf, const normal_descriptor_node::ndesc &point)
00033 {
00034   size_t dim=point.descriptor.size();
00035   if (fwrite (&(point.u), sizeof (int), 1, pf) != 1){
00036     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00037   if (fwrite (&(point.v), sizeof (int), 1, pf) != 1){
00038     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00039   if (fwrite (&(point.ori), sizeof (float), 1, pf) != 1){
00040     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00041   if (fwrite (&(point.point3d.x), sizeof (float), 1, pf) != 1){
00042     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00043   if (fwrite (&(point.point3d.y), sizeof (float), 1, pf) != 1){
00044     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00045   if (fwrite (&(point.point3d.z), sizeof (float), 1, pf) != 1){
00046     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00047   if (fwrite (&dim, sizeof (int), 1, pf) != 1){
00048     fprintf(stderr, "Error writting to file\n"); exit(-1);}
00049   for(size_t j=0;j<dim;j++)
00050     if (fwrite (&(point.descriptor[j]), sizeof (float), 1, pf) != 1){
00051       fprintf(stderr, "Error writting to file\n"); exit(-1);}
00052 }
00053 
00054 Ndescs2Disk::Ndescs2Disk(char *pref_out) //, int max_frames)
00055 {
00056   //init class attributes if necessary
00057   this->prefix_out_=std::string(pref_out);
00058   this->counter_=0;
00059   this->keep_nan_points_=false;
00060   //this->max_frames_=max_frames;
00061   //string for port names
00062 
00063   // [init publishers]
00064 
00065   // [init subscribers]
00066   this->points_subscriber_ = this->node_handle_.subscribe("ndesc", 1, &Ndescs2Disk::points_callback, this);
00067 
00068   // [init services]
00069 
00070   // [init clients]
00071 
00072   // [init action servers]
00073 
00074   // [init action clients]
00075   ROS_INFO("Init ndescs2disk node. Saving to %s",pref_out);  //, maxframes=%d\n",pref_out,max_frames);
00076 }
00077 
00078 void Ndescs2Disk::points_callback(const normal_descriptor_node::ndesc_pc::ConstPtr& ndesc_pc_msg)
00079 {
00080   ROS_INFO("Received ndesc pointset");
00081   //TODO: think of a better name generation tech.
00082   std::string file_name=this->prefix_out_+to_string(this->counter_)+".ndesc";
00083   this->counter_++;
00084   int saved_points=0;
00085   FILE* pf=fopen(file_name.c_str(),"wb");
00086   for(int ii=0;ii<ndesc_pc_msg->num;ii++)
00087   {
00088     if( (!isnan(ndesc_pc_msg->descriptors[ii].point3d.x) &&
00089          !isnan(ndesc_pc_msg->descriptors[ii].point3d.y) &&
00090          !isnan(ndesc_pc_msg->descriptors[ii].point3d.z)) ||
00091         this->keep_nan_points_)
00092     {
00093       write_point(pf, ndesc_pc_msg->descriptors[ii]);
00094       saved_points++;
00095     }
00096     // fprintf(pf,"%d %d %f %f %f ",ndesc_pc_msg->descriptors[ii].u,
00097     //      ndesc_pc_msg->descriptors[ii].v,
00098     //      ndesc_pc_msg->descriptors[ii].point3d.x,
00099     //      ndesc_pc_msg->descriptors[ii].point3d.y,
00100     //      ndesc_pc_msg->descriptors[ii].point3d.z);
00101     // for(unsigned int j=0;j<ndesc_pc_msg->descriptors[ii].descriptor.size();j++)
00102     //   fprintf(pf,"%f ",ndesc_pc_msg->descriptors[ii].descriptor[j]);
00103     // fprintf(pf,"\n");
00104   }
00105   ROS_INFO("%d descriptors (out of %d) of size %lu written to disk.\n",saved_points, ndesc_pc_msg->num, ndesc_pc_msg->descriptors[0].descriptor.size());
00106   fclose(pf);
00107   //if(this->max_frames_<=this->counter_ && this->max_frames_!=0)
00108   //  exit(0);
00109 }
00110 
00111 
00112 
00113 /* main function */
00114 int main(int argc,char *argv[])
00115 {
00116   if(argc<2){
00117     ROS_ERROR("Not enough arguments!\nUsage: ndesc2disk PREFIX_SAVE [-f MAX_FRAMES]");
00118     return -1;
00119   }
00120 
00121   //if(!DirectoryExists(argv[1]))
00122   //{
00123   //  ROS_ERROR("Error: %s does not exist",argv[1]);
00124   //}
00125   ros::init(argc, argv, "ndescs2disk");
00126   //int max_frames=0;
00127   //if (std::string(argv[2])==std::string("-f"))
00128   //  std::stringstream(std::string(argv[3])) >> max_frames;
00129   Ndescs2Disk ndescs2disk(argv[1]);//, max_frames);
00130   ros::spin();
00131 }
00132 
00133 
00134 


normal_descriptor_node
Author(s): Arnau Ramisa
autogenerated on Fri Dec 6 2013 20:19:55