sick_scan_parse_util.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3 * Copyright (C) 2017, Ing.-Buero Dr. Michael Lehning, Hildesheim
4 * Copyright (C) 2017, SICK AG, Waldkirch
5 * All rights reserved.
6 *
7 * Licensed under the Apache License, Version 2.0 (the "License");
8 * you may not use this file except in compliance with the License.
9 * You may obtain a copy of the License at
10 *
11 * http://www.apache.org/licenses/LICENSE-2.0
12 *
13 * Unless required by applicable law or agreed to in writing, software
14 * distributed under the License is distributed on an "AS IS" BASIS,
15 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 * See the License for the specific language governing permissions and
17 * limitations under the License.
18 *
19 *
20 * All rights reserved.
21 *
22 * Redistribution and use in source and binary forms, with or without
23 * modification, are permitted provided that the following conditions are met:
24 *
25 * * Redistributions of source code must retain the above copyright
26 * notice, this list of conditions and the following disclaimer.
27 * * Redistributions in binary form must reproduce the above copyright
28 * notice, this list of conditions and the following disclaimer in the
29 * documentation and/or other materials provided with the distribution.
30 * * Neither the name of Osnabrueck University nor the names of its
31 * contributors may be used to endorse or promote products derived from
32 * this software without specific prior written permission.
33 * * Neither the name of SICK AG nor the names of its
34 * contributors may be used to endorse or promote products derived from
35 * this software without specific prior written permission
36 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
37 * contributors may be used to endorse or promote products derived from
38 * this software without specific prior written permission
39 *
40 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
41 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
42 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
43 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
44 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
45 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
46 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
47 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
48 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
49 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
50 * POSSIBILITY OF SUCH DAMAGE.
51  *
52  * Created on: 24.05.2012
53  *
54  * Authors:
55  * Michael Lehning <michael.lehning@lehning.de>
56  *
57  * Utility functions for parsing scanner specific sopas requests and responses
58  *
59  */
60 
61 #ifndef SICK_SCAN_PARSE_UTIL_H_
62 #define SICK_SCAN_PARSE_UTIL_H_
63 
64 #include <string>
65 #include <vector>
66 
68 
69 namespace sick_scan_xd
70 {
71  // returns the given angle in rad normalized to angle_min ... angle_max, assuming (angle_max - angle_min) == 2 * PI
72  double normalizeAngleRad(double angle_rad, double angle_min, double angle_max);
73 
74  // Converts a string to a 6D pose x,y,z,roll,pitch,yaw in [m] resp. [rad]
75  std::vector<float> parsePose(const std::string& pose_xyz_rpy_str);
76 
78  {
79  public:
80 
81  /*
82  * Convert LMPscancfg from / to sopas requests/responses
83  */
84 
86  {
87  public:
88  uint32_t angular_resolution = 0; // angular resolution in 1/10000 deg
89  int32_t start_angle = 0; // start angle in 1/10000 deg
90  int32_t stop_angle = 0; // stop angle in 1/10000 deg
91  };
92 
93  class LMPscancfg
94  {
95  public:
96  uint32_t scan_frequency = 0; // scan frequency in 1/100 Hz
97  int16_t active_sector_cnt = 0; // number of active sectors
98  std::vector<LMPscancfgSector> sector_cfg;
99  std::string print() const;
100  };
101 
103  static bool SopasToLMPscancfg(const std::string& sopas_reply, LMPscancfg& scancfg);
104 
106  static bool LMPscancfgToSopas(const LMPscancfg& scancfg, std::string& sopas_cmd);
107 
108  }; // class SickScanParseUtil
109 } // namespace sick_scan_xd
110 
111 #endif // SICK_SCAN_PARSE_UTIL_H_
sick_scan_xd::SickScanParseUtil::LMPscancfg::sector_cfg
std::vector< LMPscancfgSector > sector_cfg
Definition: sick_scan_parse_util.h:98
sick_scan_xd::SickScanParseUtil::LMPscancfgSector::stop_angle
int32_t stop_angle
Definition: sick_scan_parse_util.h:90
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_ros_wrapper.h
sick_scan_xd::SickScanParseUtil::LMPscancfg::active_sector_cnt
int16_t active_sector_cnt
Definition: sick_scan_parse_util.h:97
sick_scan_xd::SickScanParseUtil::LMPscancfgSector::angular_resolution
uint32_t angular_resolution
Definition: sick_scan_parse_util.h:88
sick_scan_xd::SickScanParseUtil::LMPscancfgSector::start_angle
int32_t start_angle
Definition: sick_scan_parse_util.h:89
sick_scan_xd::SickScanParseUtil::LMPscancfg::scan_frequency
uint32_t scan_frequency
Definition: sick_scan_parse_util.h:96
sick_scan_xd::SickScanParseUtil::SopasToLMPscancfg
static bool SopasToLMPscancfg(const std::string &sopas_reply, LMPscancfg &scancfg)
Parse the sopas reply to "sRN LMPscancfg" and convert to LMPscancfg.
Definition: sick_scan_parse_util.cpp:174
sick_scan_xd::SickScanParseUtil::LMPscancfgToSopas
static bool LMPscancfgToSopas(const LMPscancfg &scancfg, std::string &sopas_cmd)
Convert LMPscancfg to sopas request "sMN mLMPsetscancfg ...".
Definition: sick_scan_parse_util.cpp:229
sick_scan_xd::parsePose
std::vector< float > parsePose(const std::string &pose_xyz_rpy_str)
Definition: sick_scan_parse_util.cpp:100
sick_scan_xd::SickScanParseUtil::LMPscancfg
Definition: sick_scan_parse_util.h:93
sick_scan_xd::SickScanParseUtil::LMPscancfgSector
Definition: sick_scan_parse_util.h:85
sick_scan_base.h
sick_scan_xd::SickScanParseUtil::LMPscancfg::print
std::string print() const
Definition: sick_scan_parse_util.cpp:156
sick_scan_xd::normalizeAngleRad
double normalizeAngleRad(double angle_rad, double angle_min, double angle_max)
Definition: sick_scan_parse_util.cpp:90
sick_scan_xd::SickScanParseUtil
Definition: sick_scan_parse_util.h:77


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:11