Go to the documentation of this file.00001 #include <csignal>
00002 #include <cstdio>
00003 #include <LMS1xx/LMS1xx.h>
00004 #include "ros/ros.h"
00005 #include "sensor_msgs/LaserScan.h"
00006
00007 #define DEG2RAD M_PI/180.0
00008
00009 int main(int argc, char **argv)
00010 {
00011
00012 LMS1xx laser;
00013 scanCfg cfg;
00014 scanOutputRange outputRange;
00015 scanDataCfg dataCfg;
00016 scanData data;
00017 memset(&data, 0, sizeof(data));
00018
00019 sensor_msgs::LaserScan scan_msg;
00020
00021
00022 std::string host;
00023 std::string frame_id;
00024
00025 ros::init(argc, argv, "lms1xx");
00026 ros::NodeHandle nh;
00027 ros::NodeHandle n("~");
00028 ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
00029
00030 n.param<std::string>("host", host, "192.168.1.2");
00031 n.param<std::string>("frame_id", frame_id, "laser");
00032
00033 while(ros::ok())
00034 {
00035 ROS_INFO("Connecting to laser at : %s", host.c_str());
00036
00037
00038 do {
00039 laser.connect(host);
00040
00041 if (laser.isConnected())
00042 {
00043 laser.login();
00044 cfg = laser.getScanCfg();
00045 outputRange = laser.getScanOutputRange();
00046 }
00047
00048
00049
00050 if (cfg.scaningFrequency != 5000) {
00051 laser.disconnect();
00052 ROS_INFO("Waiting for laser to initialize...");
00053 }
00054
00055 } while (!laser.isConnected() || cfg.scaningFrequency != 5000);
00056
00057 if (laser.isConnected()) {
00058 ROS_INFO("Connected to laser.");
00059
00060 ROS_DEBUG("Laser configuration: scaningFrequency %d, angleResolution %d, startAngle %d, stopAngle %d",
00061 cfg.scaningFrequency, cfg.angleResolution, cfg.startAngle, cfg.stopAngle);
00062 ROS_DEBUG("Laser output range:angleResolution %d, startAngle %d, stopAngle %d",
00063 outputRange.angleResolution, outputRange.startAngle, outputRange.stopAngle);
00064
00065 scan_msg.header.frame_id = frame_id;
00066
00067 scan_msg.range_min = 0.01;
00068 scan_msg.range_max = 20.0;
00069
00070 scan_msg.scan_time = 100.0/cfg.scaningFrequency;
00071
00072 scan_msg.angle_increment = (double)outputRange.angleResolution/10000.0 * DEG2RAD;
00073 scan_msg.angle_min = (double)outputRange.startAngle/10000.0 * DEG2RAD - M_PI/2;
00074 scan_msg.angle_max = (double)outputRange.stopAngle/10000.0 * DEG2RAD - M_PI/2;
00075
00076 ROS_DEBUG_STREAM("resolution : " << (double)outputRange.angleResolution/10000.0 << " deg");
00077 ROS_DEBUG_STREAM("frequency : " << (double)cfg.scaningFrequency/100.0 << " Hz");
00078
00079 int angle_range = outputRange.stopAngle - outputRange.startAngle;
00080 int num_values = angle_range / outputRange.angleResolution ;
00081 if (angle_range % outputRange.angleResolution == 0) {
00082
00083 ++num_values;
00084 }
00085
00086 scan_msg.time_increment =
00087 (outputRange.angleResolution / 10000.0)
00088 / 360.0
00089 / (cfg.scaningFrequency / 100.0);
00090
00091 ROS_DEBUG_STREAM("time increment : " << (double)scan_msg.time_increment << " seconds");
00092
00093 scan_msg.ranges.resize(num_values);
00094 scan_msg.intensities.resize(num_values);
00095
00096 dataCfg.outputChannel = 1;
00097 dataCfg.remission = true;
00098 dataCfg.resolution = 1;
00099 dataCfg.encoder = 0;
00100 dataCfg.position = false;
00101 dataCfg.deviceName = false;
00102 dataCfg.outputInterval = 1;
00103
00104 laser.setScanDataCfg(dataCfg);
00105
00106 laser.startMeas();
00107
00108 status_t stat;
00109 do
00110 {
00111 stat = laser.queryStatus();
00112 ros::Duration(1.0).sleep();
00113 }
00114 while (stat != ready_for_measurement);
00115
00116 laser.startDevice();
00117
00118 laser.scanContinous(1);
00119
00120 while (ros::ok())
00121 {
00122 ros::Time start = ros::Time::now();
00123
00124 scan_msg.header.stamp = start;
00125 ++scan_msg.header.seq;
00126
00127 laser.getData(data);
00128
00129 for (int i = 0; i < data.dist_len1; i++)
00130 {
00131 scan_msg.ranges[i] = data.dist1[i] * 0.001;
00132 }
00133
00134 for (int i = 0; i < data.rssi_len1; i++)
00135 {
00136 scan_msg.intensities[i] = data.rssi1[i];
00137 }
00138
00139 scan_pub.publish(scan_msg);
00140
00141 ros::spinOnce();
00142 }
00143
00144 laser.scanContinous(0);
00145 laser.stopMeas();
00146 laser.disconnect();
00147 }
00148 else
00149 {
00150 ROS_ERROR("Connection to LMS1xx device failed, retrying in 1 second.");
00151 ros::Duration(1.0).sleep();
00152 }
00153 }
00154
00155 return 0;
00156 }