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 
00032 
00033 
00034 #include <ros/ros.h>
00035 
00036 #include <tf/tf.h> 
00037 #include <dynamic_reconfigure/server.h>
00038 #include <urg_node/URGConfig.h>
00039 
00040 #include <urg_node/urg_c_wrapper.h>
00041 #include <laser_proc/LaserTransport.h>
00042 
00043 #include <diagnostic_updater/diagnostic_updater.h>
00044 #include <diagnostic_updater/publisher.h>
00045 
00047 boost::shared_ptr<urg_node::URGCWrapper> urg_;
00048 boost::shared_ptr<dynamic_reconfigure::Server<urg_node::URGConfig> > srv_; 
00049 
00050 
00051 typedef diagnostic_updater::FrequencyStatusParam FrequencyStatusParam;
00052 typedef diagnostic_updater::HeaderlessTopicDiagnostic TopicDiagnostic;
00053 typedef boost::shared_ptr<TopicDiagnostic> TopicDiagnosticPtr;
00054 
00055 boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00056 TopicDiagnosticPtr laser_freq_, echoes_freq_;
00057 
00058 bool close_diagnostics_;
00059 boost::thread diagnostics_thread_;
00060 
00061 
00062 
00063 
00064 std::string device_status_;
00065 std::string vendor_name_;
00066 std::string product_name_;
00067 std::string firmware_version_;
00068 std::string firmware_date_;
00069 std::string protocol_version_;
00070 std::string device_id_;
00071 
00072 int error_count;
00073 double freq_min, freq_max;
00074 
00075 bool reconfigure_callback(urg_node::URGConfig& config, int level){
00076   if(level < 0){ 
00077     urg_->setAngleLimitsAndCluster(config.angle_min, config.angle_max, config.cluster);
00078     urg_->setSkip(config.skip);
00079   } else if(level > 0){ 
00080     urg_->stop();
00081     ROS_INFO("Stopped data due to reconfigure.");
00082 
00083     
00084     urg_->setAngleLimitsAndCluster(config.angle_min, config.angle_max, config.cluster);
00085     urg_->setSkip(config.skip);
00086 
00087     try{
00088       urg_->start();
00089       ROS_INFO("Streaming data after reconfigure.");
00090     } catch(std::runtime_error& e){
00091       ROS_FATAL("%s", e.what());
00092       ros::spinOnce();
00093       ros::Duration(1.0).sleep();
00094       ros::shutdown();
00095       return false;
00096     }
00097   }
00098 
00099   
00100   
00101   freq_min = 1.0/(urg_->getScanPeriod() * (config.skip + 1));
00102   freq_max = freq_min;
00103 
00104   std::string frame_id = tf::resolve(config.tf_prefix, config.frame_id);
00105   urg_->setFrameId(frame_id);
00106   urg_->setUserLatency(config.time_offset);
00107 
00108   return true;
00109 }
00110 
00111 void update_reconfigure_limits(){
00112   urg_node::URGConfig min, max;
00113   srv_->getConfigMin(min);
00114   srv_->getConfigMax(max);
00115 
00116   min.angle_min = urg_->getAngleMinLimit();
00117   min.angle_max = min.angle_min;
00118   max.angle_max = urg_->getAngleMaxLimit();
00119   max.angle_min = max.angle_max;
00120   
00121   srv_->setConfigMin(min);
00122   srv_->setConfigMax(max);
00123 }
00124 
00125 void calibrate_time_offset(){
00126      try{
00127       ROS_INFO("Starting calibration. This will take a few seconds.");
00128       ROS_WARN("Time calibration is still experimental.");
00129       ros::Duration latency = urg_->computeLatency(10);
00130       ROS_INFO("Calibration finished. Latency is: %.4f.", latency.toSec());
00131     } catch(std::runtime_error& e){
00132       ROS_FATAL("Could not calibrate time offset:%s", e.what());
00133       ros::spinOnce();
00134       ros::Duration(1.0).sleep();
00135       ros::shutdown();
00136     }
00137 }
00138 
00139 
00140 
00141 void updateDiagnostics() {
00142     while(!close_diagnostics_) {
00143         diagnostic_updater_->update();
00144         boost::this_thread::sleep(boost::posix_time::milliseconds(10));
00145     }
00146 }
00147 
00148 
00149 void populateDiagnosticsStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
00150 {
00151     if(urg_->getIPAddress() != "")
00152     {
00153         stat.add("IP Address", urg_->getIPAddress());
00154         stat.add("IP Port", urg_->getIPPort());
00155     } else {
00156         stat.add("Serial Port", urg_->getSerialPort());
00157         stat.add("Serial Baud", urg_->getSerialBaud());
00158     }
00159 
00160     if(!urg_->isStarted())
00161     {
00162       stat.summary(2, "Not Connected: " + device_status_);
00163     } 
00164     else if(device_status_ != std::string("Sensor works well.") && device_status_ != std::string("Stable 000 no error."))
00165     {
00166       stat.summary(2, "Abnormal status: " + device_status_);
00167     }
00168     else
00169     {
00170       stat.summary(0, "Streaming");
00171     }
00172 
00173     stat.add("Vendor Name", vendor_name_);
00174     stat.add("Product Name", product_name_);
00175     stat.add("Firmware Version", firmware_version_);
00176     stat.add("Firmware Date", firmware_date_);
00177     stat.add("Protocol Version", protocol_version_);
00178     stat.add("Device ID", device_id_);
00179     stat.add("Computed Latency", urg_->getComputedLatency());
00180     stat.add("User Time Offset", urg_->getUserTimeOffset());
00181 
00182     
00183     stat.add("Device Status", device_status_);
00184     stat.add("Error Count", error_count);
00185 }
00186 
00187 int main(int argc, char **argv)
00188 {
00189   
00190   ros::init(argc, argv, "urg_node");
00191   ros::NodeHandle n;
00192   ros::NodeHandle pnh("~");
00193 
00194   
00195   std::string ip_address;
00196   pnh.param<std::string>("ip_address", ip_address, "");
00197   int ip_port;
00198   pnh.param<int>("ip_port", ip_port, 10940);
00199 
00200   std::string serial_port;
00201   pnh.param<std::string>("serial_port", serial_port, "/dev/ttyACM0");
00202   int serial_baud;
00203   pnh.param<int>("serial_baud", serial_baud, 115200);
00204 
00205   bool calibrate_time;
00206   pnh.param<bool>("calibrate_time", calibrate_time, false);
00207 
00208   bool publish_intensity;
00209   pnh.param<bool>("publish_intensity", publish_intensity, true);
00210 
00211   bool publish_multiecho;
00212   pnh.param<bool>("publish_multiecho", publish_multiecho, true);
00213 
00214   int error_limit;
00215   pnh.param<int>("error_limit", error_limit, 4);
00216 
00217   
00218   ros::Publisher laser_pub;
00219   laser_proc::LaserPublisher echoes_pub;
00220 
00221   close_diagnostics_ = true;
00222 
00223   
00224   while(ros::ok()){
00225     try{
00226         
00227         if(!close_diagnostics_){
00228               close_diagnostics_ = true;
00229               diagnostics_thread_.join();
00230       }
00231         urg_.reset(); 
00232         ros::Duration(1.0).sleep();
00233       if(ip_address != ""){
00234         urg_.reset(new urg_node::URGCWrapper(ip_address, ip_port, publish_intensity, publish_multiecho));
00235       } else {
00236         urg_.reset(new urg_node::URGCWrapper(serial_baud, serial_port, publish_intensity, publish_multiecho));
00237       }
00238     } catch(std::runtime_error& e){
00239       ROS_ERROR_THROTTLE(10.0, "Error connecting to Hokuyo: %s", e.what());
00240       ros::spinOnce();
00241       ros::Duration(1.0).sleep();
00242       continue; 
00243     } catch(...){
00244       ROS_ERROR_THROTTLE(10.0, "Unknown error connecting to Hokuyo");
00245       ros::spinOnce();
00246       ros::Duration(1.0).sleep();
00247       continue; 
00248     }
00249 
00250           std::stringstream ss;
00251           ss << "Connected to";
00252           if(publish_multiecho){
00253             ss << " multiecho";
00254           }
00255           if(ip_address != ""){
00256             ss << " network";
00257           } else {
00258             ss << " serial";
00259           }
00260           ss << " device with";
00261           if(publish_intensity){
00262             ss << " intensity and";
00263           }
00264           ss << " ID: " << urg_->getDeviceID();
00265           ROS_INFO_STREAM(ss.str());
00266 
00267           
00268           if(publish_multiecho){
00269                 if(!echoes_pub){
00270                 echoes_pub = laser_proc::LaserTransport::advertiseLaser(n, 20);
00271             }
00272           } else {
00273                 if(!laser_pub){
00274                 laser_pub = n.advertise<sensor_msgs::LaserScan>("scan", 20);
00275             }
00276           }
00277 
00278           device_status_ = urg_->getSensorStatus();
00279           vendor_name_ = urg_->getVendorName();
00280           product_name_ = urg_->getProductName();
00281           firmware_version_ = urg_->getFirmwareVersion();
00282           firmware_date_ = urg_->getFirmwareDate();
00283           protocol_version_ = urg_->getProtocolVersion();
00284           device_id_ = urg_->getDeviceID();
00285 
00286           diagnostic_updater_.reset(new diagnostic_updater::Updater);
00287           diagnostic_updater_->setHardwareID(urg_->getDeviceID());
00288           diagnostic_updater_->add("Hardware Status", populateDiagnosticsStatus);
00289                 float diagnostics_tolerance = 0.05;
00290                 float diagnostics_window_time = 5.0;
00291                 close_diagnostics_ = true;
00292           if(publish_multiecho){
00293             echoes_freq_.reset(new TopicDiagnostic("Laser Echoes", *diagnostic_updater_,
00294                          FrequencyStatusParam(&freq_min, &freq_min, diagnostics_tolerance, diagnostics_window_time)));
00295           } else {
00296             laser_freq_.reset(new TopicDiagnostic("Laser Scan", *diagnostic_updater_,
00297                         FrequencyStatusParam(&freq_min, &freq_min, diagnostics_tolerance, diagnostics_window_time)));
00298           }
00299 
00300           if(calibrate_time){
00301             calibrate_time_offset();
00302           }
00303 
00304           
00305           srv_.reset(new dynamic_reconfigure::Server<urg_node::URGConfig>());
00306 
00307           
00308           update_reconfigure_limits();
00309 
00310           dynamic_reconfigure::Server<urg_node::URGConfig>::CallbackType f;
00311           f = boost::bind(reconfigure_callback, _1, _2);
00312           srv_->setCallback(f);
00313 
00314           
00315     try{
00316       urg_->start();
00317       ROS_INFO("Streaming data.");
00318     } catch(std::runtime_error& e){
00319       ROS_ERROR_THROTTLE(10.0, "Error starting Hokuyo: %s", e.what());
00320       ros::spinOnce();
00321       ros::Duration(1.0).sleep();
00322       continue; 
00323     } catch(...){
00324       ROS_ERROR_THROTTLE(10.0, "Unknown error starting Hokuyo");
00325       ros::spinOnce();
00326       ros::Duration(1.0).sleep();
00327       continue; 
00328     }
00329 
00330           
00331           close_diagnostics_ = false;
00332           diagnostics_thread_ = boost::thread(updateDiagnostics);
00333 
00334           
00335           error_count = 0;
00336           while(ros::ok()){
00337                 try{
00338                     if(publish_multiecho){
00339                       const sensor_msgs::MultiEchoLaserScanPtr msg(new sensor_msgs::MultiEchoLaserScan());
00340                       if(urg_->grabScan(msg)){
00341                         echoes_pub.publish(msg);
00342                         echoes_freq_->tick();
00343                       } else {
00344                         ROS_WARN_THROTTLE(10.0, "Could not grab multi echo scan.");
00345                         device_status_ = urg_->getSensorStatus();
00346                         error_count++;
00347                       }
00348                     } else {
00349                       const sensor_msgs::LaserScanPtr msg(new sensor_msgs::LaserScan());
00350                       if(urg_->grabScan(msg)){
00351                         laser_pub.publish(msg);
00352                         laser_freq_->tick();
00353                       } else {
00354                         ROS_WARN_THROTTLE(10.0, "Could not grab single echo scan.");
00355                         device_status_ = urg_->getSensorStatus();
00356                         error_count++;
00357                       }
00358                     }
00359                    } catch(...){
00360                                 ROS_ERROR_THROTTLE(10.0, "Unknown error grabbing Hokuyo scan.");
00361                                 error_count++;
00362                    }
00363 
00364             
00365             if(error_count > error_limit){
00366               ROS_ERROR_THROTTLE(10.0, "Error count exceeded limit, reconnecting.");
00367               urg_->stop();
00368               ros::Duration(2.0).sleep();
00369               ros::spinOnce();
00370               break; 
00371             }
00372             ros::spinOnce();
00373           }
00374   }
00375 
00376   
00377   close_diagnostics_ = true;
00378   diagnostics_thread_.join();
00379 
00380   return EXIT_SUCCESS;
00381 }