urg_c_wrapper.h
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
00032  */
00033 
00034 #ifndef URG_NODE_URG_C_WRAPPER_H
00035 #define URG_NODE_URG_C_WRAPPER_H
00036 
00037 #include <stdexcept>
00038 #include <sstream>
00039 #include <vector>
00040 #include <string>
00041 
00042 #include <sensor_msgs/LaserScan.h>
00043 #include <sensor_msgs/MultiEchoLaserScan.h>
00044 
00045 #include <urg_c/urg_sensor.h>
00046 #include <urg_c/urg_utils.h>
00047 
00048 namespace urg_node
00049 {
00050 
00051 class URGStatus
00052 {
00053 public:
00054   URGStatus()
00055   {
00056     status = 0;
00057     operating_mode = 0;
00058     area_number = 0;
00059     error_status = false;
00060     error_code = 0;
00061     lockout_status = false;
00062   }
00063 
00064   uint16_t status;
00065   uint16_t operating_mode;
00066   uint16_t area_number;
00067   bool error_status;
00068   uint16_t error_code;
00069   bool lockout_status;
00070 };
00071 
00072 class UrgDetectionReport
00073 {
00074 public:
00075   UrgDetectionReport()
00076   {
00077     status = 0;
00078     area = 0;
00079     distance = 0;
00080     angle = 0;
00081   }
00082 
00083   uint16_t status;
00084   uint16_t area;
00085   uint16_t distance;
00086   float angle;
00087 };
00088 
00089 class URGCWrapper
00090 {
00091 public:
00092   URGCWrapper(const std::string& ip_address, const int ip_port,
00093       bool& using_intensity, bool& using_multiecho, bool synchronize_time);
00094 
00095   URGCWrapper(const int serial_baud, const std::string& serial_port,
00096       bool& using_intensity, bool& using_multiecho, bool synchronize_time);
00097 
00098   ~URGCWrapper();
00099 
00100   void start();
00101 
00102   void stop();
00103 
00104   bool isStarted() const;
00105 
00106   double getRangeMin() const;
00107 
00108   double getRangeMax() const;
00109 
00110   double getAngleMin() const;
00111 
00112   double getAngleMax() const;
00113 
00114   double getAngleMinLimit() const;
00115 
00116   double getAngleMaxLimit() const;
00117 
00118   double getAngleIncrement() const;
00119 
00120   double getScanPeriod() const;
00121 
00122   double getTimeIncrement() const;
00123 
00124   std::string getIPAddress() const;
00125 
00126   int getIPPort() const;
00127 
00128   std::string getSerialPort() const;
00129 
00130   int getSerialBaud() const;
00131 
00132   std::string getVendorName();
00133 
00134   std::string getProductName();
00135 
00136   std::string getFirmwareVersion();
00137 
00138   std::string getFirmwareDate();
00139 
00140   std::string getProtocolVersion();
00141 
00142   std::string getDeviceID();
00143 
00144   ros::Duration getComputedLatency() const;
00145 
00146   ros::Duration getUserTimeOffset() const;
00147 
00148   std::string getSensorStatus();
00149 
00150   std::string getSensorState();
00151 
00152   void setFrameId(const std::string& frame_id);
00153 
00154   void setUserLatency(const double latency);
00155 
00156   bool setAngleLimitsAndCluster(double& angle_min, double& angle_max, int cluster);
00157 
00158   bool setSkip(int skip);
00159 
00160   ros::Duration computeLatency(size_t num_measurements);
00161 
00162   bool grabScan(const sensor_msgs::LaserScanPtr& msg);
00163 
00164   bool grabScan(const sensor_msgs::MultiEchoLaserScanPtr& msg);
00165 
00166   bool getAR00Status(URGStatus& status);
00167 
00168   bool getDL00Status(UrgDetectionReport& report);
00169 
00170 private:
00171   void initialize(bool& using_intensity, bool& using_multiecho, bool synchronize_time);
00172 
00173   bool isIntensitySupported();
00174 
00175   bool isMultiEchoSupported();
00176 
00177   ros::Duration getAngularTimeOffset() const;
00178 
00179   ros::Duration getNativeClockOffset(size_t num_measurements);
00180 
00181   ros::Duration getTimeStampOffset(size_t num_measurements);
00182 
00189   ros::Time getSynchronizedTime(long time_stamp, long long system_time_stamp);
00190 
00195   bool setToSCIP2();
00196 
00203   uint16_t checkCRC(const char* bytes, const uint32_t size);
00204 
00211   std::string sendCommand(std::string cmd);
00212 
00213   std::string frame_id_;  
00214 
00215   urg_t urg_;
00216   bool started_;
00217 
00218   std::vector<long> data_;
00219   std::vector<unsigned short> intensity_;
00220 
00221   bool use_intensity_;
00222   bool use_multiecho_;
00223   urg_measurement_type_t measurement_type_;
00224   int first_step_;
00225   int last_step_;
00226   int cluster_;
00227   int skip_;
00228 
00229   ros::Duration system_latency_;
00230   ros::Duration user_latency_;
00231 
00232   // used for clock synchronziation
00233   bool synchronize_time_;
00234   double hardware_clock_;
00235   long last_hardware_time_stamp_;
00236   double hardware_clock_adj_;
00237   const double adj_alpha_ = .01;
00238   uint64_t adj_count_;
00239 
00240   std::string ip_address_;
00241   int ip_port_;
00242   std::string serial_port_;
00243   int serial_baud_;
00244 };
00245 }  // namespace urg_node
00246 
00247 #endif  // URG_NODE_URG_C_WRAPPER_H


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