png_to_img.cpp
Go to the documentation of this file.
00001 
00064 #include <ros/ros.h>
00065 #include <pcl/point_types.h>
00066 #include <pcl_ros/point_cloud.h>
00067 #include <pcl/io/pcd_io.h>
00068 #include <cv_bridge/cv_bridge.h>
00069 #include <highgui.h>
00070 #include <iostream>
00071 #include <fstream>
00072 
00073 int main(int argc, char **argv) {
00074   if(argc<3) {
00075     std::cerr<<"please specify *.png -> *.img\n";
00076     return 1;
00077   }
00078 
00079   cv_bridge::CvImage tmp;
00080   tmp.encoding="rgb8";
00081   tmp.image = cv::imread(argv[1],-1);
00082 
00083 
00084 
00085   sensor_msgs::ImageConstPtr last_img_ = tmp.toImageMsg();
00086 
00087 std::ofstream img_stream;
00088 
00089 img_stream << *last_img_;
00090 
00091 img_stream.close();
00092 
00093 
00094 //  //serialize image
00095 //  FILE *fp = fopen(argv[2],"wb");
00096 //  if(fp)
00097 //  {
00098 //    uint32_t len = last_img_->serializationLength();
00099 //
00100 //    uint8_t *wptr = new uint8_t[len];
00101 //    last_img_->serialize(wptr,0);
00102 //    fwrite(wptr, 1, len, fp);
00103 //    delete [] wptr;
00104 //
00105 //    fclose(fp);
00106 //  }
00107 //  else {
00108 //    ROS_ERROR("couldn't open %s", argv[2]);
00109 //    return 1;
00110 //  }
00111 
00112   return 0;
00113 }


cob_3d_registration
Author(s): Joshua Hampp
autogenerated on Wed Aug 26 2015 11:02:36