urg_c_wrapper.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, Mike O'Driscoll
00032  */
00033 
00034 #include "ros/ros.h"
00035 #include <urg_node/urg_c_wrapper.h>
00036 #include <limits>
00037 #include <string>
00038 #include <vector>
00039 #include <boost/crc.hpp>
00040 
00041 namespace urg_node
00042 {
00043 
00044 URGCWrapper::URGCWrapper(const std::string& ip_address, const int ip_port,
00045     bool& using_intensity, bool& using_multiecho, bool synchronize_time)
00046 {
00047   // Store for comprehensive diagnostics
00048   ip_address_ = ip_address;
00049   ip_port_ = ip_port;
00050   serial_port_ = "";
00051   serial_baud_ = 0;
00052 
00053 
00054   long baudrate_or_port = (long)ip_port;
00055   const char *device = ip_address.c_str();
00056 
00057   int result = urg_open(&urg_, URG_ETHERNET, device, baudrate_or_port);
00058   if (result < 0)
00059   {
00060     std::stringstream ss;
00061     ss << "Could not open network Hokuyo:\n";
00062     ss << ip_address << ":" << ip_port << "\n";
00063     ss << urg_error(&urg_);
00064     throw std::runtime_error(ss.str());
00065   }
00066 
00067   initialize(using_intensity, using_multiecho, synchronize_time);
00068 }
00069 
00070 URGCWrapper::URGCWrapper(const int serial_baud, const std::string& serial_port,
00071     bool& using_intensity, bool& using_multiecho, bool synchronize_time)
00072 {
00073   // Store for comprehensive diagnostics
00074   serial_baud_ = serial_baud;
00075   serial_port_ = serial_port;
00076   ip_address_ = "";
00077   ip_port_ = 0;
00078 
00079   long baudrate_or_port = (long)serial_baud;
00080   const char *device = serial_port.c_str();
00081 
00082   int result = urg_open(&urg_, URG_SERIAL, device, baudrate_or_port);
00083   if (result < 0)
00084   {
00085     std::stringstream ss;
00086     ss << "Could not open serial Hokuyo:\n";
00087     ss << serial_port << " @ " << serial_baud << "\n";
00088     ss << urg_error(&urg_);
00089     stop();
00090     urg_close(&urg_);
00091     throw std::runtime_error(ss.str());
00092   }
00093 
00094   initialize(using_intensity, using_multiecho, synchronize_time);
00095 }
00096 
00097 void URGCWrapper::initialize(bool& using_intensity, bool& using_multiecho, bool synchronize_time)
00098 {
00099   int urg_data_size = urg_max_data_size(&urg_);
00100   // urg_max_data_size can return a negative, error code value. Resizing based on this value will fail.
00101   if (urg_data_size < 0)
00102   {
00103     // This error can be caused by a URG-04LX in SCIP 1.1 mode, so we try to set SCIP 2.0 mode.
00104     if (setToSCIP2() && urg_max_data_size(&urg_) >= 0)
00105     {
00106       // If setting SCIP 2.0 was successful, we set urg_data_size to the correct value.
00107       urg_data_size = urg_max_data_size(&urg_);
00108     }
00109     else
00110     {
00111       urg_.last_errno = urg_data_size;
00112       std::stringstream ss;
00113       ss << "Could not initialize Hokuyo:\n";
00114       ss << urg_error(&urg_);
00115       stop();
00116       urg_close(&urg_);
00117       throw std::runtime_error(ss.str());
00118     }
00119   }
00120   // Ocassionally urg_max_data_size returns a string pointer, make sure we don't allocate too much space,
00121   // the current known max is 1440 steps
00122   if (urg_data_size  > 5000)
00123   {
00124     urg_data_size = 5000;
00125   }
00126   data_.resize(urg_data_size * URG_MAX_ECHO);
00127   intensity_.resize(urg_data_size * URG_MAX_ECHO);
00128 
00129   started_ = false;
00130   frame_id_ = "";
00131   first_step_ = 0;
00132   last_step_ = 0;
00133   cluster_ = 1;
00134   skip_ = 0;
00135 
00136   synchronize_time_ = synchronize_time;
00137   hardware_clock_ = 0.0;
00138   last_hardware_time_stamp_ = 0;
00139   hardware_clock_adj_ = 0.0;
00140   adj_count_ = 0;
00141 
00142   if (using_intensity)
00143   {
00144     using_intensity = isIntensitySupported();
00145   }
00146 
00147   if (using_multiecho)
00148   {
00149     using_multiecho = isMultiEchoSupported();
00150   }
00151 
00152   use_intensity_ = using_intensity;
00153   use_multiecho_ = using_multiecho;
00154 
00155   measurement_type_ = URG_DISTANCE;
00156   if (use_intensity_ && use_multiecho_)
00157   {
00158     measurement_type_ = URG_MULTIECHO_INTENSITY;
00159   }
00160   else if (use_intensity_)
00161   {
00162     measurement_type_ = URG_DISTANCE_INTENSITY;
00163   }
00164   else if (use_multiecho_)
00165   {
00166     measurement_type_ = URG_MULTIECHO;
00167   }
00168 }
00169 
00170 void URGCWrapper::start()
00171 {
00172   if (!started_)
00173   {
00174     int result = urg_start_measurement(&urg_, measurement_type_, 0, skip_);
00175     if (result < 0)
00176     {
00177       std::stringstream ss;
00178       ss << "Could not start Hokuyo measurement:\n";
00179       if (use_intensity_)
00180       {
00181         ss << "With Intensity" << "\n";
00182       }
00183       if (use_multiecho_)
00184       {
00185         ss << "With MultiEcho" << "\n";
00186       }
00187       ss << urg_error(&urg_);
00188       throw std::runtime_error(ss.str());
00189     }
00190   }
00191   started_ = true;
00192 }
00193 
00194 void URGCWrapper::stop()
00195 {
00196   urg_stop_measurement(&urg_);
00197   started_ = false;
00198 }
00199 
00200 URGCWrapper::~URGCWrapper()
00201 {
00202   stop();
00203   urg_close(&urg_);
00204 }
00205 
00206 bool URGCWrapper::grabScan(const sensor_msgs::LaserScanPtr& msg)
00207 {
00208   msg->header.frame_id = frame_id_;
00209   msg->angle_min = getAngleMin();
00210   msg->angle_max = getAngleMax();
00211   msg->angle_increment = getAngleIncrement();
00212   msg->scan_time = getScanPeriod();
00213   msg->time_increment = getTimeIncrement();
00214   msg->range_min = getRangeMin();
00215   msg->range_max = getRangeMax();
00216 
00217   // Grab scan
00218   int num_beams = 0;
00219   long time_stamp = 0;
00220   unsigned long long system_time_stamp = 0;
00221 
00222   if (use_intensity_)
00223   {
00224     num_beams = urg_get_distance_intensity(&urg_, &data_[0], &intensity_[0], &time_stamp, &system_time_stamp);
00225   }
00226   else
00227   {
00228     num_beams = urg_get_distance(&urg_, &data_[0], &time_stamp, &system_time_stamp);
00229   }
00230   if (num_beams <= 0)
00231   {
00232     return false;
00233   }
00234 
00235   // Fill scan
00236   if (synchronize_time_)
00237   {
00238     msg->header.stamp = getSynchronizedTime(time_stamp, system_time_stamp);
00239   }
00240   else
00241   {
00242     msg->header.stamp.fromNSec((uint64_t)system_time_stamp);
00243   }
00244   msg->header.stamp = msg->header.stamp + system_latency_ + user_latency_ + getAngularTimeOffset();
00245   msg->ranges.resize(num_beams);
00246   if (use_intensity_)
00247   {
00248     msg->intensities.resize(num_beams);
00249   }
00250 
00251   for (int i = 0; i < num_beams; i++)
00252   {
00253     if (data_[(i) + 0] != 0)
00254     {
00255       msg->ranges[i] = static_cast<float>(data_[i]) / 1000.0;
00256       if (use_intensity_)
00257       {
00258         msg->intensities[i] = intensity_[i];
00259       }
00260     }
00261     else
00262     {
00263       msg->ranges[i] = std::numeric_limits<float>::quiet_NaN();
00264       continue;
00265     }
00266   }
00267   return true;
00268 }
00269 
00270 bool URGCWrapper::grabScan(const sensor_msgs::MultiEchoLaserScanPtr& msg)
00271 {
00272   msg->header.frame_id = frame_id_;
00273   msg->angle_min = getAngleMin();
00274   msg->angle_max = getAngleMax();
00275   msg->angle_increment = getAngleIncrement();
00276   msg->scan_time = getScanPeriod();
00277   msg->time_increment = getTimeIncrement();
00278   msg->range_min = getRangeMin();
00279   msg->range_max = getRangeMax();
00280 
00281   // Grab scan
00282   int num_beams = 0;
00283   long time_stamp = 0;
00284   unsigned long long system_time_stamp;
00285 
00286   if (use_intensity_)
00287   {
00288     num_beams = urg_get_multiecho_intensity(&urg_, &data_[0], &intensity_[0], &time_stamp, &system_time_stamp);
00289   }
00290   else
00291   {
00292     num_beams = urg_get_multiecho(&urg_, &data_[0], &time_stamp, &system_time_stamp);
00293   }
00294   if (num_beams <= 0)
00295   {
00296     return false;
00297   }
00298 
00299   // Fill scan (uses vector.reserve wherever possible to avoid initalization and unecessary memory expansion)
00300   msg->header.stamp.fromNSec((uint64_t)system_time_stamp);
00301   msg->header.stamp = msg->header.stamp + system_latency_ + user_latency_ + getAngularTimeOffset();
00302   msg->ranges.reserve(num_beams);
00303   if (use_intensity_)
00304   {
00305     msg->intensities.reserve(num_beams);
00306   }
00307 
00308   for (size_t i = 0; i < num_beams; i++)
00309   {
00310     sensor_msgs::LaserEcho range_echo;
00311     range_echo.echoes.reserve(URG_MAX_ECHO);
00312     sensor_msgs::LaserEcho intensity_echo;
00313     if (use_intensity_)
00314     {
00315       intensity_echo.echoes.reserve(URG_MAX_ECHO);
00316     }
00317     for (size_t j = 0; j < URG_MAX_ECHO; j++)
00318     {
00319       if (data_[(URG_MAX_ECHO * i) + j] != 0)
00320       {
00321         range_echo.echoes.push_back(static_cast<float>(data_[(URG_MAX_ECHO * i) + j]) / 1000.0f);
00322         if (use_intensity_)
00323         {
00324           intensity_echo.echoes.push_back(intensity_[(URG_MAX_ECHO * i) + j]);
00325         }
00326       }
00327       else
00328       {
00329         break;
00330       }
00331     }
00332     msg->ranges.push_back(range_echo);
00333     if (use_intensity_)
00334     {
00335       msg->intensities.push_back(intensity_echo);
00336     }
00337   }
00338 
00339   return true;
00340 }
00341 
00342 bool URGCWrapper::getAR00Status(URGStatus& status)
00343 {
00344   // Construct and write AR00 command.
00345   std::string str_cmd;
00346   str_cmd += 0x02;  // STX
00347   str_cmd.append("000EAR00A012");  // AR00 cmd with length and checksum.
00348   str_cmd += 0x03;  // ETX
00349 
00350   // Get the response
00351   std::string response = sendCommand(str_cmd);
00352 
00353   ROS_DEBUG_STREAM("Full response: " << response);
00354 
00355   // Strip STX and ETX before calculating the CRC.
00356   response.erase(0, 1);
00357   response.erase(response.size() - 1, 1);
00358 
00359   // Get the CRC, it's the last 4 chars.
00360   std::stringstream ss;
00361   ss << response.substr(response.size() - 4, 4);
00362   uint16_t crc;
00363   ss >> std::hex >> crc;
00364 
00365   // Remove the CRC from the check.
00366   std::string msg = response.substr(0, response.size() - 4);
00367   // Check the checksum.
00368   uint16_t checksum_result = checkCRC(msg.data(), msg.size());
00369 
00370   if (checksum_result != crc)
00371   {
00372     ROS_WARN("Received bad frame, incorrect checksum");
00373     return false;
00374   }
00375 
00376   // Debug output reponse up to scan data.
00377   ROS_DEBUG_STREAM("Response: " << response.substr(0, 41));
00378   // Decode the result if crc checks out.
00379   // Grab the status
00380   ss.clear();
00381   ROS_DEBUG_STREAM("Status " << response.substr(8, 2));
00382   ss << response.substr(8, 2);  // Status is 8th position 2 chars.
00383   ss >> std::hex >> status.status;
00384 
00385   if (status.status != 0)
00386   {
00387     ROS_WARN("Received bad status");
00388     return false;
00389   }
00390 
00391   // Grab the operating mode
00392   ss.clear();
00393   ROS_DEBUG_STREAM("Operating mode " << response.substr(10, 1););
00394   ss << response.substr(10, 1);
00395   ss >> std::hex >> status.operating_mode;
00396 
00397   // Grab the area number
00398   ss.clear();
00399   ss << response.substr(11, 2);
00400   ROS_DEBUG_STREAM("Area Number " << response.substr(11, 2));
00401   ss >> std::hex >> status.area_number;
00402   // Per documentation add 1 to offset area number
00403   status.area_number++;
00404 
00405   // Grab the Error Status
00406   ss.clear();
00407   ss << response.substr(13, 1);
00408   ROS_DEBUG_STREAM("Error status " << response.substr(13, 1));
00409   ss >> std::hex >> status.error_status;
00410 
00411 
00412   // Grab the error code
00413   ss.clear();
00414   ss << response.substr(14, 2);
00415   ROS_DEBUG_STREAM("Error code " << std::hex << response.substr(14, 2));
00416   ss >> std::hex >> status.error_code;
00417   // Offset by 0x40 is non-zero as per documentation
00418   if (status.error_code != 0)
00419   {
00420      status.error_code += 0x40;
00421   }
00422 
00423   // Get the lockout status
00424   ss.clear();
00425   ss << response.substr(16, 1);
00426   ROS_DEBUG_STREAM("Lockout " << response.substr(16, 1));
00427   ss >> std::hex >> status.lockout_status;
00428 
00429   return true;
00430 }
00431 
00432 bool URGCWrapper::getDL00Status(UrgDetectionReport& report)
00433 {
00434   // Construct and write DL00 command.
00435   std::string str_cmd;
00436   str_cmd += 0x02;  // STX
00437   str_cmd.append("000EDL005BCB");  // DL00 cmd with length and checksum.
00438   str_cmd += 0x03;  // ETX
00439 
00440   // Get the response
00441   std::string response = sendCommand(str_cmd);
00442 
00443   ROS_DEBUG_STREAM("Full response: " << response);
00444 
00445   // Strip STX and ETX before calculating the CRC.
00446   response.erase(0, 1);
00447   response.erase(response.size() - 1, 1);
00448 
00449   // Get the CRC, it's the last 4 chars.
00450   std::stringstream ss;
00451   ss << response.substr(response.size() - 4, 4);
00452   uint16_t crc;
00453   ss >> std::hex >> crc;
00454 
00455   // Remove the CRC from the check.
00456   std::string msg = response.substr(0, response.size() - 4);
00457   // Check the checksum.
00458   uint16_t checksum_result = checkCRC(msg.data(), msg.size());
00459 
00460   if (checksum_result != crc)
00461   {
00462     ROS_WARN("Received bad frame, incorrect checksum");
00463     return false;
00464   }
00465 
00466   // Decode the result if crc checks out.
00467   // Grab the status
00468   uint16_t status = 0;
00469   ss.clear();
00470   ROS_DEBUG_STREAM("Status " << response.substr(8, 2));
00471   ss << response.substr(8, 2);  // Status is 8th position 2 chars.
00472   ss >> std::hex >> status;
00473 
00474   if (status != 0)
00475   {
00476     ROS_WARN("Received bad status");
00477     return false;
00478   }
00479 
00480   std::vector<UrgDetectionReport> reports;
00481   msg = msg.substr(10);  // remove the header.
00482   // Process the message, there are 29 reports.
00483   // The 30th report is a circular buff marker of area with 0xFF
00484   // denoting the "last" report being the previous one.
00485   for (int i = 0; i < 30; i++)
00486   {
00487     uint16_t area = 0;
00488     uint16_t distance = 0;
00489     uint16_t step = 0;
00490     ss.clear();
00491 
00492     // Each msg is 64 chars long, offset which
00493     // report is being read in.
00494     uint16_t offset_pos = i * 64;
00495     ss << msg.substr(offset_pos, 2);  // Area is 2 chars long
00496     ss >> std::hex >> area;
00497 
00498 
00499     ss.clear();
00500     ss << msg.substr(offset_pos + 4, 4);  // Distance is offset 4 from beginning, 4 chars long.
00501     ss >> std::hex >> distance;
00502 
00503     ss.clear();
00504     ss << msg.substr(offset_pos + 8, 4);  // "Step" is offset 8 from beginning 4 chars long.
00505     ss >> std::hex >> step;
00506     ROS_DEBUG_STREAM(i << " Area: " << area << " Distance: " << distance << " Step: " << step);
00507 
00508     UrgDetectionReport r;
00509     r.area = area;
00510     r.distance = distance;
00511     // From read value to angle of report is a value/8.
00512     r.angle = static_cast<float>(step) / 8.0;
00513 
00514     reports.push_back(r);
00515   }
00516 
00517   for (auto iter = reports.begin(); iter != reports.end(); ++iter)
00518   {
00519     // Check if value retrieved for area is FF.
00520     // if it is this is the last element lasers circular buffer.
00521     if (iter->area == 0xFF)
00522     {
00523       // Try and read the previous item.
00524       // if it's the beginning, then all reports
00525       // are empty.
00526       if (iter - 1 == reports.begin())
00527       {
00528         ROS_WARN("All reports are empty, no detections available.");
00529         report.status = status;
00530         return false;
00531       }
00532       if (iter - 1 != reports.begin())
00533       {
00534         report = *(iter-1);
00535         report.area += 1;  // Final area is offset by 1.
00536         report.status = status;
00537         break;
00538       }
00539     }
00540   }
00541 
00542   return true;
00543 }
00544 
00545 bool URGCWrapper::setToSCIP2()
00546 {
00547   if (urg_.connection.type == URG_ETHERNET)
00548     return false;
00549 
00550   char buffer[sizeof("SCIP2.0\n")];
00551   int n;
00552 
00553   do
00554   {
00555     n = serial_readline(&(urg_.connection.serial), buffer, sizeof(buffer), 1000);
00556   }
00557   while (n >= 0);
00558 
00559   serial_write(&(urg_.connection.serial), "SCIP2.0\n", sizeof(buffer));
00560   n = serial_readline(&(urg_.connection.serial), buffer, sizeof(buffer), 1000);
00561 
00562   // Check if switching was successful.
00563   if (n > 0 && strcmp(buffer, "SCIP2.0") == 0
00564     && urg_open(&urg_, URG_SERIAL, serial_port_.c_str(), (long)serial_baud_) >= 0)
00565   {
00566     ROS_DEBUG_STREAM("Set sensor to SCIP 2.0.");
00567     return true;
00568   }
00569   return false;
00570 }
00571 
00572 uint16_t URGCWrapper::checkCRC(const char* bytes, const uint32_t size)
00573 {
00574   boost::crc_optimal<16, 0x1021, 0, 0, true, true>  crc_kermit_type;
00575   crc_kermit_type.process_bytes(bytes, size);
00576   return crc_kermit_type.checksum();
00577 }
00578 
00579 std::string URGCWrapper::sendCommand(std::string cmd)
00580 {
00581   std::string result;
00582   bool restart = false;
00583 
00584   if (isStarted())
00585   {
00586     restart = true;
00587     // Scan must stop before sending a command
00588     stop();
00589   }
00590 
00591   // Get the socket reference and send
00592   int sock = urg_.connection.tcpclient.sock_desc;
00593   write(sock, cmd.c_str(), cmd.size());
00594 
00595   // All serial command structures start with STX + LEN as
00596   // the first 5 bytes, read those in.
00597   size_t total_read_len = 0;
00598   size_t read_len = 0;
00599   // Read in the header, make sure we get all 5 bytes expcted
00600   char recvb[5] = {0};
00601   ssize_t expected_read = 5;
00602   while (total_read_len < expected_read)
00603   {
00604     read_len = read(sock, recvb + total_read_len, expected_read - total_read_len);  // READ STX
00605     total_read_len += read_len;
00606     if (read_len <= 0)
00607     {
00608       ROS_ERROR("Read socket failed: %s", strerror(errno));
00609       result.clear();
00610       return result;
00611     }
00612   }
00613 
00614   std::string recv_header(recvb, read_len);
00615   // Convert the read len from hex chars to int.
00616   std::stringstream ss;
00617   ss << recv_header.substr(1, 4);
00618   ss >> std::hex >> expected_read;
00619   ROS_DEBUG_STREAM("Read len " << expected_read);
00620 
00621   // Already read len of 5, take that out.
00622   uint32_t arr_size = expected_read - 5;
00623   // Bounds check the size, we really shouldn't exceed 8703 bytes
00624   // based on the currently known messages on the hokuyo documentations
00625   if (arr_size > 10000)
00626   {
00627     ROS_ERROR("Buffer creation bounds exceeded, shouldn't allocate: %u bytes", arr_size);
00628     result.clear();
00629     return result;
00630   }
00631 
00632   ROS_DEBUG_STREAM("Creating buffer read of arr_Size: " << arr_size);
00633   // Create buffer space for read.
00634   boost::shared_array<char> data;
00635   data.reset(new char[arr_size]);
00636 
00637   // Read the remaining command
00638   total_read_len = 0;
00639   read_len = 0;
00640   expected_read = arr_size;
00641 
00642   ROS_DEBUG_STREAM("Expected body size: " << expected_read);
00643   while (total_read_len < expected_read)
00644   {
00645     read_len = read(sock, data.get()+total_read_len, expected_read - total_read_len);
00646     total_read_len += read_len;
00647     ROS_DEBUG_STREAM("Read in after header " << read_len);
00648     if (read_len <= 0)
00649     {
00650       ROS_ERROR("Read socket failed: %s", strerror(errno));
00651       result.clear();
00652       return result;
00653     }
00654   }
00655 
00656   // Combine the read portions to return for processing.
00657   result += recv_header;
00658   result += std::string(data.get(), expected_read);
00659 
00660   // Resume scan after sending.
00661   if (restart)
00662   {
00663     start();
00664   }
00665 
00666   return result;
00667 }
00668 
00669 bool URGCWrapper::isStarted() const
00670 {
00671   return started_;
00672 }
00673 
00674 double URGCWrapper::getRangeMin() const
00675 {
00676   long minr;
00677   long maxr;
00678   urg_distance_min_max(&urg_, &minr, &maxr);
00679   return static_cast<double>(minr) / 1000.0;
00680 }
00681 
00682 double URGCWrapper::getRangeMax() const
00683 {
00684   long minr;
00685   long maxr;
00686   urg_distance_min_max(&urg_, &minr, &maxr);
00687   return static_cast<double>(maxr) / 1000.0;
00688 }
00689 
00690 double URGCWrapper::getAngleMin() const
00691 {
00692   return urg_step2rad(&urg_, first_step_);
00693 }
00694 
00695 double URGCWrapper::getAngleMax() const
00696 {
00697   return urg_step2rad(&urg_, last_step_);
00698 }
00699 
00700 double URGCWrapper::getAngleMinLimit() const
00701 {
00702   int min_step;
00703   int max_step;
00704   urg_step_min_max(&urg_, &min_step, &max_step);
00705   return urg_step2rad(&urg_, min_step);
00706 }
00707 
00708 double URGCWrapper::getAngleMaxLimit() const
00709 {
00710   int min_step;
00711   int max_step;
00712   urg_step_min_max(&urg_, &min_step, &max_step);
00713   return urg_step2rad(&urg_, max_step);
00714 }
00715 
00716 double URGCWrapper::getAngleIncrement() const
00717 {
00718   double angle_min = getAngleMin();
00719   double angle_max = getAngleMax();
00720   return cluster_ * (angle_max - angle_min) / static_cast<double>(last_step_ - first_step_);
00721 }
00722 
00723 double URGCWrapper::getScanPeriod() const
00724 {
00725   long scan_usec = urg_scan_usec(&urg_);
00726   return 1.e-6 * static_cast<double>(scan_usec);
00727 }
00728 
00729 double URGCWrapper::getTimeIncrement() const
00730 {
00731   int min_step;
00732   int max_step;
00733   urg_step_min_max(&urg_, &min_step, &max_step);
00734   double scan_period = getScanPeriod();
00735   double circle_fraction = (getAngleMaxLimit() - getAngleMinLimit()) / (2.0 * 3.141592);
00736   return cluster_ * circle_fraction * scan_period / static_cast<double>(max_step - min_step);
00737 }
00738 
00739 
00740 std::string URGCWrapper::getIPAddress() const
00741 {
00742   return ip_address_;
00743 }
00744 
00745 int URGCWrapper::getIPPort() const
00746 {
00747   return ip_port_;
00748 }
00749 
00750 std::string URGCWrapper::getSerialPort() const
00751 {
00752   return serial_port_;
00753 }
00754 
00755 int URGCWrapper::getSerialBaud() const
00756 {
00757   return serial_baud_;
00758 }
00759 
00760 std::string URGCWrapper::getVendorName()
00761 {
00762   return std::string(urg_sensor_vendor(&urg_));
00763 }
00764 
00765 std::string URGCWrapper::getProductName()
00766 {
00767   return std::string(urg_sensor_product_type(&urg_));
00768 }
00769 
00770 std::string URGCWrapper::getFirmwareVersion()
00771 {
00772   return std::string(urg_sensor_firmware_version(&urg_));
00773 }
00774 
00775 std::string URGCWrapper::getFirmwareDate()
00776 {
00777   return std::string(urg_sensor_firmware_date(&urg_));
00778 }
00779 
00780 std::string URGCWrapper::getProtocolVersion()
00781 {
00782   return std::string(urg_sensor_protocol_version(&urg_));
00783 }
00784 
00785 std::string URGCWrapper::getDeviceID()
00786 {
00787   return std::string(urg_sensor_serial_id(&urg_));
00788 }
00789 
00790 ros::Duration URGCWrapper::getComputedLatency() const
00791 {
00792   return system_latency_;
00793 }
00794 
00795 ros::Duration URGCWrapper::getUserTimeOffset() const
00796 {
00797   return user_latency_;
00798 }
00799 
00800 std::string URGCWrapper::getSensorStatus()
00801 {
00802   return std::string(urg_sensor_status(&urg_));
00803 }
00804 
00805 std::string URGCWrapper::getSensorState()
00806 {
00807   return std::string(urg_sensor_state(&urg_));
00808 }
00809 
00810 void URGCWrapper::setFrameId(const std::string& frame_id)
00811 {
00812   frame_id_ = frame_id;
00813 }
00814 
00815 void URGCWrapper::setUserLatency(const double latency)
00816 {
00817   user_latency_.fromSec(latency);
00818 }
00819 
00820 // Must be called before urg_start
00821 bool URGCWrapper::setAngleLimitsAndCluster(double& angle_min, double& angle_max, int cluster)
00822 {
00823   if (started_)
00824   {
00825     return false;  // Must not be streaming
00826   }
00827 
00828   // Set step limits
00829   first_step_ = urg_rad2step(&urg_, angle_min);
00830   last_step_ = urg_rad2step(&urg_, angle_max);
00831   cluster_ = cluster;
00832 
00833   // Make sure step limits are not the same
00834   if (first_step_ == last_step_)
00835   {
00836     // Make sure we're not at a limit
00837     int min_step;
00838     int max_step;
00839     urg_step_min_max(&urg_, &min_step, &max_step);
00840     if (first_step_ == min_step)  // At beginning of range
00841     {
00842       last_step_ = first_step_ + 1;
00843     }
00844     else     // At end of range (or all other cases)
00845     {
00846       first_step_ = last_step_ - 1;
00847     }
00848   }
00849 
00850   // Make sure angle_max is greater than angle_min (should check this after end limits)
00851   if (last_step_ < first_step_)
00852   {
00853     double temp = first_step_;
00854     first_step_ = last_step_;
00855     last_step_ = temp;
00856   }
00857 
00858   angle_min = urg_step2rad(&urg_, first_step_);
00859   angle_max = urg_step2rad(&urg_, last_step_);
00860   int result = urg_set_scanning_parameter(&urg_, first_step_, last_step_, cluster);
00861   if (result < 0)
00862   {
00863     return false;
00864   }
00865   return true;
00866 }
00867 
00868 bool URGCWrapper::setSkip(int skip)
00869 {
00870   skip_ = skip;
00871 }
00872 
00873 bool URGCWrapper::isIntensitySupported()
00874 {
00875   if (started_)
00876   {
00877     return false;  // Must not be streaming
00878   }
00879 
00880   urg_start_measurement(&urg_, URG_DISTANCE_INTENSITY, 0, 0);
00881   int ret = urg_get_distance_intensity(&urg_, &data_[0], &intensity_[0], NULL, NULL);
00882   if (ret <= 0)
00883   {
00884     return false;  // Failed to start measurement with intensity: must not support it
00885   }
00886   urg_stop_measurement(&urg_);
00887   return true;
00888 }
00889 
00890 bool URGCWrapper::isMultiEchoSupported()
00891 {
00892   if (started_)
00893   {
00894     return false;  // Must not be streaming
00895   }
00896 
00897   urg_start_measurement(&urg_, URG_MULTIECHO, 0, 0);
00898   int ret = urg_get_multiecho(&urg_, &data_[0], NULL, NULL);
00899   if (ret <= 0)
00900   {
00901     return false;  // Failed to start measurement with multiecho: must not support it
00902   }
00903   urg_stop_measurement(&urg_);
00904   return true;
00905 }
00906 
00907 ros::Duration URGCWrapper::getAngularTimeOffset() const
00908 {
00909   // Adjust value for Hokuyo's timestamps
00910   // Hokuyo's timestamps start from the rear center of the device (at Pi according to ROS standards)
00911   double circle_fraction = 0.0;
00912   if (first_step_ == 0 && last_step_ == 0)
00913   {
00914     circle_fraction = (getAngleMinLimit() + 3.141592) / (2.0 * 3.141592);
00915   }
00916   else
00917   {
00918     circle_fraction = (getAngleMin() + 3.141592) / (2.0 * 3.141592);
00919   }
00920   return ros::Duration(circle_fraction * getScanPeriod());
00921 }
00922 
00923 ros::Duration URGCWrapper::computeLatency(size_t num_measurements)
00924 {
00925   system_latency_.fromNSec(0);
00926 
00927   ros::Duration start_offset = getNativeClockOffset(1);
00928   ros::Duration previous_offset;
00929 
00930   std::vector<ros::Duration> time_offsets(num_measurements);
00931   for (size_t i = 0; i < num_measurements; i++)
00932   {
00933     ros::Duration scan_offset = getTimeStampOffset(1);
00934     ros::Duration post_offset = getNativeClockOffset(1);
00935     ros::Duration adjusted_scan_offset = scan_offset - start_offset;
00936     ros::Duration adjusted_post_offset = post_offset - start_offset;
00937     ros::Duration average_offset;
00938     average_offset.fromSec((adjusted_post_offset.toSec() + previous_offset.toSec()) / 2.0);
00939 
00940     time_offsets[i] = adjusted_scan_offset - average_offset;
00941 
00942     previous_offset = adjusted_post_offset;
00943   }
00944 
00945   // Get median value
00946   // Sort vector using nth_element (partially sorts up to the median index)
00947   std::nth_element(time_offsets.begin(), time_offsets.begin() + time_offsets.size() / 2, time_offsets.end());
00948   system_latency_ = time_offsets[time_offsets.size() / 2];
00949   // Angular time offset makes the output comparable to that of hokuyo_node
00950   return system_latency_ + getAngularTimeOffset();
00951 }
00952 
00953 ros::Duration URGCWrapper::getNativeClockOffset(size_t num_measurements)
00954 {
00955   if (started_)
00956   {
00957     std::stringstream ss;
00958     ss << "Cannot get native clock offset while started.";
00959     throw std::runtime_error(ss.str());
00960   }
00961 
00962   if (urg_start_time_stamp_mode(&urg_) < 0)
00963   {
00964     std::stringstream ss;
00965     ss << "Cannot start time stamp mode.";
00966     throw std::runtime_error(ss.str());
00967   }
00968 
00969   std::vector<ros::Duration> time_offsets(num_measurements);
00970   for (size_t i = 0; i < num_measurements; i++)
00971   {
00972     ros::Time request_time = ros::Time::now();
00973     ros::Time laser_time;
00974     laser_time.fromNSec(1e6 * (uint64_t)urg_time_stamp(&urg_));  // 1e6 * milliseconds = nanoseconds
00975     ros::Time response_time = ros::Time::now();
00976     ros::Time average_time;
00977     average_time.fromSec((response_time.toSec() + request_time.toSec()) / 2.0);
00978     time_offsets[i] = laser_time - average_time;
00979   }
00980 
00981   if (urg_stop_time_stamp_mode(&urg_) < 0)
00982   {
00983     std::stringstream ss;
00984     ss << "Cannot stop time stamp mode.";
00985     throw std::runtime_error(ss.str());
00986   };
00987 
00988   // Return median value
00989   // Sort vector using nth_element (partially sorts up to the median index)
00990   std::nth_element(time_offsets.begin(), time_offsets.begin() + time_offsets.size() / 2, time_offsets.end());
00991   return time_offsets[time_offsets.size() / 2];
00992 }
00993 
00994 ros::Duration URGCWrapper::getTimeStampOffset(size_t num_measurements)
00995 {
00996   if (started_)
00997   {
00998     std::stringstream ss;
00999     ss << "Cannot get time stamp offset while started.";
01000     throw std::runtime_error(ss.str());
01001   }
01002 
01003   start();
01004 
01005   std::vector<ros::Duration> time_offsets(num_measurements);
01006   for (size_t i = 0; i < num_measurements; i++)
01007   {
01008     long time_stamp;
01009     unsigned long long system_time_stamp;
01010     int ret = 0;
01011 
01012     if (measurement_type_ == URG_DISTANCE)
01013     {
01014       ret = urg_get_distance(&urg_, &data_[0], &time_stamp, &system_time_stamp);
01015     }
01016     else if (measurement_type_ == URG_DISTANCE_INTENSITY)
01017     {
01018       ret = urg_get_distance_intensity(&urg_, &data_[0], &intensity_[0], &time_stamp, &system_time_stamp);
01019     }
01020     else if (measurement_type_ == URG_MULTIECHO)
01021     {
01022       ret = urg_get_multiecho(&urg_, &data_[0], &time_stamp, &system_time_stamp);
01023     }
01024     else if (measurement_type_ == URG_MULTIECHO_INTENSITY)
01025     {
01026       ret = urg_get_multiecho_intensity(&urg_, &data_[0], &intensity_[0], &time_stamp, &system_time_stamp);
01027     }
01028 
01029     if (ret <= 0)
01030     {
01031       std::stringstream ss;
01032       ss << "Cannot get scan to measure time stamp offset.";
01033       throw std::runtime_error(ss.str());
01034     }
01035 
01036     ros::Time laser_timestamp;
01037     laser_timestamp.fromNSec(1e6 * (uint64_t)time_stamp);
01038     ros::Time system_time;
01039     system_time.fromNSec((uint64_t)system_time_stamp);
01040 
01041     time_offsets[i] = laser_timestamp - system_time;
01042   }
01043 
01044   stop();
01045 
01046   // Return median value
01047   // Sort vector using nth_element (partially sorts up to the median index)
01048   std::nth_element(time_offsets.begin(), time_offsets.begin() + time_offsets.size() / 2, time_offsets.end());
01049   return time_offsets[time_offsets.size() / 2];
01050 }
01051 
01052 ros::Time URGCWrapper::getSynchronizedTime(long time_stamp, long long system_time_stamp)
01053 {
01054   ros::Time stamp, system_time;
01055   system_time.fromNSec((uint64_t)system_time_stamp);
01056   stamp = system_time;
01057 
01058   const uint32_t t1 = static_cast<uint32_t>(time_stamp);
01059   const uint32_t t0 = static_cast<uint32_t>(last_hardware_time_stamp_);
01060   // hokuyo uses a 24-bit counter, so mask out irrelevant bits
01061   const uint32_t mask = 0x00ffffff;
01062   double delta = static_cast<double>(mask&(t1-t0))/1000.0;
01063   hardware_clock_ += delta;
01064   double cur_adj = stamp.toSec() - hardware_clock_;
01065   if (adj_count_ > 0)
01066   {
01067     hardware_clock_adj_ = adj_alpha_*cur_adj+(1.0-adj_alpha_)*hardware_clock_adj_;
01068   }
01069   else
01070   {
01071     // Initialize the EMA
01072     hardware_clock_adj_ = cur_adj;
01073   }
01074   adj_count_++;
01075   last_hardware_time_stamp_ = time_stamp;
01076 
01077   // Once hardware clock is synchronized, use it. Otherwise just return the
01078   // input system_time_stamp as ros::Time.
01079   if (adj_count_ > 100)
01080   {
01081     stamp.fromSec(hardware_clock_+hardware_clock_adj_);
01082     // If the time error is large a clock warp has occurred.
01083     // Reset the EMA and use the system time.
01084     if (fabs((stamp-system_time).toSec()) > 0.1)
01085     {
01086         adj_count_ = 0;
01087         hardware_clock_ = 0.0;
01088         last_hardware_time_stamp_ = 0;
01089         stamp = system_time;
01090         ROS_INFO("%s: detected clock warp, reset EMA", __func__);
01091     }
01092   }
01093   return stamp;
01094 }
01095 }  // namespace urg_node


urg_node
Author(s): Chad Rockey , Mike O'Driscoll
autogenerated on Sat Jun 8 2019 19:16:00