urg_node_driver.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*
00031  * Author: Chad Rockey, Michael Carroll, Mike O'Driscoll
00032  */
00033 
00034 #include "urg_node/urg_node_driver.h"
00035 
00036 #include <tf/tf.h>  // tf header for resolving tf prefix
00037 #include <string>
00038 #include <diagnostic_msgs/DiagnosticStatus.h>
00039 #include <urg_node/Status.h>
00040 
00041 namespace urg_node
00042 {
00043 
00044 // Useful typedefs
00045 typedef diagnostic_updater::FrequencyStatusParam FrequencyStatusParam;
00046 
00047 UrgNode::UrgNode(ros::NodeHandle nh, ros::NodeHandle private_nh) :
00048   nh_(nh),
00049   pnh_(private_nh)
00050 {
00051   initSetup();
00052 }
00053 
00054 UrgNode::UrgNode():
00055   nh_(),
00056   pnh_("~")
00057 {
00058   initSetup();
00059 }
00060 
00061 void UrgNode::initSetup()
00062 {
00063   close_diagnostics_ = true;
00064   close_scan_ = true;
00065   service_yield_ = false;
00066 
00067   error_code_ = 0;
00068   lockout_status_ = false;
00069   // Initialize node and nodehandles
00070 
00071   // Get parameters so we can change these later.
00072   pnh_.param<std::string>("ip_address", ip_address_, "");
00073   pnh_.param<int>("ip_port", ip_port_, 10940);
00074   pnh_.param<std::string>("serial_port", serial_port_, "/dev/ttyACM0");
00075   pnh_.param<int>("serial_baud", serial_baud_, 115200);
00076   pnh_.param<bool>("calibrate_time", calibrate_time_, false);
00077   pnh_.param<bool>("publish_intensity", publish_intensity_, true);
00078   pnh_.param<bool>("publish_multiecho", publish_multiecho_, false);
00079   pnh_.param<int>("error_limit", error_limit_, 4);
00080   pnh_.param<double>("diagnostics_tolerance", diagnostics_tolerance_, 0.05);
00081   pnh_.param<double>("diagnostics_window_time", diagnostics_window_time_, 5.0);
00082   pnh_.param<bool>("get_detailed_status", detailed_status_, false);
00083 
00084   // Set up publishers and diagnostics updaters, we only need one
00085   if (publish_multiecho_)
00086   {
00087     echoes_pub_ = laser_proc::LaserTransport::advertiseLaser(nh_, 20);
00088   }
00089   else
00090   {
00091     laser_pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan", 20);
00092   }
00093 
00094   status_service_ = nh_.advertiseService("update_laser_status", &UrgNode::statusCallback, this);
00095   status_pub_ = nh_.advertise<urg_node::Status>("laser_status", 1, true);
00096 
00097   diagnostic_updater_.reset(new diagnostic_updater::Updater);
00098   diagnostic_updater_->add("Hardware Status", this, &UrgNode::populateDiagnosticsStatus);
00099 }
00100 
00101 UrgNode::~UrgNode()
00102 {
00103   if (diagnostics_thread_.joinable())
00104   {
00105     // Clean up our diagnostics thread.
00106     close_diagnostics_ = true;
00107     diagnostics_thread_.join();
00108   }
00109   if (scan_thread_.joinable())
00110   {
00111     close_scan_ = true;
00112     scan_thread_.join();
00113   }
00114 }
00115 
00116 bool UrgNode::updateStatus()
00117 {
00118   bool result = false;
00119   service_yield_ = true;
00120   boost::mutex::scoped_lock lock(lidar_mutex_);
00121 
00122   if (urg_)
00123   {
00124     device_status_ = urg_->getSensorStatus();
00125 
00126     if (detailed_status_)
00127     {
00128       URGStatus status;
00129       if (urg_->getAR00Status(status))
00130       {
00131         urg_node::Status msg;
00132         msg.operating_mode = status.operating_mode;
00133         msg.error_status = status.error_status;
00134         msg.error_code = status.error_code;
00135         msg.lockout_status = status.lockout_status;
00136 
00137         lockout_status_ = status.lockout_status;
00138         error_code_ = status.error_code;
00139 
00140         UrgDetectionReport report;
00141         if (urg_->getDL00Status(report))
00142         {
00143           msg.area_number = report.area;
00144           msg.distance = report.distance;
00145           msg.angle = report.angle;
00146         }
00147         else
00148         {
00149            ROS_WARN("Failed to get detection report.");
00150         }
00151 
00152         // Publish the status on the latched topic for inspection.
00153         status_pub_.publish(msg);
00154         result = true;
00155       }
00156       else
00157       {
00158         ROS_WARN("Failed to retrieve status");
00159 
00160         urg_node::Status msg;
00161         status_pub_.publish(msg);
00162       }
00163     }
00164   }
00165   return result;
00166 }
00167 
00168 bool UrgNode::statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
00169 {
00170   ROS_INFO("Got update lidar status callback");
00171   res.success = false;
00172   res.message = "Laser not ready";
00173 
00174   if (updateStatus())
00175   {
00176     res.message = "Status retrieved";
00177     res.success = true;
00178   }
00179   else
00180   {
00181     res.message = "Failed to update status";
00182     res.success = false;
00183   }
00184 
00185   return true;
00186 }
00187 
00188 bool UrgNode::reconfigure_callback(urg_node::URGConfig& config, int level)
00189 {
00190   if (!urg_)
00191   {
00192     ROS_ERROR("Reconfigure failed, not ready");
00193     return false;
00194   }
00195 
00196   if (level < 0)  // First call, initialize, laser not yet started
00197   {
00198     urg_->setAngleLimitsAndCluster(config.angle_min, config.angle_max, config.cluster);
00199     urg_->setSkip(config.skip);
00200   }
00201   else if (level > 0)   // Must stop
00202   {
00203     urg_->stop();
00204     ROS_INFO("Stopped data due to reconfigure.");
00205 
00206     // Change values that required stopping
00207     urg_->setAngleLimitsAndCluster(config.angle_min, config.angle_max, config.cluster);
00208     urg_->setSkip(config.skip);
00209 
00210     try
00211     {
00212       urg_->start();
00213       ROS_INFO("Streaming data after reconfigure.");
00214     }
00215     catch (std::runtime_error& e)
00216     {
00217       ROS_FATAL("%s", e.what());
00218       ros::Duration(1.0).sleep();
00219       ros::shutdown();
00220       return false;
00221     }
00222   }
00223 
00224   // The publish frequency changes based on the number of skipped scans.
00225   // Update accordingly here.
00226   freq_min_ = 1.0 / (urg_->getScanPeriod() * (config.skip + 1));
00227 
00228   std::string frame_id = tf::resolve(config.tf_prefix, config.frame_id);
00229   urg_->setFrameId(frame_id);
00230   urg_->setUserLatency(config.time_offset);
00231 
00232   return true;
00233 }
00234 
00235 void UrgNode::update_reconfigure_limits()
00236 {
00237   if (!urg_ || !srv_)
00238   {
00239     ROS_DEBUG_THROTTLE(10, "Unable to update reconfigure limits. Not Ready.");
00240     return;
00241   }
00242 
00243   urg_node::URGConfig min, max;
00244   srv_->getConfigMin(min);
00245   srv_->getConfigMax(max);
00246 
00247   min.angle_min = urg_->getAngleMinLimit();
00248   min.angle_max = min.angle_min;
00249   max.angle_max = urg_->getAngleMaxLimit();
00250   max.angle_min = max.angle_max;
00251 
00252   srv_->setConfigMin(min);
00253   srv_->setConfigMax(max);
00254 }
00255 
00256 void UrgNode::calibrate_time_offset()
00257 {
00258   boost::mutex::scoped_lock lock(lidar_mutex_);
00259   if (!urg_)
00260   {
00261     ROS_DEBUG_THROTTLE(10, "Unable to calibrate time offset. Not Ready.");
00262     return;
00263   }
00264   try
00265   {
00266     // Don't let outside interruption effect lidar offset.
00267     ROS_INFO("Starting calibration. This will take a few seconds.");
00268     ROS_WARN("Time calibration is still experimental.");
00269     ros::Duration latency = urg_->computeLatency(10);
00270     ROS_INFO("Calibration finished. Latency is: %.4f.", latency.toSec());
00271   }
00272   catch (std::runtime_error& e)
00273   {
00274     ROS_FATAL("Could not calibrate time offset: %s", e.what());
00275     ros::Duration(1.0).sleep();
00276     ros::shutdown();
00277   }
00278 }
00279 
00280 
00281 // Diagnostics update task to be run in a thread.
00282 void UrgNode::updateDiagnostics()
00283 {
00284   while (!close_diagnostics_)
00285   {
00286     diagnostic_updater_->update();
00287     boost::this_thread::sleep_for(boost::chrono::milliseconds(10));
00288   }
00289 }
00290 
00291 // Populate a diagnostics status message.
00292 void UrgNode::populateDiagnosticsStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
00293 {
00294   if (!urg_)
00295   {
00296     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00297         "Not Connected");
00298     return;
00299   }
00300 
00301   if (!urg_->getIPAddress().empty())
00302   {
00303     stat.add("IP Address", urg_->getIPAddress());
00304     stat.add("IP Port", urg_->getIPPort());
00305   }
00306   else
00307   {
00308     stat.add("Serial Port", urg_->getSerialPort());
00309     stat.add("Serial Baud", urg_->getSerialBaud());
00310   }
00311 
00312   if (!urg_->isStarted())
00313   {
00314     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00315         "Not Connected: " + device_status_);
00316   }
00317   else if (device_status_ != std::string("Sensor works well.") &&
00318            device_status_ != std::string("Stable 000 no error.") &&
00319            device_status_ != std::string("sensor is working normally"))
00320   {
00321     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00322         "Abnormal status: " + device_status_);
00323   }
00324   else if (error_code_ != 0)
00325   {
00326     stat.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR,
00327         "Lidar reporting error code: %X",
00328         error_code_);
00329   }
00330   else if (lockout_status_)
00331   {
00332     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00333         "Lidar locked out.");
00334   }
00335   else
00336   {
00337     stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00338         "Streaming");
00339   }
00340 
00341   stat.add("Vendor Name", vendor_name_);
00342   stat.add("Product Name", product_name_);
00343   stat.add("Firmware Version", firmware_version_);
00344   stat.add("Firmware Date", firmware_date_);
00345   stat.add("Protocol Version", protocol_version_);
00346   stat.add("Device ID", device_id_);
00347   stat.add("Computed Latency", urg_->getComputedLatency());
00348   stat.add("User Time Offset", urg_->getUserTimeOffset());
00349 
00350   // Things not explicitly required by REP-0138, but still interesting.
00351   stat.add("Device Status", device_status_);
00352   stat.add("Scan Retrieve Error Count", error_count_);
00353 
00354   stat.add("Lidar Error Code", error_code_);
00355   stat.add("Locked out", lockout_status_);
00356 }
00357 
00358 bool UrgNode::connect()
00359 {
00360   // Don't let external access to retrieve
00361   // status during the connection process.
00362   boost::mutex::scoped_lock lock(lidar_mutex_);
00363 
00364   try
00365   {
00366     urg_.reset();  // Clear any previous connections();
00367     if (!ip_address_.empty())
00368     {
00369       urg_.reset(new urg_node::URGCWrapper(ip_address_, ip_port_, publish_intensity_, publish_multiecho_));
00370     }
00371     else
00372     {
00373       urg_.reset(new urg_node::URGCWrapper(serial_baud_, serial_port_, publish_intensity_, publish_multiecho_));
00374     }
00375 
00376     std::stringstream ss;
00377     ss << "Connected to";
00378     if (publish_multiecho_)
00379     {
00380       ss << " multiecho";
00381     }
00382     if (!ip_address_.empty())
00383     {
00384       ss << " network";
00385     }
00386     else
00387     {
00388       ss << " serial";
00389     }
00390     ss << " device with";
00391     if (publish_intensity_)
00392     {
00393       ss << " intensity and";
00394     }
00395     ss << " ID: " << urg_->getDeviceID();
00396     ROS_INFO_STREAM(ss.str());
00397 
00398     device_status_ = urg_->getSensorStatus();
00399     vendor_name_ = urg_->getVendorName();
00400     product_name_ = urg_->getProductName();
00401     firmware_version_ = urg_->getFirmwareVersion();
00402     firmware_date_ = urg_->getFirmwareDate();
00403     protocol_version_ = urg_->getProtocolVersion();
00404     device_id_ = urg_->getDeviceID();
00405 
00406     if (diagnostic_updater_ && urg_)
00407     {
00408       diagnostic_updater_->setHardwareID(urg_->getDeviceID());
00409     }
00410 
00411     return true;
00412   }
00413   catch (std::runtime_error& e)
00414   {
00415     ROS_ERROR_THROTTLE(10.0, "Error connecting to Hokuyo: %s", e.what());
00416     urg_.reset();
00417     return false;
00418   }
00419   catch (std::exception& e)
00420   {
00421     ROS_ERROR_THROTTLE(10.0, "Unknown error connecting to Hokuyo: %s", e.what());
00422     urg_.reset();
00423     return false;
00424   }
00425 
00426   return false;
00427 }
00428 
00429 void UrgNode::scanThread()
00430 {
00431   while (!close_scan_)
00432   {
00433     if (!urg_)
00434     {
00435       if (!connect())
00436       {
00437         boost::this_thread::sleep(boost::posix_time::milliseconds(500));
00438         continue;  // Connect failed, sleep, try again.
00439       }
00440     }
00441 
00442     // Configure limits (Must do this after creating the urgwidget)
00443     update_reconfigure_limits();
00444 
00445     if (calibrate_time_)
00446     {
00447       calibrate_time_offset();
00448     }
00449 
00450     // Clear the dynamic reconfigure server
00451     srv_.reset();
00452     // Spin once to de-register it's services before making a new
00453     // service next.
00454     ros::spinOnce();
00455 
00456     if (!urg_ || !ros::ok)
00457     {
00458       continue;
00459     }
00460     else
00461     {
00462       // Set up dynamic reconfigure
00463       srv_.reset(new dynamic_reconfigure::Server<urg_node::URGConfig>(pnh_));
00464       // Configure limits (Must do this after creating the urgwidget)
00465       update_reconfigure_limits();
00466       srv_->setCallback(boost::bind(&UrgNode::reconfigure_callback, this, _1, _2));
00467     }
00468 
00469     // Before starting, update the status
00470     updateStatus();
00471 
00472     // Start the urgwidget
00473     try
00474     {
00475       // If the connection failed, don't try and connect
00476       // pointer is invalid.
00477       if (!urg_)
00478       {
00479         continue;  // Return to top of main loop, not connected.
00480       }
00481       device_status_ = urg_->getSensorStatus();
00482       urg_->start();
00483       ROS_INFO("Streaming data.");
00484       // Clear the error count.
00485       error_count_ = 0;
00486     }
00487     catch (std::runtime_error& e)
00488     {
00489       ROS_ERROR_THROTTLE(10.0, "Error starting Hokuyo: %s", e.what());
00490       urg_.reset();
00491       ros::Duration(1.0).sleep();
00492       continue;  // Return to top of main loop
00493     }
00494     catch (...)
00495     {
00496       ROS_ERROR_THROTTLE(10.0, "Unknown error starting Hokuyo");
00497       urg_.reset();
00498       ros::Duration(1.0).sleep();
00499       continue;  // Return to top of main loop
00500     }
00501 
00502     while (!close_scan_)
00503     {
00504       // Don't allow external access during grabbing the scan.
00505       try
00506       {
00507         boost::mutex::scoped_lock lock(lidar_mutex_);
00508         if (publish_multiecho_)
00509         {
00510           const sensor_msgs::MultiEchoLaserScanPtr msg(new sensor_msgs::MultiEchoLaserScan());
00511           if (urg_->grabScan(msg))
00512           {
00513             echoes_pub_.publish(msg);
00514             echoes_freq_->tick();
00515           }
00516           else
00517           {
00518             ROS_WARN_THROTTLE(10.0, "Could not grab multi echo scan.");
00519             device_status_ = urg_->getSensorStatus();
00520             error_count_++;
00521           }
00522         }
00523         else
00524         {
00525           const sensor_msgs::LaserScanPtr msg(new sensor_msgs::LaserScan());
00526           if (urg_->grabScan(msg))
00527           {
00528             laser_pub_.publish(msg);
00529             laser_freq_->tick();
00530           }
00531           else
00532           {
00533             ROS_WARN_THROTTLE(10.0, "Could not grab single echo scan.");
00534             device_status_ = urg_->getSensorStatus();
00535             error_count_++;
00536           }
00537         }
00538       }
00539       catch (...)
00540       {
00541         ROS_ERROR_THROTTLE(10.0, "Unknown error grabbing Hokuyo scan.");
00542         error_count_++;
00543       }
00544 
00545       if (service_yield_)
00546       {
00547         boost::this_thread::sleep_for(boost::chrono::milliseconds(10));
00548         service_yield_ = false;
00549       }
00550 
00551       // Reestablish conneciton if things seem to have gone wrong.
00552       if (error_count_ > error_limit_)
00553       {
00554         ROS_ERROR_THROTTLE(10.0, "Error count exceeded limit, reconnecting.");
00555         urg_.reset();
00556         ros::Duration(2.0).sleep();
00557 
00558         break;  // Return to top of main loop
00559       }
00560     }
00561   }
00562 }
00563 
00564 void UrgNode::run()
00565 {
00566   // Setup initial connection
00567   connect();
00568 
00569   // Stop diagnostics
00570   if (!close_diagnostics_)
00571   {
00572     close_diagnostics_ = true;
00573     diagnostics_thread_.join();
00574   }
00575 
00576   if (publish_multiecho_)
00577   {
00578     echoes_freq_.reset(new diagnostic_updater::HeaderlessTopicDiagnostic("Laser Echoes",
00579           *diagnostic_updater_,
00580           FrequencyStatusParam(&freq_min_, &freq_min_, diagnostics_tolerance_, diagnostics_window_time_)));
00581   }
00582   else
00583   {
00584     laser_freq_.reset(new diagnostic_updater::HeaderlessTopicDiagnostic("Laser Scan",
00585           *diagnostic_updater_,
00586           FrequencyStatusParam(&freq_min_, &freq_min_, diagnostics_tolerance_, diagnostics_window_time_)));
00587   }
00588 
00589   // Now that we are setup, kick off diagnostics.
00590   close_diagnostics_ = false;
00591   diagnostics_thread_ = boost::thread(boost::bind(&UrgNode::updateDiagnostics, this));
00592 
00593   // Start scanning now that everything is configured.
00594   close_scan_ = false;
00595   scan_thread_ = boost::thread(boost::bind(&UrgNode::scanThread, this));
00596 }
00597 }  // namespace urg_node


urg_node
Author(s): Chad Rockey , Mike O'Driscoll
autogenerated on Wed Jun 14 2017 04:05:48