$search
00001 00005 #ifndef _THERMALVIS_LISTENER_H_ 00006 #define _THERMALVIS_LISTENER_H_ 00007 00008 #include "ros_resources.hpp" 00009 #include "general_resources.hpp" 00010 #include "opencv_resources.hpp" 00011 #include "tools.hpp" 00012 #include "improc.hpp" 00013 00014 #include <dynamic_reconfigure/server.h> 00015 #include "listenerConfig.h" 00016 00017 #include <rosbag/bag.h> 00018 #include <rosbag/view.h> 00019 00020 #include <message_filters/subscriber.h> 00021 #include <message_filters/synchronizer.h> 00022 #include <message_filters/sync_policies/approximate_time.h> 00023 00024 #include <opencv/cv.h> 00025 #include <opencv/highgui.h> 00026 00027 #include <cv_bridge/cv_bridge.h> 00028 #include <image_transport/image_transport.h> 00029 00030 #include <boost/foreach.hpp> 00031 #include "boost/filesystem.hpp" 00032 #include <time.h> 00033 #include <math.h> 00034 00035 #include "ros/ros.h" 00036 #include "sensor_msgs/Image.h" 00037 #include "sensor_msgs/CameraInfo.h" 00038 00039 #include <iostream> 00040 #include <fstream> 00041 00042 #define SAVEPLY false 00043 #define FILTER_DISTANCE 1 00044 #define SIGMA_P 15 00045 #define SIGMA_R .05 00046 00047 #define DEFAULT_MAX_TIMESTAMP_DIFF 0.01 00048 00049 const char __PROGRAM__[] = "LISTENER"; 00050 00052 struct listenerData { 00053 00054 string bagFile, outputFolder; 00055 00056 int maxFrames; 00057 00058 string read_addr; 00059 00060 // Topics 00061 string rgbTopic; 00062 string depthTopic; 00063 string thermalTopic; 00064 00065 string rgbInfoTopic; 00066 string depthInfoTopic; 00067 string thermalInfoTopic; 00068 00069 string thermalIntrinsics; 00070 bool undistortThermal; 00071 bool debugMode; 00072 bool thermalOnly; 00073 00074 double maxTimestampDiff; 00075 00076 bool obtainStartingData(ros::NodeHandle& nh); 00077 00078 }; 00079 00081 class listenerNode { 00082 private: 00083 00084 ros::NodeHandle *ref; 00085 00086 // cam-calib 00087 Mat imageSize, cameraMatrix, distCoeffs, newCamMat; 00088 Size cameraSize; 00089 Mat map1, map2; 00090 00091 double timeDiff; 00092 00093 Mat oldThermal; 00094 00095 rosbag::Bag bag; 00096 00097 float *writeData; 00098 00099 listenerData configData; 00100 00101 bool stillListening; 00102 00103 ofstream ofs_thermistor_log; 00104 string thermistorLogFile; 00105 00106 ros::NodeHandle private_node_handle; 00107 00108 char nodeName[256]; 00109 00110 dynamic_reconfigure::Server<thermalvis::listenerConfig> server; 00111 dynamic_reconfigure::Server<thermalvis::listenerConfig>::CallbackType f; 00112 00113 int getPointCloud(const sensor_msgs::Image::ConstPtr& depthImg); 00114 int getPointCloud(const sensor_msgs::Image::ConstPtr& depthImg, const sensor_msgs::Image::ConstPtr& rgbImg); 00115 00116 int DepthToCloud(float** data, const int width, const int height, float* result); 00117 int DepthToCloud(float** data, const int width, const int height, const double timeDif, const sensor_msgs::Image::ConstPtr& rgbImg, float* result); 00118 00119 float** ApplyBilateralFilter(float** data, const int width, const int height, float sigmaP, float sigmaR); 00120 00121 FILE *dataFile, *timeFile, *depthtimeFile, *depthInternaltimeFile, *imgtimeFile, *imgInternaltimeFile, *thermaltimeFile, *thermalInternaltimeFile, *thermalDuplicatesFile; 00122 00123 int count; 00124 int filenum; 00125 double startTime; 00126 int skipFrames; 00127 int maxFrames; 00128 00129 float d_fx; 00130 float d_fy; 00131 float d_cx; 00132 float d_cy; 00133 00134 char *outputFilename; 00135 char *outputFilenameThermal; 00136 char *outputdepth, *outputcloud ; 00137 00138 stringstream imgPath; 00139 stringstream timePath; 00140 stringstream imgtimePath, imgInternaltimePath, depthtimePath, depthInternaltimePath, thermaltimePath, thermalInternaltimePath, thermalDuplicatesPath; 00141 00142 // Image topics to load 00143 std::vector<std::string> topics; 00144 00145 00146 00147 int count_rgb; 00148 int count_depth; 00149 int count_rgbinfo; 00150 int count_depthinfo; 00151 int count_thermal; 00152 int count_thermalinfo; 00153 00154 sensor_msgs::Image::ConstPtr rgbImg; 00155 sensor_msgs::CameraInfo::ConstPtr rgbInfo; 00156 sensor_msgs::Image::ConstPtr depthImg; 00157 sensor_msgs::CameraInfo::ConstPtr depthInfo; 00158 sensor_msgs::Image::ConstPtr thermalImg; 00159 sensor_msgs::CameraInfo::ConstPtr thermalInfo; 00160 00161 00162 public: 00163 00164 rosbag::View *view; 00165 00166 listenerNode(ros::NodeHandle& nh, listenerData startupData); 00167 ~listenerNode(); 00168 00169 void makeDirectories(); 00170 00171 bool isStillListening(); 00172 00173 void serverCallback(thermalvis::listenerConfig &config, uint32_t level); 00174 00175 00176 00177 void extractBagFile(); 00178 void cameraCallback(const sensor_msgs::Image::ConstPtr& rgbImgMsg, 00179 const sensor_msgs::Image::ConstPtr& depthImgMsg, 00180 const sensor_msgs::Image::ConstPtr& thermalImgMsg, 00181 const sensor_msgs::CameraInfo::ConstPtr& rgbInfoMsg, 00182 const sensor_msgs::CameraInfo::ConstPtr& depthInfoMsg, 00183 const sensor_msgs::CameraInfo::ConstPtr& thermalInfoMsg 00184 ); 00185 }; 00186 00187 typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > SyncPolicy; 00188 00193 template <class M> 00194 class BagSubscriber : public message_filters::SimpleFilter<M> 00195 { 00196 public: 00197 void newMessage(const boost::shared_ptr<M const> &msg) 00198 { 00199 signalMessage(msg); 00200 } 00201 }; 00202 00203 #endif