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
00035 #include <sick_tim/sick_tim551_2050001_parser.h>
00036
00037 #include <ros/ros.h>
00038
00039 namespace sick_tim
00040 {
00041
00042 SickTim5512050001Parser::SickTim5512050001Parser() :
00043 AbstractParser(),
00044 override_range_min_(0.05),
00045 override_range_max_(10.0),
00046 override_time_increment_(-1.0)
00047 {
00048 }
00049
00050 SickTim5512050001Parser::~SickTim5512050001Parser()
00051 {
00052 }
00053
00054 int SickTim5512050001Parser::parse_datagram(char* datagram, size_t datagram_length, SickTimConfig &config,
00055 sensor_msgs::LaserScan &msg)
00056 {
00057 static const size_t HEADER_FIELDS = 33;
00058 char* cur_field;
00059 size_t count;
00060
00061
00062 std::vector<char *> fields;
00063 fields.reserve(datagram_length / 2);
00064
00065
00066 char datagram_copy[datagram_length + 1];
00067 strncpy(datagram_copy, datagram, datagram_length);
00068 datagram_copy[datagram_length] = 0;
00069
00070
00071 count = 0;
00072 cur_field = strtok(datagram, " ");
00073
00074 while (cur_field != NULL)
00075 {
00076 fields.push_back(cur_field);
00077 cur_field = strtok(NULL, " ");
00078 }
00079
00080 count = fields.size();
00081
00082
00083
00084
00085 if (count < HEADER_FIELDS)
00086 {
00087 ROS_WARN(
00088 "received less fields than minimum fields (actual: %zu, minimum: %zu), ignoring scan", count, HEADER_FIELDS);
00089 ROS_WARN("are you using the correct node? (124 --> sick_tim310_1130000m01, > 33 --> sick_tim551_2050001, 580 --> sick_tim310s01, 592 --> sick_tim310)");
00090
00091 return ExitError;
00092 }
00093 if (strcmp(fields[15], "0"))
00094 {
00095 ROS_WARN("Field 15 of received data is not equal to 0 (%s). Unexpected data, ignoring scan", fields[15]);
00096 return ExitError;
00097 }
00098 if (strcmp(fields[20], "DIST1"))
00099 {
00100 ROS_WARN("Field 20 of received data is not equal to DIST1i (%s). Unexpected data, ignoring scan", fields[20]);
00101 return ExitError;
00102 }
00103
00104
00105
00106 unsigned short int number_of_data = 0;
00107 sscanf(fields[25], "%hx", &number_of_data);
00108
00109 if (number_of_data < 1 || number_of_data > 811)
00110 {
00111 ROS_WARN("Data length is outside acceptable range 1-811 (%d). Ignoring scan", number_of_data);
00112 return ExitError;
00113 }
00114 if (count < HEADER_FIELDS + number_of_data)
00115 {
00116 ROS_WARN("Less fields than expected for %d data points (%zu). Ignoring scan", number_of_data, count);
00117 return ExitError;
00118 }
00119 ROS_DEBUG("Number of data: %d", number_of_data);
00120
00121
00122 size_t rssi_idx = 26 + number_of_data;
00123 int tmp;
00124 sscanf(fields[rssi_idx], "%d", &tmp);
00125 bool rssi = tmp > 0;
00126 unsigned short int number_of_rssi_data = 0;
00127 if (rssi)
00128 {
00129 sscanf(fields[rssi_idx + 6], "%hx", &number_of_rssi_data);
00130
00131
00132 if (number_of_rssi_data != number_of_data)
00133 {
00134 ROS_WARN("Number of RSSI data is lower than number of range data (%d vs %d", number_of_data, number_of_rssi_data);
00135 return ExitError;
00136 }
00137
00138
00139
00140 if (count < HEADER_FIELDS + number_of_data + number_of_rssi_data + 6)
00141 {
00142 ROS_WARN("Less fields than expected for %d data points (%zu). Ignoring scan", number_of_data, count);
00143 return ExitError;
00144 }
00145
00146 if (strcmp(fields[rssi_idx + 1], "RSSI1"))
00147 {
00148 ROS_WARN("Field %zu of received data is not equal to RSSI1 (%s). Unexpected data, ignoring scan", rssi_idx + 1, fields[rssi_idx + 1]);
00149 }
00150 }
00151
00152
00153 msg.header.frame_id = config.frame_id;
00154 ROS_DEBUG("publishing with frame_id %s", config.frame_id.c_str());
00155
00156 ros::Time start_time = ros::Time::now();
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174 unsigned short scanning_freq = -1;
00175 sscanf(fields[16], "%hx", &scanning_freq);
00176 msg.scan_time = 1.0 / (scanning_freq / 100.0);
00177
00178
00179
00180 unsigned short measurement_freq = -1;
00181 sscanf(fields[17], "%hx", &measurement_freq);
00182 msg.time_increment = 1.0 / (measurement_freq * 100.0);
00183 if (override_time_increment_ > 0.0)
00184 {
00185
00186 msg.time_increment = override_time_increment_;
00187 }
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204 int starting_angle = -1;
00205 sscanf(fields[23], "%x", &starting_angle);
00206 msg.angle_min = (starting_angle / 10000.0) / 180.0 * M_PI - M_PI / 2;
00207
00208
00209
00210 unsigned short angular_step_width = -1;
00211 sscanf(fields[24], "%hx", &angular_step_width);
00212 msg.angle_increment = (angular_step_width / 10000.0) / 180.0 * M_PI;
00213 msg.angle_max = msg.angle_min + (number_of_data - 1) * msg.angle_increment;
00214
00215
00216
00217
00218
00219 int index_min = 0;
00220 while (msg.angle_min + msg.angle_increment < config.min_ang)
00221 {
00222 msg.angle_min += msg.angle_increment;
00223 index_min++;
00224 }
00225
00226
00227 int index_max = number_of_data - 1;
00228 while (msg.angle_max - msg.angle_increment > config.max_ang)
00229 {
00230 msg.angle_max -= msg.angle_increment;
00231 index_max--;
00232 }
00233
00234 ROS_DEBUG("index_min: %d, index_max: %d", index_min, index_max);
00235
00236
00237
00238 msg.ranges.resize(index_max - index_min + 1);
00239 for (int j = index_min; j <= index_max; ++j)
00240 {
00241 unsigned short range;
00242 sscanf(fields[j + 26], "%hx", &range);
00243 msg.ranges[j - index_min] = range / 1000.0;
00244 }
00245
00246 if (config.intensity) {
00247 if (rssi)
00248 {
00249
00250
00251
00252
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262 msg.intensities.resize(index_max - index_min + 1);
00263 size_t offset = 26 + number_of_data + 7;
00264 for (int j = index_min; j <= index_max; ++j)
00265 {
00266 unsigned short intensity;
00267 sscanf(fields[j + offset], "%hx", &intensity);
00268 msg.intensities[j - index_min] = intensity;
00269 }
00270 } else {
00271 ROS_WARN_ONCE("Intensity parameter is enabled, but the scanner is not configured to send RSSI values! "
00272 "Please read the section 'Enabling intensity (RSSI) output' here: http://wiki.ros.org/sick_tim.");
00273 }
00274 }
00275
00276
00277
00278
00279
00280
00281
00282
00283 msg.range_min = override_range_min_;
00284 msg.range_max = override_range_max_;
00285
00286
00287
00288 msg.header.stamp = start_time - ros::Duration().fromSec(number_of_data * msg.time_increment);
00289
00290
00291 msg.header.stamp += ros::Duration().fromSec((double)index_min * msg.time_increment);
00292
00293
00294 msg.header.stamp += ros::Duration().fromSec(config.time_offset);
00295
00296
00297 float expected_time_increment = msg.scan_time * msg.angle_increment / (2.0 * M_PI);
00298 if (fabs(expected_time_increment - msg.time_increment) > 0.00001)
00299 {
00300 ROS_WARN_THROTTLE(60, "The time_increment, scan_time and angle_increment values reported by the scanner are inconsistent! "
00301 "Expected time_increment: %.9f, reported time_increment: %.9f. "
00302 "Perhaps you should set the parameter time_increment to the expected value. This message will print every 60 seconds.",
00303 expected_time_increment, msg.time_increment);
00304 }
00305
00306 return ExitSuccess;
00307 }
00308
00309 void SickTim5512050001Parser::set_range_min(float min)
00310 {
00311 override_range_min_ = min;
00312 }
00313
00314 void SickTim5512050001Parser::set_range_max(float max)
00315 {
00316 override_range_max_ = max;
00317 }
00318
00319 void SickTim5512050001Parser::set_time_increment(float time)
00320 {
00321 override_time_increment_ = time;
00322 }
00323
00324 }