sick_tim551_2050001_parser.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2013, Osnabrück University
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Osnabrück University nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *  Created on: 14.11.2013
00030  *
00031  *      Author: Martin Günther <mguenthe@uos.de>
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   // Reserve sufficient space
00062   std::vector<char *> fields;
00063   fields.reserve(datagram_length / 2);
00064 
00065   // ----- only for debug output
00066   char datagram_copy[datagram_length + 1];
00067   strncpy(datagram_copy, datagram, datagram_length); // datagram will be changed by strtok
00068   datagram_copy[datagram_length] = 0;
00069 
00070   // ----- tokenize
00071   count = 0;
00072   cur_field = strtok(datagram, " ");
00073   fields.push_back(cur_field);
00074 
00075   while (cur_field != NULL)
00076   {
00077     cur_field = strtok(NULL, " ");
00078     fields.push_back(cur_field);
00079   }
00080 
00081   count = fields.size();
00082 
00083   // Validate header. Total number of tokens is highly unreliable as this may
00084   // change when you change the scanning range or the device name using SOPAS ET
00085   // tool. The header remains stable, however.
00086   if (count < HEADER_FIELDS)
00087   {
00088     ROS_WARN(
00089         "received less fields than minimum fields (actual: %zu, minimum: %zu), ignoring scan", count, HEADER_FIELDS);
00090     ROS_WARN("are you using the correct node? (124 --> sick_tim310_1130000m01, > 33 --> sick_tim551_2050001, 580 --> sick_tim310s01, 592 --> sick_tim310)");
00091     // ROS_DEBUG("received message was: %s", datagram_copy);
00092     return EXIT_FAILURE;
00093   }
00094   if (strcmp(fields[15], "0"))
00095   {
00096     ROS_WARN("Field 15 of received data is not equal to 0 (%s). Unexpected data, ignoring scan", fields[15]);
00097     return EXIT_FAILURE;
00098   }
00099   if (strcmp(fields[20], "DIST1"))
00100   {
00101     ROS_WARN("Field 20 of received data is not equal to DIST1i (%s). Unexpected data, ignoring scan", fields[20]);
00102     return EXIT_FAILURE;
00103   }
00104 
00105   // More in depth checks: check data length and RSSI availability
00106   // 25: Number of data (<= 10F)
00107   unsigned short int number_of_data = 0;
00108   sscanf(fields[25], "%hx", &number_of_data);
00109 
00110   if (number_of_data < 1 || number_of_data > 811)
00111   {
00112     ROS_WARN("Data length is outside acceptable range 1-811 (%d). Ignoring scan", number_of_data);
00113     return EXIT_FAILURE;
00114   }
00115   if (count < HEADER_FIELDS + number_of_data)
00116   {
00117     ROS_WARN("Less fields than expected for %d data points (%zu). Ignoring scan", number_of_data, count);
00118     return EXIT_FAILURE;
00119   }
00120   ROS_DEBUG("Number of data: %d", number_of_data);
00121 
00122   // Calculate offset of field that contains indicator of whether or not RSSI data is included
00123   size_t rssi_idx = 26 + number_of_data;
00124   int tmp;
00125   sscanf(fields[rssi_idx], "%d", &tmp);
00126   bool rssi = tmp > 0;
00127   unsigned short int number_of_rssi_data = 0;
00128   if (rssi)
00129   {
00130     sscanf(fields[rssi_idx + 6], "%hx", &number_of_rssi_data);
00131 
00132     // Number of RSSI data should be equal to number of data
00133     if (number_of_rssi_data != number_of_data)
00134     {
00135       ROS_WARN("Number of RSSI data is lower than number of range data (%d vs %d", number_of_data, number_of_rssi_data);
00136       return EXIT_FAILURE;
00137     }
00138 
00139     // Check if the total length is still appropriate.
00140     // RSSI data size = number of RSSI readings + 6 fields describing the data
00141     if (count < HEADER_FIELDS + number_of_data + number_of_rssi_data + 6)
00142     {
00143       ROS_WARN("Less fields than expected for %d data points (%zu). Ignoring scan", number_of_data, count);
00144       return EXIT_FAILURE;
00145     }
00146 
00147     if (strcmp(fields[rssi_idx + 1], "RSSI1"))
00148     {
00149       ROS_WARN("Field %zu of received data is not equal to RSSI1 (%s). Unexpected data, ignoring scan", rssi_idx + 1, fields[rssi_idx + 1]);
00150     }
00151   }
00152 
00153   // ----- read fields into msg
00154   msg.header.frame_id = config.frame_id;
00155   ROS_DEBUG("publishing with frame_id %s", config.frame_id.c_str());
00156 
00157   ros::Time start_time = ros::Time::now(); // will be adjusted in the end
00158 
00159   // <STX> (\x02)
00160   // 0: Type of command (SN)
00161   // 1: Command (LMDscandata)
00162   // 2: Firmware version number (1)
00163   // 3: Device number (1)
00164   // 4: Serial number (eg. B96518)
00165   // 5 + 6: Device Status (0 0 = ok, 0 1 = error)
00166   // 7: Telegram counter (eg. 99)
00167   // 8: Scan counter (eg. 9A)
00168   // 9: Time since startup (eg. 13C8E59)
00169   // 10: Time of transmission (eg. 13C9CBE)
00170   // 11 + 12: Input status (0 0)
00171   // 13 + 14: Output status (8 0)
00172   // 15: Reserved Byte A (0)
00173 
00174   // 16: Scanning Frequency (5DC)
00175   unsigned short scanning_freq = -1;
00176   sscanf(fields[16], "%hx", &scanning_freq);
00177   msg.scan_time = 1.0 / (scanning_freq / 100.0);
00178   // ROS_DEBUG("hex: %s, scanning_freq: %d, scan_time: %f", fields[16], scanning_freq, msg.scan_time);
00179 
00180   // 17: Measurement Frequency (36)
00181   unsigned short measurement_freq = -1;
00182   sscanf(fields[17], "%hx", &measurement_freq);
00183   msg.time_increment = 1.0 / (measurement_freq * 100.0);
00184   if (override_time_increment_ > 0.0)
00185   {
00186     // Some lasers may report incorrect measurement frequency
00187     msg.time_increment = override_time_increment_;
00188   }
00189   // ROS_DEBUG("measurement_freq: %d, time_increment: %f", measurement_freq, msg.time_increment);
00190 
00191   // 18: Number of encoders (0)
00192   // 19: Number of 16 bit channels (1)
00193   // 20: Measured data contents (DIST1)
00194 
00195   // 21: Scaling factor (3F800000)
00196   // ignored for now (is always 1.0):
00197 //      unsigned int scaling_factor_int = -1;
00198 //      sscanf(fields[21], "%x", &scaling_factor_int);
00199 //
00200 //      float scaling_factor = reinterpret_cast<float&>(scaling_factor_int);
00201 //      // ROS_DEBUG("hex: %s, scaling_factor_int: %d, scaling_factor: %f", fields[21], scaling_factor_int, scaling_factor);
00202 
00203   // 22: Scaling offset (00000000) -- always 0
00204   // 23: Starting angle (FFF92230)
00205   int starting_angle = -1;
00206   sscanf(fields[23], "%x", &starting_angle);
00207   msg.angle_min = (starting_angle / 10000.0) / 180.0 * M_PI - M_PI / 2;
00208   // ROS_DEBUG("starting_angle: %d, angle_min: %f", starting_angle, msg.angle_min);
00209 
00210   // 24: Angular step width (2710)
00211   unsigned short angular_step_width = -1;
00212   sscanf(fields[24], "%hx", &angular_step_width);
00213   msg.angle_increment = (angular_step_width / 10000.0) / 180.0 * M_PI;
00214   msg.angle_max = msg.angle_min + (number_of_data - 1) * msg.angle_increment;
00215 
00216   // 25: Number of data (<= 10F)
00217   // This is already determined above in number_of_data
00218 
00219   // adjust angle_min to min_ang config param
00220   int index_min = 0;
00221   while (msg.angle_min + msg.angle_increment < config.min_ang)
00222   {
00223     msg.angle_min += msg.angle_increment;
00224     index_min++;
00225   }
00226 
00227   // adjust angle_max to max_ang config param
00228   int index_max = number_of_data - 1;
00229   while (msg.angle_max - msg.angle_increment > config.max_ang)
00230   {
00231     msg.angle_max -= msg.angle_increment;
00232     index_max--;
00233   }
00234 
00235   ROS_DEBUG("index_min: %d, index_max: %d", index_min, index_max);
00236   // ROS_DEBUG("angular_step_width: %d, angle_increment: %f, angle_max: %f", angular_step_width, msg.angle_increment, msg.angle_max);
00237 
00238   // 26..26 + n - 1: Data_1 .. Data_n
00239   msg.ranges.resize(index_max - index_min + 1);
00240   for (int j = index_min; j <= index_max; ++j)
00241   {
00242     unsigned short range;
00243     sscanf(fields[j + 26], "%hx", &range);
00244     msg.ranges[j - index_min] = range / 1000.0;
00245   }
00246 
00247   if (rssi)
00248   {
00249     // 26 + n: RSSI data included
00250 
00251     //   26 + n + 1 = RSSI Measured Data Contents (RSSI1)
00252     //   26 + n + 2 = RSSI scaling factor (3F80000)
00253     //   26 + n + 3 = RSSI Scaling offset (0000000)
00254     //   26 + n + 4 = RSSI starting angle (equal to Range starting angle)
00255     //   26 + n + 5 = RSSI angular step width (equal to Range angular step width)
00256     //   26 + n + 6 = RSSI number of data (equal to Range number of data)
00257     //   26 + n + 7 .. 26 + n + 7 + n - 1: RSSI_Data_1 .. RSSI_Data_n
00258     //   26 + n + 7 + n .. 26 + n + 7 + n + 2 = unknown (but seems to be [0, 1, B] always)
00259     //   26 + n + 7 + n + 2 .. count - 4 = device label
00260     //   count - 3 .. count - 1 = unknown (but seems to be 0 always)
00261     //   <ETX> (\x03)
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   }
00271 
00272   // 26 + n: RSSI data included
00273   // IF RSSI not included:
00274   //   26 + n + 1 .. 26 + n + 3 = unknown (but seems to be [0, 1, B] always)
00275   //   26 + n + 4 .. count - 4 = device label
00276   //   count - 3 .. count - 1 = unknown (but seems to be 0 always)
00277   //   <ETX> (\x03)
00278 
00279   msg.range_min = override_range_min_;
00280   msg.range_max = override_range_max_;
00281 
00282   // ----- adjust start time
00283   // - last scan point = now  ==>  first scan point = now - number_of_data * time increment
00284   msg.header.stamp = start_time - ros::Duration().fromSec(number_of_data * msg.time_increment);
00285 
00286   // - shift forward to time of first published scan point
00287   msg.header.stamp += ros::Duration().fromSec((double)index_min * msg.time_increment);
00288 
00289   // - add time offset (to account for USB latency etc.)
00290   msg.header.stamp += ros::Duration().fromSec(config.time_offset);
00291 
00292   // ----- consistency check
00293  float expected_time_increment = msg.scan_time * msg.angle_increment / (2.0 * M_PI);
00294  if (fabs(expected_time_increment - msg.time_increment) > 0.00001)
00295  {
00296    ROS_WARN_THROTTLE(60, "The time_increment, scan_time and angle_increment values reported by the scanner are inconsistent! "
00297        "Expected time_increment: %.9f, reported time_increment: %.9f. "
00298        "Perhaps you should set the parameter time_increment to the expected value. This message will print every 60 seconds.",
00299        expected_time_increment, msg.time_increment);
00300  }
00301 
00302   return EXIT_SUCCESS;
00303 }
00304 
00305 void SickTim5512050001Parser::set_range_min(float min)
00306 {
00307   override_range_min_ = min;
00308 }
00309 
00310 void SickTim5512050001Parser::set_range_max(float max)
00311 {
00312   override_range_max_ = max;
00313 }
00314 
00315 void SickTim5512050001Parser::set_time_increment(float time)
00316 {
00317   override_time_increment_ = time;
00318 }
00319 
00320 } /* namespace sick_tim */


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther
autogenerated on Thu Aug 27 2015 15:14:34