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 #include <csignal>
00033 #include <cstdio>
00034 #include <math.h>
00035 #include <limits>
00036 #include <sicklms-1.0/SickLMS.hh>
00037 #include "ros/ros.h"
00038 #include "sensor_msgs/LaserScan.h"
00039 #include <diagnostic_updater/diagnostic_updater.h>
00040 #include <diagnostic_updater/publisher.h>
00041 using namespace SickToolbox;
00042 using namespace std;
00043
00044
00045 bool use_rep_117_;
00046
00047 void publish_scan(diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan> *pub, uint32_t *range_values,
00048 uint32_t n_range_values, uint32_t *intensity_values,
00049 uint32_t n_intensity_values, double scale, ros::Time start,
00050 double scan_time, bool inverted, float angle_min,
00051 float angle_max, std::string frame_id)
00052 {
00053 static int scan_count = 0;
00054 sensor_msgs::LaserScan scan_msg;
00055 scan_msg.header.frame_id = frame_id;
00056 scan_count++;
00057 if (inverted) {
00058 scan_msg.angle_min = angle_max;
00059 scan_msg.angle_max = angle_min;
00060 } else {
00061 scan_msg.angle_min = angle_min;
00062 scan_msg.angle_max = angle_max;
00063 }
00064 scan_msg.angle_increment = (scan_msg.angle_max - scan_msg.angle_min) / (double)(n_range_values-1);
00065 scan_msg.scan_time = scan_time;
00066 scan_msg.time_increment = scan_time / (2*M_PI) * scan_msg.angle_increment;
00067 scan_msg.range_min = 0;
00068 if (scale == 0.01) {
00069 scan_msg.range_max = 81;
00070 }
00071 else if (scale == 0.001) {
00072 scan_msg.range_max = 8.1;
00073 }
00074 scan_msg.ranges.resize(n_range_values);
00075 scan_msg.header.stamp = start;
00076 if(use_rep_117_){
00077 for (size_t i = 0; i < n_range_values; i++) {
00078
00079 switch (range_values[i])
00080 {
00081
00082 case 8191:
00083 scan_msg.ranges[i] = numeric_limits<float>::quiet_NaN();
00084 break;
00085 case 8190:
00086 scan_msg.ranges[i] = numeric_limits<float>::quiet_NaN();
00087 break;
00088 case 8189:
00089 scan_msg.ranges[i] = numeric_limits<float>::quiet_NaN();
00090 break;
00091 case 8187:
00092 scan_msg.ranges[i] = numeric_limits<float>::quiet_NaN();
00093 break;
00094 case 8186:
00095 scan_msg.ranges[i] = numeric_limits<float>::quiet_NaN();
00096 break;
00097 case 8183:
00098 scan_msg.ranges[i] = numeric_limits<float>::infinity();
00099 break;
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139 default:
00140 scan_msg.ranges[i] = (float)range_values[i] * (float)scale;
00141 }
00142 }
00143 } else {
00144 for (size_t i = 0; i < n_range_values; i++) {
00145 scan_msg.ranges[i] = (float)range_values[i] * (float)scale;
00146 }
00147 }
00148 scan_msg.intensities.resize(n_intensity_values);
00149 for (size_t i = 0; i < n_intensity_values; i++) {
00150 scan_msg.intensities[i] = (float)intensity_values[i];
00151 }
00152
00153
00154 pub->publish(scan_msg);
00155 }
00156
00157 SickLMS::sick_lms_measuring_units_t StringToLmsMeasuringUnits(string units)
00158 {
00159 if (units.compare("mm") == 0)
00160 return SickLMS::SICK_MEASURING_UNITS_MM;
00161 else if (units.compare("cm") == 0)
00162 return SickLMS::SICK_MEASURING_UNITS_CM;
00163
00164 return SickLMS::SICK_MEASURING_UNITS_UNKNOWN;
00165 }
00166
00167
00168 int main(int argc, char **argv)
00169 {
00170 ros::init(argc, argv, "sicklms");
00171 ros::NodeHandle nh;
00172 ros::NodeHandle nh_ns("~");
00173 string port;
00174 int baud;
00175 int delay;
00176 bool inverted;
00177 int angle;
00178 double resolution;
00179 std::string measuring_units;
00180 std::string frame_id;
00181 double scan_time = 0;
00182 double angle_increment = 0;
00183 float angle_min = 0.0;
00184 float angle_max = 0.0;
00185
00186
00187 double desired_freq;
00188 nh_ns.param<double>("desired_frequency", desired_freq, 75.0);
00189 double min_freq;
00190 nh_ns.param<double>("min_frequency", min_freq, desired_freq);
00191 double max_freq;
00192 nh_ns.param<double>("max_frequency", max_freq, desired_freq);
00193 double freq_tolerance;
00194 nh_ns.param<double>("frequency_tolerance", freq_tolerance, 0.3);
00195 int window_size;
00196 nh_ns.param<int>("window_size", window_size, 30);
00197 double min_delay;
00198 nh_ns.param<double>("min_acceptable_delay", min_delay, 0.0);
00199 double max_delay;
00200 nh_ns.param<double>("max_acceptable_delay", max_delay, 0.2);
00201 std::string hardware_id;
00202 nh_ns.param<std::string>("hardware_id", hardware_id, "SICK LMS");
00203
00204
00205 diagnostic_updater::Updater updater;
00206 updater.setHardwareID(hardware_id);
00207 diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan> scan_pub(nh.advertise<sensor_msgs::LaserScan>("scan", 10), updater,
00208 diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq, freq_tolerance, window_size),
00209 diagnostic_updater::TimeStampStatusParam(min_delay, max_delay));
00210
00211 nh_ns.param("port", port, string("/dev/lms200"));
00212 nh_ns.param("baud", baud, 38400);
00213 nh_ns.param("connect_delay", delay, 0);
00214 nh_ns.param("inverted", inverted, false);
00215 nh_ns.param("angle", angle, 0);
00216 nh_ns.param("resolution", resolution, 0.0);
00217 nh_ns.param("units", measuring_units, string());
00218 nh_ns.param<std::string>("frame_id", frame_id, "laser");
00219
00220
00221 std::string key;
00222 if (nh.searchParam("use_rep_117", key))
00223 {
00224 nh.getParam(key, use_rep_117_);
00225 } else {
00226 ROS_WARN("The use_rep_117 parameter has not been specified and has been automatically set to true. This parameter will be removed in Hydromedusa. Please see: http://ros.org/wiki/rep_117/migration");
00227 use_rep_117_ = true;
00228 }
00229
00230 if(!use_rep_117_){
00231 ROS_WARN("The use_rep_117 parameter is set to false. This parameter will be removed in Hydromedusa. Please see: http://ros.org/wiki/rep_117/migration");
00232 }
00233
00234 SickLMS::sick_lms_baud_t desired_baud = SickLMS::IntToSickBaud(baud);
00235 if (desired_baud == SickLMS::SICK_BAUD_UNKNOWN)
00236 {
00237 ROS_ERROR("Baud rate must be in {9600, 19200, 38400, 500000}");
00238 return 1;
00239 }
00240 uint32_t range_values[SickLMS::SICK_MAX_NUM_MEASUREMENTS] = {0};
00241 uint32_t intensity_values[SickLMS::SICK_MAX_NUM_MEASUREMENTS] = {0};
00242 uint32_t n_range_values = 0;
00243 uint32_t n_intensity_values = 0;
00244 SickLMS sick_lms(port);
00245 double scale = 0;
00246 double angle_offset;
00247 uint32_t partial_scan_index;
00248
00249 try
00250 {
00251 uint32_t on_delay = 0;
00252 if(delay > 0){
00253 on_delay = delay;
00254 }
00255 sick_lms.Initialize(desired_baud, on_delay);
00256
00257
00258
00259 int actual_angle = sick_lms.GetSickScanAngle();
00260 double actual_resolution = sick_lms.GetSickScanResolution();
00261 SickLMS::sick_lms_measuring_units_t actual_units = sick_lms.GetSickMeasuringUnits();
00262
00263
00264 try {
00265 if ((angle && actual_angle != angle) || (resolution && actual_resolution != resolution)) {
00266 ROS_INFO("Setting variant to (%i, %f)", angle, resolution);
00267 sick_lms.SetSickVariant(sick_lms.IntToSickScanAngle(angle),
00268 sick_lms.DoubleToSickScanResolution(resolution));
00269 } else {
00270 ROS_INFO("Variant setup not requested or identical to actual (%i, %f)", actual_angle,
00271 actual_resolution);
00272 angle = actual_angle;
00273 resolution = actual_resolution;
00274 }
00275 } catch (SickConfigException e) {
00276 actual_angle = sick_lms.GetSickScanAngle();
00277 actual_resolution = sick_lms.GetSickScanResolution();
00278 if (angle != actual_angle) {
00279 ROS_WARN("Unable to set scan angle. Using %i instead of %i.", actual_angle, angle);
00280 angle = actual_angle;
00281 }
00282 if (resolution != actual_resolution) {
00283 ROS_WARN("Unable to set resolution. Using %e instead of %e.", actual_resolution, resolution);
00284 resolution = actual_resolution;
00285 }
00286 }
00287
00288
00289 try {
00290 if (!measuring_units.empty() && (actual_units != StringToLmsMeasuringUnits(measuring_units))) {
00291 ROS_INFO("Setting measuring units to '%s'", measuring_units.c_str());
00292 actual_units = StringToLmsMeasuringUnits(measuring_units);
00293 sick_lms.SetSickMeasuringUnits(actual_units);
00294 } else {
00295 ROS_INFO("Measuring units setup not requested or identical to actual ('%s')",
00296 sick_lms.SickMeasuringUnitsToString(actual_units).c_str());
00297 }
00298 } catch (SickConfigException e) {
00299 actual_units = sick_lms.GetSickMeasuringUnits();
00300 if (StringToLmsMeasuringUnits(measuring_units) != actual_units) {
00301 ROS_WARN("Unable to set measuring units. Using '%s' instead of '%s'.",
00302 sick_lms.SickMeasuringUnitsToString(actual_units).c_str(), measuring_units.c_str());
00303 measuring_units = sick_lms.SickMeasuringUnitsToString(actual_units);
00304 }
00305 }
00306
00307 if (actual_units == SickLMS::SICK_MEASURING_UNITS_CM)
00308 scale = 0.01;
00309 else if (actual_units == SickLMS::SICK_MEASURING_UNITS_MM)
00310 scale = 0.001;
00311 else
00312 {
00313 ROS_ERROR("Invalid measuring unit.");
00314 return 1;
00315 }
00316
00317
00318
00319
00320
00321 if (angle == 180 || sick_lms.IsSickLMSFast()) {
00322 scan_time = 1.0 / 75;
00323 }
00324 else {
00325 SickLMS::sick_lms_scan_resolution_t scan_resolution =
00326 SickLMS::DoubleToSickScanResolution(resolution);
00327 if ( scan_resolution == SickLMS::SICK_SCAN_RESOLUTION_25) {
00328
00329 scan_time = 4.0 / 75;
00330 }
00331 else if ( scan_resolution == SickLMS::SICK_SCAN_RESOLUTION_50) {
00332
00333 scan_time = 2.0 / 75;
00334 }
00335 else if ( scan_resolution == SickLMS::SICK_SCAN_RESOLUTION_100) {
00336
00337 scan_time = 1.0 / 75;
00338 }
00339 else {
00340 ROS_ERROR("Bogus scan resolution.");
00341 return 1;
00342 }
00343 if ( scan_resolution != SickLMS::SICK_SCAN_RESOLUTION_100) {
00344 ROS_WARN("You are using an angle smaller than 180 degrees and a "
00345 "scan resolution less than 1 degree per scan. Thus, "
00346 "you are in inteleaved mode and the returns will not "
00347 "arrive sequentially how you read them. So, the "
00348 "time_increment field will be misleading. If you need to "
00349 "know when the measurement was made at a time resolution "
00350 "better than the scan_time, use the whole 180 degree "
00351 "field of view.");
00352 }
00353 }
00354
00355
00356
00357
00358
00359 angle_increment = sick_lms.IsSickLMSFast() ? 0.5 : 1.0;
00360
00361 angle_offset = (180.0-angle)/2;
00362 }
00363 catch (...)
00364 {
00365 ROS_ERROR("Initialize failed! are you using the correct device path?");
00366 return 2;
00367 }
00368 try
00369 {
00370 while (ros::ok())
00371 {
00372 if (sick_lms.IsSickLMSFast()) {
00373
00374
00375 sick_lms.GetSickScan(range_values, intensity_values,
00376 n_range_values, n_intensity_values);
00377 angle_min = -M_PI/4;
00378 angle_max = M_PI/4;
00379 }
00380 else if (angle != 180) {
00381
00382
00383
00384 sick_lms.GetSickScan(range_values, n_range_values);
00385 angle_min = (-90.0 + angle_offset) * M_PI / 180.0;
00386 angle_max = (90.0 - angle_offset) * M_PI / 180.0;
00387 }
00388 else {
00389
00390
00391
00392
00393 sick_lms.GetSickPartialScan(range_values, n_range_values,
00394 partial_scan_index);
00395 double partialScanOffset = 0.25 * partial_scan_index;
00396 angle_min = (-90.0 + angle_offset + partialScanOffset) * M_PI / 180.0;
00397 angle_max = (90.0 - angle_offset - fmod(1.0 - partialScanOffset, 1.0))
00398 * M_PI / 180.0;
00399 }
00400
00401
00402
00403
00404 ros::Time end_of_scan = ros::Time::now();
00405 ros::Time start = end_of_scan - ros::Duration(scan_time / 2.0);
00406
00407 publish_scan(&scan_pub, range_values, n_range_values, intensity_values,
00408 n_intensity_values, scale, start, scan_time, inverted,
00409 angle_min, angle_max, frame_id);
00410 ros::spinOnce();
00411
00412 updater.update();
00413 }
00414 }
00415 catch (...)
00416 {
00417 ROS_ERROR("Unknown error.");
00418 return 1;
00419 }
00420 try
00421 {
00422 sick_lms.Uninitialize();
00423 }
00424 catch (...)
00425 {
00426 ROS_ERROR("Error during uninitialize");
00427 return 1;
00428 }
00429 ROS_INFO("Success.\n");
00430
00431 return 0;
00432 }
00433