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_C_WRAPPER_H 00035 #define URG_C_WRAPPER_H 00036 00037 #include <stdexcept> 00038 #include <sstream> 00039 #include <limits> 00040 00041 #include <sensor_msgs/LaserScan.h> 00042 #include <sensor_msgs/MultiEchoLaserScan.h> 00043 00044 #include <urg_c/urg_sensor.h> 00045 #include <urg_c/urg_utils.h> 00046 00047 namespace urg_node 00048 { 00049 class URGCWrapper 00050 { 00051 public: 00052 URGCWrapper(const std::string& ip_address, const int ip_port, bool& using_intensity, bool& using_multiecho); 00053 00054 URGCWrapper(const int serial_baud, const std::string& serial_port, bool& using_intensity, bool& using_multiecho); 00055 00056 ~URGCWrapper(); 00057 00058 void start(); 00059 00060 void stop(); 00061 00062 bool isStarted() const; 00063 00064 double getRangeMin() const; 00065 00066 double getRangeMax() const; 00067 00068 double getAngleMin() const; 00069 00070 double getAngleMax() const; 00071 00072 double getAngleMinLimit() const; 00073 00074 double getAngleMaxLimit() const; 00075 00076 double getAngleIncrement() const; 00077 00078 double getScanPeriod() const; 00079 00080 double getTimeIncrement() const; 00081 00082 std::string getIPAddress() const; 00083 00084 int getIPPort() const; 00085 00086 std::string getSerialPort() const; 00087 00088 int getSerialBaud() const; 00089 00090 std::string getVendorName(); 00091 00092 std::string getProductName(); 00093 00094 std::string getFirmwareVersion(); 00095 00096 std::string getFirmwareDate(); 00097 00098 std::string getProtocolVersion(); 00099 00100 std::string getDeviceID(); 00101 00102 ros::Duration getComputedLatency() const; 00103 00104 ros::Duration getUserTimeOffset() const; 00105 00106 std::string getSensorStatus(); 00107 00108 std::string getSensorState(); 00109 00110 void setFrameId(const std::string& frame_id); 00111 00112 void setUserLatency(const double latency); 00113 00114 bool setAngleLimitsAndCluster(double& angle_min, double& angle_max, int cluster); 00115 00116 bool setSkip(int skip); 00117 00118 ros::Duration computeLatency(size_t num_measurements); 00119 00120 bool grabScan(const sensor_msgs::LaserScanPtr& msg); 00121 00122 bool grabScan(const sensor_msgs::MultiEchoLaserScanPtr& msg); 00123 00124 private: 00125 void initialize(bool& using_intensity, bool& using_multiecho); 00126 00127 bool isIntensitySupported(); 00128 00129 bool isMultiEchoSupported(); 00130 00131 ros::Duration getAngularTimeOffset() const; 00132 00133 ros::Duration getNativeClockOffset(size_t num_measurements); 00134 00135 ros::Duration getTimeStampOffset(size_t num_measurements); 00136 00137 std::string frame_id_; 00138 00139 urg_t urg_; 00140 bool started_; 00141 00142 std::vector<long> data_; 00143 std::vector<unsigned short> intensity_; 00144 00145 bool use_intensity_; 00146 bool use_multiecho_; 00147 urg_measurement_type_t measurement_type_; 00148 int first_step_; 00149 int last_step_; 00150 int cluster_; 00151 int skip_; 00152 00153 ros::Duration system_latency_; 00154 ros::Duration user_latency_; 00155 00156 std::string ip_address_; 00157 int ip_port_; 00158 std::string serial_port_; 00159 int serial_baud_; 00160 }; 00161 00162 00163 }; // urg_node 00164 00165 #endif