laser.h
Go to the documentation of this file.
1 /*
2 * Copyright (c) 2022, Autonics Co.,Ltd.
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
7 * are met:
8 *
9 * * Redistributions of source code must retain the above copyright
10 * notice, this list of conditions and the following disclaimer.
11 *
12 * * Redistributions in binary form must reproduce the above
13 * copyright notice, this list of conditions and the following
14 * disclaimer in the documentation and/or other materials provided
15 * with the distribution.
16 *
17 * * Neither the name of the Autonics Co.,Ltd nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 */
34 
35 
36 
37 #ifndef LASER_H
38 #define LASER_H
39 
40 #include <ros/ros.h>
41 #include "std_msgs/String.h"
42 #include <sensor_msgs/LaserScan.h>
43 
46 
47 #include "socket.hpp"
48 #include "parser.hpp"
49 
50 #define CONNECT_ATTEMPT_CNT 999
51 
52 class AutoLaser
53 {
54 public:
55  AutoLaser();
56  ~AutoLaser();
57 
58  int laserInit(void);
59  int run(void);
60 
61 
62 private:
63  bool checkConnection();
64 
65  void watchingDisconnection(void);
66  std::string itostr(int i);
67  std::string ftostr(float i);
68  unsigned char hexToChar(unsigned int value);
69 
70  int laserSendCommand(const std::string str);
71  int getLaserData(sensor_msgs::LaserScan::Ptr scan_msg);
72  void comSubCallback(const std_msgs::String::ConstPtr& msg);
74  int getLscData(void);
75  void login(std::string password);
76 
80 
83 
86 
87  sensor_msgs::LaserScan::Ptr scan_msg;
89 
91  std::vector<unsigned char> rcv_msg_;
92 
93  std::string topic_name;
94 };
95 
96 #endif
AutoLaser::topic_name
std::string topic_name
Definition: laser.h:93
parser.hpp
AutoLaser::AutoLaser
AutoLaser()
Definition: laser.cpp:45
AutoLaser::laserSendCommand
int laserSendCommand(const std::string str)
Definition: laser.cpp:109
AutoLaser::ftostr
std::string ftostr(float i)
Definition: laser.cpp:66
msg
msg
ros::Publisher
AutoLaser::p
Parser p
Definition: laser.h:82
AutoLaser::rcv_msg_
std::vector< unsigned char > rcv_msg_
Definition: laser.h:91
AutoLaser::scan_msg
sensor_msgs::LaserScan::Ptr scan_msg
Definition: laser.h:87
AutoLaser::pub_scan
ros::Publisher pub_scan
Definition: laser.h:84
AutoLaser::getLaserData
int getLaserData(sensor_msgs::LaserScan::Ptr scan_msg)
Definition: laser.cpp:218
AutoLaser::n
ros::NodeHandle n
Definition: laser.h:77
AutoLaser::comSubCallback
void comSubCallback(const std_msgs::String::ConstPtr &msg)
Definition: laser.cpp:94
AutoLaser
Definition: laser.h:52
ros.h
AutoLaser::itostr
std::string itostr(int i)
Definition: laser.cpp:55
AutoLaser::rcv_msg_flag_
bool rcv_msg_flag_
Definition: laser.h:90
diagnostic_updater::Updater
Socket
Definition: socket.hpp:53
AutoLaser::run
int run(void)
Definition: laser.cpp:313
AutoLaser::priv_nh
ros::NodeHandle priv_nh
Definition: laser.h:78
publisher.h
diagnostic_updater.h
AutoLaser::hexToChar
unsigned char hexToChar(unsigned int value)
Definition: laser.cpp:77
AutoLaser::watchingDisconnection
void watchingDisconnection(void)
Definition: laser.cpp:241
AutoLaser::selfTest
void selfTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: laser.cpp:187
socket.hpp
AutoLaser::laserInit
int laserInit(void)
Definition: laser.cpp:257
AutoLaser::getLscData
int getLscData(void)
Definition: laser.cpp:201
AutoLaser::diagnostic_topic_updater
diagnostic_updater::Updater diagnostic_topic_updater
Definition: laser.h:79
Parser
Definition: parser.hpp:69
Lsc_t
Definition: parser.hpp:63
AutoLaser::~AutoLaser
~AutoLaser()
Definition: laser.cpp:50
diagnostic_updater::DiagnosticStatusWrapper
AutoLaser::sub_cmd
ros::Subscriber sub_cmd
Definition: laser.h:85
AutoLaser::lsc
Lsc_t lsc
Definition: laser.h:88
AutoLaser::socket
Socket socket
Definition: laser.h:81
ros::NodeHandle
ros::Subscriber
AutoLaser::login
void login(std::string password)
Definition: laser.cpp:101
AutoLaser::checkConnection
bool checkConnection()
Definition: laser.cpp:171


lsc_ros_driver
Author(s): Autonics-lidar
autogenerated on Sat Jan 14 2023 03:18:24