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