lms1xx_node.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <csignal>
33 #include <cstdio>
34 #include <lms1xx/lms1xx.h>
35 #include "ros/ros.h"
36 #include "sensor_msgs/LaserScan.h"
37 
38 #define DEG2RAD M_PI/180.0
39 
40 int main(int argc, char **argv)
41 {
42  // laser data
43  LMS1xx laser;
44  scanCfg cfg;
45  scanDataCfg dataCfg;
46  scanData data;
47  // published data
48  sensor_msgs::LaserScan scan_msg;
49  // parameters
50  std::string host;
51  std::string frame_id;
52 
53  ros::init(argc, argv, "lms1xx");
54  ros::NodeHandle nh;
55  ros::NodeHandle n("~");
56  ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
57 
58  n.param<std::string>("host", host, "192.168.1.2");
59  n.param<std::string>("frame_id", frame_id, "laser");
60 
61  ROS_INFO("connecting to laser at : %s", host.c_str());
62  // initialize hardware
63  laser.connect(host);
64 
65  if (laser.isConnected())
66  {
67  ROS_INFO("Connected to laser.");
68 
69  laser.login();
70  cfg = laser.getScanCfg();
71 
72  scan_msg.header.frame_id = frame_id;
73 
74  scan_msg.range_min = 0.01;
75  scan_msg.range_max = 40.0;
76 
77  scan_msg.scan_time = 100.0/cfg.scaningFrequency;
78 
79  scan_msg.angle_increment = (double)cfg.angleResolution/10000.0 * DEG2RAD;
80  scan_msg.angle_min = (double)cfg.startAngle/10000.0 * DEG2RAD - M_PI/2;
81  scan_msg.angle_max = (double)cfg.stopAngle/10000.0 * DEG2RAD - M_PI/2;
82 
83  std::cout << "resolution : " << (double)cfg.angleResolution/10000.0 << " deg " << std::endl;
84  std::cout << "frequency : " << (double)cfg.scaningFrequency/100.0 << " Hz " << std::endl;
85 
86  int num_values;
87  if (cfg.angleResolution == 2500)
88  {
89  num_values = 1081;
90  }
91  else if (cfg.angleResolution == 5000)
92  {
93  num_values = 541;
94  }
95  else
96  {
97  ROS_ERROR("Unsupported resolution");
98  return 0;
99  }
100 
101  scan_msg.time_increment = scan_msg.scan_time/num_values;
102 
103  scan_msg.ranges.resize(num_values);
104  scan_msg.intensities.resize(num_values);
105 
106  dataCfg.outputChannel = 1;
107  dataCfg.remission = true;
108  dataCfg.resolution = 1;
109  dataCfg.encoder = 0;
110  dataCfg.position = false;
111  dataCfg.deviceName = false;
112  dataCfg.outputInterval = 1;
113 
114  laser.setScanDataCfg(dataCfg);
115 
116  laser.startMeas();
117 
118  status_t stat;
119  do // wait for ready status
120  {
121  stat = laser.queryStatus();
122  ros::Duration(1.0).sleep();
123  }
124  while (stat != ready_for_measurement);
125 
126  laser.scanContinous(1);
127 
128  while (ros::ok())
129  {
130  ros::Time start = ros::Time::now();
131 
132  scan_msg.header.stamp = start;
133  ++scan_msg.header.seq;
134 
135  laser.getData(data);
136 
137  for (int i = 0; i < data.dist_len1; i++)
138  {
139  scan_msg.ranges[i] = data.dist1[i] * 0.001;
140  }
141 
142  for (int i = 0; i < data.rssi_len1; i++)
143  {
144  scan_msg.intensities[i] = data.rssi1[i];
145  }
146 
147  scan_pub.publish(scan_msg);
148 
149  ros::spinOnce();
150  }
151 
152  laser.scanContinous(0);
153  laser.stopMeas();
154  laser.disconnect();
155  }
156  else
157  {
158  ROS_ERROR("Connection to device failed");
159  }
160  return 0;
161 }
status_t
Definition: lms1xx.h:177
void setScanDataCfg(const scanDataCfg &cfg)
Set scan data configuration. Set format of scan message returned by device.
Definition: lms1xx.cpp:171
scanCfg getScanCfg() const
Get current scan configuration. Get scan configuration :
Definition: lms1xx.cpp:138
status_t queryStatus()
Get current status of LMS1xx device.
Definition: lms1xx.cpp:104
int main(int argc, char **argv)
Definition: lms1xx_node.cpp:40
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
Definition: lms1xx.cpp:123
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring...
Definition: lms1xx.cpp:89
Structure containing single scan message.
Structure containing scan configuration.
void scanContinous(int start)
Start or stop continuous data acquisition. After reception of this command device start or stop conti...
Definition: lms1xx.cpp:185
void startMeas()
Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring...
Definition: lms1xx.cpp:74
bool isConnected()
Get status of connection.
Definition: lms1xx.cpp:70
void disconnect()
Disconnect from LMS1xx device.
Definition: lms1xx.cpp:63
void connect(std::string host, int port=2111)
Connect to LMS1xx.
Definition: lms1xx.cpp:44
#define DEG2RAD
Definition: lms1xx_node.cpp:38
void getData(scanData &data)
Receive single scan message.
Definition: lms1xx.cpp:207
Structure containing scan data configuration.
Class responsible for communicating with LMS1xx device.
Definition: lms1xx.h:195


lms1xx
Author(s): Konrad Banachowicz
autogenerated on Mon Mar 2 2015 01:32:13