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


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