hlds_laser_segment_publisher.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright (c) 2016, Hitachi-LG Data Storage
3 * Copyright (c) 2017, ROBOTIS
4 * All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions are met:
8 *
9 * * Redistributions of source code must retain the above copyright notice, this
10 * list of conditions and the following disclaimer.
11 *
12 * * Redistributions in binary form must reproduce the above copyright notice,
13 * this list of conditions and the following disclaimer in the documentation
14 * and/or other materials provided with the distribution.
15 *
16 * * Neither the name of the copyright holder nor the names of its
17 * contributors may be used to endorse or promote products derived from
18 * this software without specific prior written permission.
19 *
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 *******************************************************************************/
31 
32  /* Authors: SP Kong, JH Yang */
33  /* maintainer: Pyo */
34 
35 #include <string>
36 #include <sensor_msgs/LaserScan.h>
37 #include <boost/asio.hpp>
38 #include <boost/array.hpp>
39 
40 namespace hls_lfcd_lds
41 {
42 class LFCDLaser
43 {
44 public:
45  uint16_t rpms;
46 
52  LFCDLaser(const std::string& port, uint32_t baud_rate, boost::asio::io_service& io);
53 
57  ~LFCDLaser();
58 
63  void poll(sensor_msgs::LaserScan::Ptr scan);
64 
68  void close() { shutting_down_ = true; }
69 
70 private:
71  std::string port_;
72  uint32_t baud_rate_;
74  boost::asio::serial_port serial_;
75  uint16_t motor_speed_;
76 };
77 }
uint16_t motor_speed_
current motor speed as reported by the LFCD.
uint16_t rpms
RPMS derived from the rpm bytes in an LFCD packet.
bool shutting_down_
Flag for whether the driver is supposed to be shutting down or not.
boost::asio::serial_port serial_
Actual serial port object for reading/writing to the LFCD Laser Scanner.
LFCDLaser(const std::string &port, uint32_t baud_rate, boost::asio::io_service &io)
Constructs a new LFCDLaser attached to the given serial port.
void close()
Close the driver down and prevent the polling loop from advancing.
std::string port_
The serial port the driver is attached to.
uint32_t baud_rate_
The baud rate for the serial connection.
~LFCDLaser()
Default destructor.
void poll(sensor_msgs::LaserScan::Ptr scan)
Poll the laser to get a new scan. Blocks until a complete new scan is received or close is called...


hls-lfcd-lds-driver
Author(s): Pyo , Darby Lim , Gilbert , Will Son , JH Yang, SP Kong
autogenerated on Fri Apr 16 2021 02:20:09