Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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, bool& using_intensity, bool& using_multiecho);
00093
00094 URGCWrapper(const int serial_baud, const std::string& serial_port, bool& using_intensity, bool& using_multiecho);
00095
00096 ~URGCWrapper();
00097
00098 void start();
00099
00100 void stop();
00101
00102 bool isStarted() const;
00103
00104 double getRangeMin() const;
00105
00106 double getRangeMax() const;
00107
00108 double getAngleMin() const;
00109
00110 double getAngleMax() const;
00111
00112 double getAngleMinLimit() const;
00113
00114 double getAngleMaxLimit() const;
00115
00116 double getAngleIncrement() const;
00117
00118 double getScanPeriod() const;
00119
00120 double getTimeIncrement() const;
00121
00122 std::string getIPAddress() const;
00123
00124 int getIPPort() const;
00125
00126 std::string getSerialPort() const;
00127
00128 int getSerialBaud() const;
00129
00130 std::string getVendorName();
00131
00132 std::string getProductName();
00133
00134 std::string getFirmwareVersion();
00135
00136 std::string getFirmwareDate();
00137
00138 std::string getProtocolVersion();
00139
00140 std::string getDeviceID();
00141
00142 ros::Duration getComputedLatency() const;
00143
00144 ros::Duration getUserTimeOffset() const;
00145
00146 std::string getSensorStatus();
00147
00148 std::string getSensorState();
00149
00150 void setFrameId(const std::string& frame_id);
00151
00152 void setUserLatency(const double latency);
00153
00154 bool setAngleLimitsAndCluster(double& angle_min, double& angle_max, int cluster);
00155
00156 bool setSkip(int skip);
00157
00158 ros::Duration computeLatency(size_t num_measurements);
00159
00160 bool grabScan(const sensor_msgs::LaserScanPtr& msg);
00161
00162 bool grabScan(const sensor_msgs::MultiEchoLaserScanPtr& msg);
00163
00164 bool getAR00Status(URGStatus& status);
00165
00166 bool getDL00Status(UrgDetectionReport& report);
00167
00168 private:
00169 void initialize(bool& using_intensity, bool& using_multiecho);
00170
00171 bool isIntensitySupported();
00172
00173 bool isMultiEchoSupported();
00174
00175 ros::Duration getAngularTimeOffset() const;
00176
00177 ros::Duration getNativeClockOffset(size_t num_measurements);
00178
00179 ros::Duration getTimeStampOffset(size_t num_measurements);
00180
00187 uint16_t checkCRC(const char* bytes, const uint32_t size);
00188
00195 std::string sendCommand(std::string cmd);
00196
00197 std::string frame_id_;
00198
00199 urg_t urg_;
00200 bool started_;
00201
00202 std::vector<long> data_;
00203 std::vector<unsigned short> intensity_;
00204
00205 bool use_intensity_;
00206 bool use_multiecho_;
00207 urg_measurement_type_t measurement_type_;
00208 int first_step_;
00209 int last_step_;
00210 int cluster_;
00211 int skip_;
00212
00213 ros::Duration system_latency_;
00214 ros::Duration user_latency_;
00215
00216 std::string ip_address_;
00217 int ip_port_;
00218 std::string serial_port_;
00219 int serial_baud_;
00220 };
00221 }
00222
00223 #endif // URG_NODE_URG_C_WRAPPER_H