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