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 #include <csignal>
00025 #include <cstdio>
00026 #include <LMS1xx/LMS1xx.h>
00027 #include "ros/ros.h"
00028 #include "sensor_msgs/LaserScan.h"
00029
00030 #define DEG2RAD M_PI/180.0
00031
00032 int main(int argc, char **argv)
00033 {
00034
00035 LMS1xx laser;
00036 scanCfg cfg;
00037 scanOutputRange outputRange;
00038 scanDataCfg dataCfg;
00039 sensor_msgs::LaserScan scan_msg;
00040
00041
00042 std::string host;
00043 std::string frame_id;
00044 int port;
00045
00046 ros::init(argc, argv, "lms1xx");
00047 ros::NodeHandle nh;
00048 ros::NodeHandle n("~");
00049 ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
00050
00051 n.param<std::string>("host", host, "192.168.1.2");
00052 n.param<std::string>("frame_id", frame_id, "laser");
00053 n.param<int>("port", port, 2111);
00054
00055 while (ros::ok())
00056 {
00057 ROS_INFO_STREAM("Connecting to laser at " << host);
00058 laser.connect(host, port);
00059 if (!laser.isConnected())
00060 {
00061 ROS_WARN("Unable to connect, retrying.");
00062 ros::Duration(1).sleep();
00063 continue;
00064 }
00065
00066 ROS_DEBUG("Logging in to laser.");
00067 laser.login();
00068 cfg = laser.getScanCfg();
00069 outputRange = laser.getScanOutputRange();
00070
00071 if (cfg.scaningFrequency != 5000)
00072 {
00073 laser.disconnect();
00074 ROS_WARN("Unable to get laser output range. Retrying.");
00075 ros::Duration(1).sleep();
00076 continue;
00077 }
00078
00079 ROS_INFO("Connected to laser.");
00080
00081 ROS_DEBUG("Laser configuration: scaningFrequency %d, angleResolution %d, startAngle %d, stopAngle %d",
00082 cfg.scaningFrequency, cfg.angleResolution, cfg.startAngle, cfg.stopAngle);
00083 ROS_DEBUG("Laser output range:angleResolution %d, startAngle %d, stopAngle %d",
00084 outputRange.angleResolution, outputRange.startAngle, outputRange.stopAngle);
00085
00086 scan_msg.header.frame_id = frame_id;
00087 scan_msg.range_min = 0.01;
00088 scan_msg.range_max = 20.0;
00089 scan_msg.scan_time = 100.0 / cfg.scaningFrequency;
00090 scan_msg.angle_increment = (double)outputRange.angleResolution / 10000.0 * DEG2RAD;
00091 scan_msg.angle_min = (double)outputRange.startAngle / 10000.0 * DEG2RAD - M_PI / 2;
00092 scan_msg.angle_max = (double)outputRange.stopAngle / 10000.0 * DEG2RAD - M_PI / 2;
00093
00094 ROS_DEBUG_STREAM("Device resolution is " << (double)outputRange.angleResolution / 10000.0 << " degrees.");
00095 ROS_DEBUG_STREAM("Device frequency is " << (double)cfg.scaningFrequency / 100.0 << " Hz");
00096
00097 int angle_range = outputRange.stopAngle - outputRange.startAngle;
00098 int num_values = angle_range / outputRange.angleResolution ;
00099 if (angle_range % outputRange.angleResolution == 0)
00100 {
00101
00102 ++num_values;
00103 }
00104 scan_msg.ranges.resize(num_values);
00105 scan_msg.intensities.resize(num_values);
00106
00107 scan_msg.time_increment =
00108 (outputRange.angleResolution / 10000.0)
00109 / 360.0
00110 / (cfg.scaningFrequency / 100.0);
00111
00112 ROS_DEBUG_STREAM("Time increment is " << static_cast<int>(scan_msg.time_increment * 1000000) << " microseconds");
00113
00114 dataCfg.outputChannel = 1;
00115 dataCfg.remission = true;
00116 dataCfg.resolution = 1;
00117 dataCfg.encoder = 0;
00118 dataCfg.position = false;
00119 dataCfg.deviceName = false;
00120 dataCfg.outputInterval = 1;
00121
00122 ROS_DEBUG("Setting scan data configuration.");
00123 laser.setScanDataCfg(dataCfg);
00124
00125 ROS_DEBUG("Starting measurements.");
00126 laser.startMeas();
00127
00128 ROS_DEBUG("Waiting for ready status.");
00129 ros::Time ready_status_timeout = ros::Time::now() + ros::Duration(5);
00130
00131
00132
00133 status_t stat = laser.queryStatus();
00134 ros::Duration(1.0).sleep();
00135 if (stat != ready_for_measurement)
00136 {
00137 ROS_WARN("Laser not ready. Retrying initialization.");
00138 laser.disconnect();
00139 ros::Duration(1).sleep();
00140 continue;
00141 }
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162 ROS_DEBUG("Starting device.");
00163 laser.startDevice();
00164
00165 ROS_DEBUG("Commanding continuous measurements.");
00166 laser.scanContinous(1);
00167
00168 while (ros::ok())
00169 {
00170 ros::Time start = ros::Time::now();
00171
00172 scan_msg.header.stamp = start;
00173 ++scan_msg.header.seq;
00174
00175 scanData data;
00176 ROS_DEBUG("Reading scan data.");
00177 if (laser.getScanData(&data))
00178 {
00179 for (int i = 0; i < data.dist_len1; i++)
00180 {
00181 scan_msg.ranges[i] = data.dist1[i] * 0.001;
00182 }
00183
00184 for (int i = 0; i < data.rssi_len1; i++)
00185 {
00186 scan_msg.intensities[i] = data.rssi1[i];
00187 }
00188
00189 ROS_DEBUG("Publishing scan data.");
00190 scan_pub.publish(scan_msg);
00191 }
00192 else
00193 {
00194 ROS_ERROR("Laser timed out on delivering scan, attempting to reinitialize.");
00195 break;
00196 }
00197
00198 ros::spinOnce();
00199 }
00200
00201 laser.scanContinous(0);
00202 laser.stopMeas();
00203 laser.disconnect();
00204 }
00205
00206 return 0;
00207 }