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
00032 #include <csignal>
00033 #include <cstdio>
00034 #include <LMS1xx.h>
00035 #include "ros/ros.h"
00036 #include "sensor_msgs/LaserScan.h"
00037
00038 #define DEG2RAD M_PI/180.0
00039
00040 int main(int argc, char **argv)
00041 {
00042
00043 LMS1xx laser;
00044 scanCfg cfg;
00045 scanDataCfg dataCfg;
00046 scanData data;
00047
00048 sensor_msgs::LaserScan scan_msg;
00049
00050 std::string host;
00051 std::string frame_id;
00052
00053 ros::init(argc, argv, "lms1xx");
00054 ros::NodeHandle nh;
00055 ros::NodeHandle n("~");
00056 ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
00057
00058 n.param<std::string>("host", host, "192.168.1.2");
00059 n.param<std::string>("frame_id", frame_id, "laser");
00060
00061 ROS_INFO("connecting to laser at : %s", host.c_str());
00062
00063 laser.connect(host);
00064
00065 if (laser.isConnected())
00066 {
00067 ROS_INFO("Connected to laser.");
00068
00069 laser.login();
00070 cfg = laser.getScanCfg();
00071
00072 scan_msg.header.frame_id = frame_id;
00073
00074 scan_msg.range_min = 0.01;
00075 scan_msg.range_max = 40.0;
00076
00077 scan_msg.scan_time = 100.0/cfg.scaningFrequency;
00078
00079 scan_msg.angle_increment = (double)cfg.angleResolution/10000.0 * DEG2RAD;
00080 scan_msg.angle_min = (double)cfg.startAngle/10000.0 * DEG2RAD - M_PI/2;
00081 scan_msg.angle_max = (double)cfg.stopAngle/10000.0 * DEG2RAD - M_PI/2;
00082
00083 std::cout << "resolution : " << (double)cfg.angleResolution/10000.0 << " deg " << std::endl;
00084 std::cout << "frequency : " << (double)cfg.scaningFrequency/100.0 << " Hz " << std::endl;
00085
00086 int num_values;
00087 if (cfg.angleResolution == 2500)
00088 {
00089 num_values = 1081;
00090 }
00091 else if (cfg.angleResolution == 5000)
00092 {
00093 num_values = 541;
00094 }
00095 else
00096 {
00097 ROS_ERROR("Unsupported resolution");
00098 return 0;
00099 }
00100
00101 scan_msg.time_increment = scan_msg.scan_time/num_values;
00102
00103 scan_msg.ranges.resize(num_values);
00104 scan_msg.intensities.resize(num_values);
00105
00106 dataCfg.outputChannel = 1;
00107 dataCfg.remission = true;
00108 dataCfg.resolution = 1;
00109 dataCfg.encoder = 0;
00110 dataCfg.position = false;
00111 dataCfg.deviceName = false;
00112 dataCfg.outputInterval = 1;
00113
00114 laser.setScanDataCfg(dataCfg);
00115
00116 laser.startMeas();
00117
00118 status_t stat;
00119 do
00120 {
00121 stat = laser.queryStatus();
00122 ros::Duration(1.0).sleep();
00123 }
00124 while (stat != ready_for_measurement);
00125
00126 laser.scanContinous(1);
00127
00128 while (ros::ok())
00129 {
00130 ros::Time start = ros::Time::now();
00131
00132 scan_msg.header.stamp = start;
00133 ++scan_msg.header.seq;
00134
00135 laser.getData(data);
00136
00137 for (int i = 0; i < data.dist_len1; i++)
00138 {
00139 scan_msg.ranges[i] = data.dist1[i] * 0.001;
00140 }
00141
00142 for (int i = 0; i < data.rssi_len1; i++)
00143 {
00144 scan_msg.intensities[i] = data.rssi1[i];
00145 }
00146
00147 scan_pub.publish(scan_msg);
00148
00149 ros::spinOnce();
00150 }
00151
00152 laser.scanContinous(0);
00153 laser.stopMeas();
00154 laser.disconnect();
00155 }
00156 else
00157 {
00158 ROS_ERROR("Connection to device failed");
00159 }
00160 return 0;
00161 }