From 08e2a550d8f78f3c037e303089be9a07582af33d Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Tue, 20 Oct 2015 08:36:50 +0200 Subject: [PATCH 1/2] extend setOutputRange function --- include/LMS1xx/LMS1xx.h | 10 ++++++++++ src/LMS1xx.cpp | 12 ++++++++++++ 2 files changed, 22 insertions(+) diff --git a/include/LMS1xx/LMS1xx.h b/include/LMS1xx/LMS1xx.h index a4b6335..edd2573 100644 --- a/include/LMS1xx/LMS1xx.h +++ b/include/LMS1xx/LMS1xx.h @@ -293,6 +293,16 @@ class LMS1xx { */ void setScanDataCfg(const scanDataCfg &cfg); + /*! + * @brief Set output range configuration. + * Get output range configuration : + * - angle resolution. + * - start angle. + * - stop angle. + * @param cfg structure containing output range configuration. + */ + void setOutputRange(const scanOutputRange &cfg); + /*! * @brief Get current output range configuration. * Get output range configuration : diff --git a/src/LMS1xx.cpp b/src/LMS1xx.cpp index d03436d..84c466f 100644 --- a/src/LMS1xx.cpp +++ b/src/LMS1xx.cpp @@ -187,6 +187,18 @@ void LMS1xx::setScanDataCfg(const scanDataCfg &cfg) { buf[len - 1] = 0; } +void LMS1xx::setOutputRange(const scanOutputRange &cfg) { + char buf[100]; + sprintf(buf, "%c%s 1 %X %X %X%c", 0x02, "sWN LMPoutputRange", + cfg.angleResolution, cfg.startAngle, cfg.stopAngle, 0x03); + + write(sockDesc, buf, strlen(buf)); + + int len = read(sockDesc, buf, 100); + + buf[len - 1] = 0; +} + scanOutputRange LMS1xx::getScanOutputRange() const { scanOutputRange outputRange; char buf[100]; From 61420b0f3ad7c929d4e3be7ca311578c5bb1d296 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Tue, 20 Oct 2015 11:01:22 +0200 Subject: [PATCH 2/2] disable hardcoded frequence condition --- src/LMS1xx_node.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/src/LMS1xx_node.cpp b/src/LMS1xx_node.cpp index 9ba2f9b..7b86df8 100644 --- a/src/LMS1xx_node.cpp +++ b/src/LMS1xx_node.cpp @@ -45,14 +45,9 @@ int main(int argc, char **argv) outputRange = laser.getScanOutputRange(); } - //check if laser is fully initialized, else reconnect - //assuming fully initialized => scaningFrequency=5000 - if (cfg.scaningFrequency != 5000) { - laser.disconnect(); ROS_INFO("Waiting for laser to initialize..."); - } - } while (!laser.isConnected() || cfg.scaningFrequency != 5000); + } while (!laser.isConnected()); if (laser.isConnected()) { ROS_INFO("Connected to laser.");