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