parser.hpp
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 #ifndef PARSER_H
37 #define PARSER_H
38 
39 #include <sensor_msgs/LaserScan.h>
40 
41 //#define PRINT_PARSE_DATA
42 
43 #define PI 3.14159265358979323846
44 #define DEG2RAD PI / 180
45 
46 struct ScanInfo
47 {
48  uint16_t fw_ver;
49  std::string model_name;
50 };
51 
52 struct ScanMea
53 {
54  uint16_t scan_counter;
55  uint16_t scan_freq;
56  uint16_t meas_freq;
57  int32_t angle_begin;
58  uint16_t angle_resol;
59  uint16_t amnt_of_data;
60  uint16_t active_field_num;
61 };
62 
63 struct Lsc_t
64 {
67 };
68 
69 class Parser
70 {
71 public:
72  Parser();
73 
74  void parsingMsg(std::vector<unsigned char> raw_msg, sensor_msgs::LaserScan::Ptr msg, Lsc_t* lsc);
75  int makeCommand(unsigned char* buf, std::string cmd);
76 };
77 
78 #endif
msg
Definition: parser.hpp:63
ScanInfo scan_info
Definition: parser.hpp:66
uint16_t angle_resol
Definition: parser.hpp:58
uint16_t amnt_of_data
Definition: parser.hpp:59
ScanMea scan_mea
Definition: parser.hpp:65
int32_t angle_begin
Definition: parser.hpp:57
uint16_t scan_freq
Definition: parser.hpp:55
uint16_t fw_ver
Definition: parser.hpp:48
uint16_t meas_freq
Definition: parser.hpp:56
std::string model_name
Definition: parser.hpp:49
uint16_t scan_counter
Definition: parser.hpp:54
uint16_t active_field_num
Definition: parser.hpp:60


lsc_ros_driver
Author(s): Autonics-lidar
autogenerated on Thu Jan 12 2023 03:08:46