00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00090 
00091 #include "ros/node_handle.h"
00092 #include "ros/time.h"
00093 #include "ros/common.h"
00094 
00095 #include "std_msgs/PointCloud.h"
00096 #include "std_msgs/ImageArray.h"
00097 #include "std_msgs/Image.h"
00098 
00099 
00100 #include <opencv/cv.h>
00101 #include <opencv/highgui.h>
00102 
00103 #include <fstream>
00104 
00105 
00106 #include "stoc.h"
00107 #include "swissranger.h"
00108 #include "flir.h"
00109 
00110 #include "tf/tf.h"
00111 
00112 #define DEFAULT_INT_VALUE INT_MIN
00113 #define DEFAULT_DBL_VALUE DBL_MIN
00114 
00115 using namespace std;
00116 
00117 class CompositeNode: public ros::node
00118 {
00119   public:
00120 
00121     int sr_auto_illumination_, sr_integration_time_, sr_modulation_freq_, sr_amp_threshold_;
00122     int stoc_speckle_diff_, stoc_speckle_size_, stoc_horopter_, stoc_corrsize_, stoc_unique_, stoc_tex_thresh_, stoc_ndisp_;
00123     bool stoc_multiproc_;
00124     double stoc_zmax_;
00125 
00126     int sr_auto_illumination_prev_, sr_integration_time_prev_, sr_modulation_freq_prev_, sr_amp_threshold_prev_;
00127     int stoc_speckle_diff_prev_, stoc_speckle_size_prev_, stoc_horopter_prev_, stoc_corrsize_prev_, stoc_unique_prev_, stoc_tex_thresh_prev_, stoc_ndisp_prev_;
00128     bool stoc_multiproc_prev_;
00129     double stoc_zmax_prev_;
00130 
00131     
00132     std_msgs::PointCloud sr_msg_cloud_, stoc_msg_cloud_;
00133     std_msgs::ImageArray sr_msg_images_, stoc_msg_images_;
00134     std_msgs::Image flir_msg_image_, stoc_msg_left_image_;
00135 
00136     swissranger::SwissRanger sr_;
00137     stoc::STOC stoc_;
00138     unicap::FLIR flir_;
00139 
00140     
00141     bool dump_to_disk_, sr_enable_, stoc_enable_, flir_enable_, stoc_just_left_;
00142     
00143     int composite_snapshot_mode_, composite_snapshot_mode_prev_;
00144 
00145     CompositeNode () : ros::node ("composite"), dump_to_disk_(false), 
00146                                                 sr_enable_(true), stoc_enable_(true), flir_enable_(true), 
00147                                                 stoc_just_left_(false)
00148     {
00149       
00150       param ("~sr_auto_illumination", sr_auto_illumination_, DEFAULT_INT_VALUE);
00151       param ("~sr_integration_time", sr_integration_time_, DEFAULT_INT_VALUE);
00152       param ("~sr_modulation_freq", sr_modulation_freq_, DEFAULT_INT_VALUE);
00153       param ("~sr_amp_threshold", sr_amp_threshold_, DEFAULT_INT_VALUE);
00154       
00155       sr_auto_illumination_prev_ = sr_integration_time_prev_ = sr_modulation_freq_prev_ = sr_amp_threshold_prev_ = DEFAULT_INT_VALUE;
00156       
00157       param ("~stoc_speckle_diff", stoc_speckle_diff_, DEFAULT_INT_VALUE);
00158       param ("~stoc_speckle_size", stoc_speckle_size_, DEFAULT_INT_VALUE);
00159       param ("~stoc_horopter", stoc_horopter_, DEFAULT_INT_VALUE);
00160       param ("~stoc_corrsize", stoc_corrsize_, DEFAULT_INT_VALUE);
00161       param ("~stoc_unique", stoc_unique_, DEFAULT_INT_VALUE);
00162       param ("~stoc_tex_thresh", stoc_tex_thresh_, DEFAULT_INT_VALUE);
00163       param ("~stoc_ndisp", stoc_ndisp_, DEFAULT_INT_VALUE);
00164 
00165       stoc_speckle_diff_prev_ = stoc_speckle_size_prev_ = stoc_horopter_prev_ = stoc_corrsize_prev_ = stoc_unique_prev_ = stoc_tex_thresh_prev_ = stoc_ndisp_prev_ = DEFAULT_INT_VALUE;
00166       
00167 
00168       param ("~stoc_zmax", stoc_zmax_, DEFAULT_DBL_VALUE);
00169       
00170       stoc_zmax_prev_ = DEFAULT_DBL_VALUE;
00171       
00172       composite_snapshot_mode_ = composite_snapshot_mode_prev_ = 0;
00173 
00174       
00175       advertise<std_msgs::PointCloud>("cloud_sr", 1);
00176       advertise<std_msgs::PointCloud>("cloud_stoc", 1);
00177 
00178       advertise<std_msgs::ImageArray>("images_sr", 1);
00179       if (stoc_just_left_)
00180         advertise<std_msgs::Image>("image_stoc_left", 1);
00181       else
00182         advertise<std_msgs::ImageArray>("images_stoc", 1);
00183         
00184       advertise<std_msgs::Image>("image_flir", 1);
00185     }
00186 
00187     ~CompositeNode ()
00188     {
00189       stop ();
00190     }
00191 
00193     
00194     int
00195       start ()
00196     {
00197       
00198       try
00199       {
00200         if (sr_.open () == 0)
00201         {
00202           ROS_INFO ("[CompositeNode::SwissRanger] Connected to device with ID: %s", sr_.device_id_.c_str ());
00203           ROS_INFO ("[CompositeNode::SwissRanger] libusbSR version: %s", sr_.lib_version_.c_str ());
00204         }
00205       } catch (swissranger::Exception& e) {
00206         ROS_ERROR("[CompositeNode::SwissRanger] Exception thrown while connecting to the sensor.\n%s", e.what ());
00207         if (sr_enable_)
00208           return (-1);
00209       }
00210 
00211 
00212 
00213       sr_.setModulationFrequency (MF_30MHz);                    
00214       ROS_INFO ("[CompositeNode::SwissRanger] Modulation frequency is: %d", sr_.getModulationFrequency ());
00215       ROS_INFO ("[CompositeNode::SwissRanger] Amplitude threshold is: %d", sr_.getAmplitudeThreshold ());
00216 
00217       
00218       try
00219       {
00220         if (stoc_.open () == 0)
00221           ROS_INFO ("[CompositeNode::STOC] Connected to device with ID: %s", stoc_.device_id_.c_str ());
00222       } catch (stoc::Exception& e) {
00223         ROS_ERROR("[CompositeNode::STOC] Exception thrown while connecting to the sensor.\n%s", e.what ());
00224         if (stoc_enable_)
00225           return (-1);
00226       }
00227 
00228       
00229       try
00230       {
00231         if (flir_.open () == 0)
00232           ROS_INFO ("[CompositeNode::FLIR] Connected to device at %i: %s", flir_.device_id_, flir_.device_.identifier);
00233       } catch (unicap::Exception& e) {
00234         ROS_ERROR("[CompositeNode::FLIR] Exception thrown while connecting to the sensor.\n%s", e.what ());
00235         if (flir_enable_)
00236           return (-1);
00237       }
00238 
00239       return (0);
00240     }
00241 
00243     
00244     int
00245       stop ()
00246     {
00247       
00248       if (sr_.close () == 0)
00249         ROS_INFO ("[CompositeNode::SwissRanger] Driver shut down successfully");
00250       else
00251         return (-1);
00252 
00253       
00254       if (stoc_.close () == 0)
00255         ROS_INFO ("[CompositeNode::STOC] Driver shut down successfully");
00256       else
00257         return (-1);
00258 
00259       
00260       if (flir_.close () == 0)
00261         ROS_INFO ("[CompositeNode::FLIR] Driver shut down successfully");
00262       else
00263         return (-1);
00264 
00265       return (0);
00266     }
00267 
00269     
00270     void
00271       SaveCloud (char *fn, std_msgs::PointCloud cloud)
00272     {
00273       std::ofstream fs;
00274       fs.precision (5);
00275       fs.open (fn);
00276 
00277       int nr_pts = cloud.get_pts_size ();
00278       int dim    = cloud.get_chan_size ();
00279       fs << "COLUMNS x y z i pid";
00280       for (int d = 0; d < dim; d++)
00281         fs << " " << cloud.chan[d].name;
00282       fs << endl;
00283       fs << "POINTS " << nr_pts << endl;
00284       fs << "DATA ascii" << endl;
00285       
00286       for (int i = 0; i < nr_pts; i++)
00287       {
00288         fs << cloud.pts[i].x << " " << cloud.pts[i].y << " " << cloud.pts[i].z;
00289         for (int d = 0; d < dim; d++)
00290           fs << " " << cloud.chan[d].vals[i];
00291         fs << endl;
00292       }
00293       fs.close ();
00294     }
00295 
00297     
00298     void
00299       getParametersFromServer ()
00300     {
00301       
00302       if (has_param ("~composite_snapshot"))
00303         get_param ("~composite_snapshot", composite_snapshot_mode_);
00304       
00305       
00306       if (has_param ("~sr_auto_illumination"))
00307         get_param ("~sr_auto_illumination", sr_auto_illumination_);
00308       if (has_param ("~sr_integration_time"))
00309         get_param ("~sr_integration_time", sr_integration_time_);
00310       if (has_param ("~sr_modulation_freq"))
00311         get_param ("~sr_modulation_freq", sr_modulation_freq_);
00312       if (has_param ("~sr_amp_threshold"))
00313         get_param ("~sr_amp_threshold", sr_amp_threshold_);
00314         
00315       
00316       if (has_param ("~stoc_speckle_diff"))
00317         get_param ("~stoc_speckle_diff", stoc_speckle_diff_);
00318       if (has_param ("~stoc_speckle_size"))
00319         get_param ("~stoc_speckle_size", stoc_speckle_size_);
00320       if (has_param ("~stoc_horopter"))
00321         get_param ("~stoc_horopter", stoc_horopter_);
00322       if (has_param ("~stoc_corrsize")) 
00323         get_param ("~stoc_corrsize", stoc_corrsize_);
00324       if (has_param ("~stoc_unique"))
00325         get_param ("~stoc_unique", stoc_unique_);
00326       if (has_param ("~stoc_tex_thresh"))
00327         get_param ("~stoc_tex_thresh", stoc_tex_thresh_);
00328       if (has_param ("~stoc_ndisp"))
00329         get_param ("~stoc_ndisp", stoc_ndisp_);
00330 
00331 
00332 
00333       if (has_param ("~stoc_zmax"))
00334         get_param ("~stoc_zmax", stoc_zmax_);
00335     }
00336     
00338     
00339     void
00340       setInternalParameters ()
00341     {
00342       
00343       if (sr_auto_illumination_ != sr_auto_illumination_prev_)
00344       {
00345         sr_auto_illumination_prev_ = sr_auto_illumination_;
00346         ROS_INFO ("[CompositeNode::setInternalParameters::Swissranger] Auto illumination settings changed to %d", sr_auto_illumination_);
00347         sr_.setAutoIllumination (sr_auto_illumination_);
00348       }
00349 
00350       if (sr_integration_time_ != sr_integration_time_prev_)
00351       {
00352         sr_integration_time_prev_ = sr_integration_time_;
00353         ROS_INFO ("[CompositeNode::setInternalParameters::Swissranger] Integration time changed to %d", sr_integration_time_);
00354         sr_.setIntegrationTime (sr_integration_time_);
00355       }
00356 
00357       if (sr_modulation_freq_ != sr_modulation_freq_prev_)
00358       {
00359         sr_modulation_freq_prev_ = sr_modulation_freq_;
00360         ROS_INFO ("[CompositeNode::setInternalParameters::Swissranger] Modulation frequency changed to %d", sr_modulation_freq_);
00361         sr_.setModulationFrequency (sr_modulation_freq_);
00362       }
00363 
00364       if (sr_amp_threshold_ != sr_amp_threshold_prev_)
00365       {
00366         sr_amp_threshold_prev_ = sr_amp_threshold_;
00367         ROS_INFO ("[CompositeNode::setInternalParameters::Swissranger] Amplitude threshold changed to %d", sr_amp_threshold_);
00368         sr_.setAmplitudeThreshold (sr_amp_threshold_);
00369       }
00370       
00371       
00372       if (stoc_zmax_ != stoc_zmax_prev_) 
00373       {
00374         stoc_zmax_prev_ = stoc_zmax_;
00375         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Z-max cutoff value changed to %g", stoc_zmax_);
00376         stoc_.z_max_     = stoc_zmax_;
00377       }
00378 
00379       if (stoc_ndisp_ != stoc_ndisp_prev_) 
00380       {
00381         stoc_ndisp_prev_ = stoc_ndisp_;
00382         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Number of disparities changed to %d", stoc_ndisp_);
00383         stoc_.setNDisp (stoc_ndisp_);
00384       }
00385 
00386       if (stoc_tex_thresh_ != stoc_tex_thresh_prev_) 
00387       {
00388         stoc_tex_thresh_prev_ = stoc_tex_thresh_;
00389         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Texture filter threshold changed to %d", stoc_tex_thresh_);
00390         stoc_.setTexThresh (stoc_tex_thresh_);
00391       }
00392 
00393       if (stoc_unique_ != stoc_unique_prev_) 
00394       {
00395         stoc_unique_prev_ = stoc_unique_;
00396         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Uniqueness filter threshold changed to %d", stoc_unique_);
00397         stoc_.setUnique (stoc_unique_);
00398       }
00399 
00400       if (stoc_corrsize_ != stoc_corrsize_prev_) 
00401       {
00402         stoc_corrsize_prev_ = stoc_corrsize_;
00403         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Correlation window size changed to %d", stoc_corrsize_);
00404         stoc_.setCorrSize (stoc_corrsize_);
00405       }
00406 
00407       if (stoc_horopter_ != stoc_horopter_prev_) 
00408       {
00409         stoc_horopter_prev_ = stoc_horopter_;
00410         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Horopter (X Offset) changed to %d", stoc_horopter_);
00411         stoc_.setHoropter (stoc_horopter_);
00412       }
00413 
00414       if (stoc_speckle_size_ != stoc_speckle_size_prev_) 
00415       {
00416         stoc_speckle_size_prev_ = stoc_speckle_size_;
00417         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Minimum disparity region size changed to %d", stoc_speckle_size_);
00418         stoc_.setSpeckleSize (stoc_speckle_size_);
00419       }
00420 
00421       if (stoc_speckle_diff_ != stoc_speckle_diff_prev_) 
00422       {
00423         stoc_speckle_diff_prev_ = stoc_speckle_diff_;
00424         ROS_INFO ("[CompositeNode::setInternalParameters::STOC] Disparity region neighbor difference changed to %d", stoc_speckle_diff_);
00425         stoc_.setSpeckleDiff (stoc_speckle_diff_);
00426       }
00427     }
00428     
00430     
00431     void
00432       saveSRImages (std_msgs::ImageArray sr_msg_images_, int img_count)
00433     {
00434       char fn[80];
00435       CvSize sr_size = cvSize (sr_msg_images_.images[0].width, sr_msg_images_.images[0].height);
00436       IplImage *image_sr = cvCreateImage (sr_size, IPL_DEPTH_16U, 1);
00437 
00438       image_sr->imageData = (char*)&(sr_msg_images_.images[0].data[0]);
00439       sprintf (fn, "%04i-sr4k-distance.png", img_count);
00440       cvSaveImage (fn, image_sr);
00441 
00442       image_sr->imageData = (char*)&(sr_msg_images_.images[1].data[0]);
00443       sprintf (fn, "%04i-sr4k-intensity.png", img_count);
00444       cvSaveImage (fn, image_sr);
00445 
00446       image_sr->imageData = (char*)&(sr_msg_images_.images[2].data[0]);
00447       sprintf (fn, "%04i-sr4k-confidence.png", img_count);
00448       cvSaveImage (fn, image_sr);
00449 
00450       cvReleaseImage (&image_sr);
00451     }
00452 
00454     
00455     void
00456       saveSTOCLeftImage (std_msgs::Image stoc_msg_left_image_, int img_count)
00457     {
00458       char fn[80];
00459       CvSize stoc_size = cvSize (stoc_msg_left_image_.width, stoc_msg_left_image_.height);
00460       IplImage *image_stoc;
00461 
00462       
00463       if (stoc_msg_left_image_.colorspace == "rgb24")
00464         image_stoc = cvCreateImage (stoc_size, IPL_DEPTH_8U, 3);
00465       else
00466         image_stoc = cvCreateImage (stoc_size, IPL_DEPTH_8U, 1);
00467 
00468       image_stoc->imageData = (char*)&(stoc_msg_left_image_.data[0]);
00469       sprintf (fn, "%04i-stoc-left.png", img_count);
00470       
00471       cvSaveImage (fn, image_stoc);
00472 
00473       cvReleaseImage (&image_stoc);
00474     }
00475 
00477     
00478     void
00479       saveSTOCImages (std_msgs::ImageArray stoc_msg_images_, int img_count)
00480     {
00481       char fn[80];
00482       CvSize stoc_size = cvSize (stoc_msg_images_.images[0].width, stoc_msg_images_.images[0].height);
00483       IplImage *image_stoc;
00484 
00485       
00486       if (stoc_msg_images_.images[0].colorspace == "rgb24")
00487         image_stoc = cvCreateImage (stoc_size, IPL_DEPTH_8U, 3);
00488       else
00489         image_stoc = cvCreateImage (stoc_size, IPL_DEPTH_8U, 1);
00490 
00491       image_stoc->imageData = (char*)&(stoc_msg_images_.images[0].data[0]);
00492       sprintf (fn, "%04i-stoc-left.png", img_count);
00493       
00494       cvSaveImage (fn, image_stoc);
00495 
00496       cvReleaseImage (&image_stoc);  
00497 
00498       
00499       if (stoc_msg_images_.images[1].colorspace == "rgb24")
00500         image_stoc = cvCreateImage (stoc_size, IPL_DEPTH_8U, 3);
00501       else
00502         image_stoc = cvCreateImage (stoc_size, IPL_DEPTH_8U, 1);
00503 
00504       image_stoc->imageData = (char*)&(stoc_msg_images_.images[1].data[0]);
00505       sprintf (fn, "%04i-stoc-right.png", img_count);
00506       
00507       cvSaveImage (fn, image_stoc);
00508 
00509       cvReleaseImage (&image_stoc);
00510     }
00511     
00513     
00514     void
00515       rotateImage180_16bit (std_msgs::Image &image)
00516     {
00517       
00518       vector<uint8_t> imgdata (image.get_data_size ());
00519       memcpy (&(imgdata[0]), &(image.data[0]), image.get_data_size ());
00520       
00521       for (unsigned int u = 0; u < image.height; u++)
00522       {
00523         int nu_ = (image.height - u - 1) * image.width;
00524         int u_  =                 u      * image.width;
00525         for (unsigned int v = 0; v < image.width; v++)
00526         {
00527           int nv = image.width - v - 1;
00528           image.data[(nu_ + nv) * 2 + 0] = imgdata[(u_ + v) * 2 + 0];
00529           image.data[(nu_ + nv) * 2 + 1] = imgdata[(u_ + v) * 2 + 1];
00530         }
00531       }
00532     }
00533 
00535     
00536     void
00537       rotateImage180_16bit (std_msgs::ImageArray &images)
00538     {
00539       
00540       for (unsigned int cp = 0; cp < images.get_images_size (); cp++)
00541       {
00542         vector<uint8_t> imgdata (images.images[cp].get_data_size ());
00543         memcpy (&(imgdata[0]), &(images.images[cp].data[0]), images.images[cp].get_data_size ());
00544         
00545         for (unsigned int u = 0; u < images.images[cp].height; u++)
00546         {
00547           int nu_ = (images.images[cp].height - u - 1) * images.images[cp].width;
00548           int u_  =                             u      * images.images[cp].width;
00549           for (unsigned int v = 0; v < images.images[cp].width; v++)
00550           {
00551             int nv = images.images[cp].width - v - 1;
00552             images.images[cp].data[(nu_ + nv) * 2 + 0] = imgdata[(u_ + v) * 2 + 0];
00553             images.images[cp].data[(nu_ + nv) * 2 + 1] = imgdata[(u_ + v) * 2 + 1];
00554           }
00555         }
00556       }
00557     }
00558 
00560     
00561     bool spin ()
00562     {
00563       char fn[80];
00564       int img_count = 1;
00565 
00566       while (ok ())
00567       {
00568 
00569         
00570         
00571         getParametersFromServer ();
00572         setInternalParameters ();
00573         
00574         try
00575         {
00576           
00577           if (sr_enable_)
00578             sr_.readData (sr_msg_cloud_, sr_msg_images_);
00579           
00580           if (stoc_enable_)
00581           {
00582             if (stoc_just_left_)
00583               stoc_.readDataLeft (stoc_msg_cloud_, stoc_msg_left_image_);
00584             else
00585               stoc_.readData (stoc_msg_cloud_, stoc_msg_images_);
00586           }
00587           
00588           if (flir_enable_)
00589             flir_.readData (flir_msg_image_);
00590         } catch (swissranger::Exception& e) {
00591           ROS_WARN("[CompositeNode] Exception thrown while trying to read data.\n%s", e.what ());
00592           continue;
00593         } catch (stoc::Exception& e) {
00594           ROS_WARN("[CompositeNode] Exception thrown while trying to read data.\n%s", e.what ());
00595           continue;
00596         } catch (unicap::Exception& e) {
00597           ROS_WARN("[CompositeNode] Exception thrown while trying to read data.\n%s", e.what ());
00598           continue;
00599         }
00600         
00601         
00602         if (composite_snapshot_mode_ != composite_snapshot_mode_prev_)
00603         {
00604           composite_snapshot_mode_prev_ = composite_snapshot_mode_;
00605           ROS_INFO ("[CompositeNode] Snapshot request received!");
00606           
00607           if (sr_enable_)
00608             saveSRImages (sr_msg_images_, img_count);
00609           if (stoc_enable_)
00610           {
00611             if (stoc_just_left_)
00612               saveSTOCLeftImage (stoc_msg_left_image_, img_count);
00613             else               
00614               saveSTOCImages (stoc_msg_images_, img_count);
00615           }
00616         }
00617         
00618         
00619         if (sr_enable_)
00620         {
00621           if (dump_to_disk_)
00622           {
00623             saveSRImages (sr_msg_images_, img_count);
00624             sprintf (fn, "%04i-sr4k.pcd", img_count);
00625             SaveCloud (fn, sr_msg_cloud_);
00626           } 
00627           
00628           
00629           publish ("cloud_sr", sr_msg_cloud_);
00630 
00631 
00632 
00633           publish ("images_sr", sr_msg_images_);
00634         } 
00635 
00636         
00637         if (stoc_enable_)
00638         {
00639           if (dump_to_disk_)
00640           {
00641             if (stoc_just_left_)
00642               saveSTOCLeftImage (stoc_msg_left_image_, img_count);
00643             else               
00644               saveSTOCImages (stoc_msg_images_, img_count);
00645 
00646 
00647 
00648           } 
00649 
00650           
00651           publish ("cloud_stoc", stoc_msg_cloud_);
00652           if (stoc_just_left_)
00653             publish ("image_stoc_left", stoc_msg_left_image_);
00654           else
00655             publish ("images_stoc", stoc_msg_images_);
00656         } 
00657 
00658 
00659         
00660         if (flir_enable_)
00661         {
00662           if (dump_to_disk_)
00663           {
00664             CvSize flir_size = cvSize (flir_msg_image_.width, flir_msg_image_.height);
00665             IplImage *image_flir = cvCreateImage (flir_size, IPL_DEPTH_16U, 1);
00666 
00667             image_flir->imageData = (char*)&(flir_msg_image_.data[0]);
00668             sprintf (fn, "%04i-thermal.png", img_count);
00669             cvSaveImage (fn, image_flir);
00670             cvReleaseImage (&image_flir);
00671           } 
00672 
00673           
00674           publish ("image_flir", flir_msg_image_);
00675         } 
00676 
00677         
00678         img_count++;
00679       }
00680 
00681       return true;
00682     }
00683 
00684   
00685 };
00686 
00687 
00688 int
00689   main (int argc, char** argv)
00690 {
00691   ros::init (argc, argv);
00692 
00693   CompositeNode c;
00694   c.dump_to_disk_ = false;
00695   c.sr_enable_    = false;
00696   c.flir_enable_  = false;
00697   c.stoc_enable_  = false; 
00698 
00699   if (c.start () == 0)
00700     c.spin ();
00701 
00702   ros::fini ();
00703 
00704   return (0);
00705 }
00706