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
00035 #include <sick_tim/sick_tim310_parser.h>
00036
00037 #include <ros/ros.h>
00038
00039 namespace sick_tim
00040 {
00041
00042 SickTim310Parser::SickTim310Parser() :
00043 AbstractParser()
00044 {
00045 }
00046
00047 SickTim310Parser::~SickTim310Parser()
00048 {
00049 }
00050
00051 int SickTim310Parser::parse_datagram(char* datagram, size_t datagram_length, SickTimConfig &config,
00052 sensor_msgs::LaserScan &msg)
00053 {
00054 static const size_t NUM_FIELDS = 592;
00055 char* fields[NUM_FIELDS];
00056 char* cur_field;
00057 size_t count;
00058
00059
00060 char datagram_copy[datagram_length + 1];
00061 strncpy(datagram_copy, datagram, datagram_length);
00062 datagram_copy[datagram_length] = 0;
00063
00064
00065 count = 0;
00066 cur_field = strtok(datagram, " ");
00067 fields[count] = cur_field;
00068
00069
00070 while (cur_field != NULL)
00071 {
00072 count++;
00073 cur_field = strtok(NULL, " ");
00074 if (count <= NUM_FIELDS)
00075 fields[count] = cur_field;
00076
00077
00078 }
00079
00080 if (count < NUM_FIELDS)
00081 {
00082 ROS_WARN(
00083 "received less fields than expected fields (actual: %zu, expected: %zu), ignoring scan", count, NUM_FIELDS);
00084 ROS_WARN("are you using the correct node? (124 --> sick_tim310_1130000m01, 306 --> sick_tim551_2050001, 580 --> sick_tim310s01, 592 --> sick_tim310)");
00085
00086 return EXIT_FAILURE;
00087 }
00088 else if (count > NUM_FIELDS)
00089 {
00090 ROS_WARN("received more fields than expected (actual: %zu, expected: %zu), ignoring scan", count, NUM_FIELDS);
00091 ROS_WARN("are you using the correct node? (124 --> sick_tim310_1130000m01, 306 --> sick_tim551_2050001, 580 --> sick_tim310s01, 592 --> sick_tim310)");
00092
00093 return EXIT_FAILURE;
00094 }
00095
00096
00097 msg.header.frame_id = config.frame_id;
00098 ROS_DEBUG("publishing with frame_id %s", config.frame_id.c_str());
00099
00100 ros::Time start_time = ros::Time::now();
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118 unsigned short scanning_freq = -1;
00119 sscanf(fields[16], "%hx", &scanning_freq);
00120 msg.scan_time = 1.0 / (scanning_freq / 100.0);
00121
00122
00123
00124 unsigned short measurement_freq = 36;
00125
00126 msg.time_increment = 1.0 / (measurement_freq * 100.0);
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143 int starting_angle = -1;
00144 sscanf(fields[25], "%x", &starting_angle);
00145 msg.angle_min = (starting_angle / 10000.0) / 180.0 * M_PI - M_PI / 2;
00146
00147
00148
00149 unsigned short angular_step_width = -1;
00150 sscanf(fields[26], "%hx", &angular_step_width);
00151 msg.angle_increment = (angular_step_width / 10000.0) / 180.0 * M_PI;
00152 msg.angle_max = msg.angle_min + 270.0 * msg.angle_increment;
00153
00154
00155 int index_min = 0;
00156 while (msg.angle_min + msg.angle_increment < config.min_ang)
00157 {
00158 msg.angle_min += msg.angle_increment;
00159 index_min++;
00160 }
00161
00162
00163 int index_max = 270;
00164 while (msg.angle_max - msg.angle_increment > config.max_ang)
00165 {
00166 msg.angle_max -= msg.angle_increment;
00167 index_max--;
00168 }
00169
00170 ROS_DEBUG("index_min: %d, index_max: %d", index_min, index_max);
00171
00172
00173
00174
00175
00176 msg.ranges.resize(index_max - index_min + 1);
00177 for (int j = index_min; j <= index_max; ++j)
00178 {
00179 unsigned short range;
00180 sscanf(fields[j + 28], "%hx", &range);
00181 msg.ranges[j - index_min] = range / 1000.0;
00182 }
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192 if (config.intensity)
00193 {
00194 msg.intensities.resize(index_max - index_min + 1);
00195 for (int j = index_min; j <= index_max; ++j)
00196 {
00197 unsigned short intensity;
00198 sscanf(fields[j + 305], "%hx", &intensity);
00199 msg.intensities[j - index_min] = intensity;
00200 }
00201 }
00202
00203
00204
00205
00206
00207
00208
00209
00210 msg.range_min = 0.05;
00211 msg.range_max = 4.0;
00212
00213
00214
00215 msg.header.stamp = start_time - ros::Duration().fromSec(271 * msg.time_increment);
00216
00217
00218 msg.header.stamp += ros::Duration().fromSec((double)index_min * msg.time_increment);
00219
00220
00221 msg.header.stamp += ros::Duration().fromSec(config.time_offset);
00222
00223 return EXIT_SUCCESS;
00224 }
00225
00226 }