sick_ldmrs_config.hpp
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) 2020, Ing.-Buero Dr. Michael Lehning, Hildesheim
4  * Copyright (C) 2020, 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: 2nd Oct 2020
53  *
54  * Authors:
55  * Michael Lehning <michael.lehning@lehning.de>
56  *
57  */
58 
59 #ifndef __SICK_LDMRS_CONFIG_H__
60 #define __SICK_LDMRS_CONFIG_H__
61 
62 #include <cmath>
63 #include <string>
65 
66 namespace sick_ldmrs_driver
67 {
68  /*
69  * @brief Utility function to declare and get a ros parameter
70  */
71  template<typename T> bool param(rosNodePtr node, const std::string & param_name, T& value, const T& default_value)
72  {
73  ROS_DEBUG_STREAM("ROS::param(" << param_name << "," << default_value << ")");
74  try
75  {
76  rosDeclareParam<T>(node, param_name, default_value);
77  }
78  catch(const std::exception& exc)
79  {
80  ROS_WARN_STREAM("## ERROR ROS::param: declare_parameter(" << param_name << "," << default_value << ") failed, exception " << exc.what());
81  }
82  try
83  {
84  bool ret = rosGetParam(node, param_name, value);
85  ROS_INFO_STREAM("ROS::param(" << param_name << "," << default_value << "): " << param_name << "=" << value);
86  return ret;
87  }
88  catch(const std::exception& exc)
89  {
90  ROS_WARN_STREAM("## ERROR ROS::param: get_parameter(" << param_name << "," << default_value << ") failed, exception " << exc.what());
91  }
92  return false;
93  }
94 
95  /*
96  * @brief Configuration of SICK LDMRS driver
97  */
99  {
100  public:
101 
102  static const double deg2rad(double angle){ return (angle * M_PI / 180.0); }
103  static const double tics2rad(double tics){ return (deg2rad(tics / 32.0)); }
104 
105  enum scan_freq_enum // "Available scan frequencies"
106  {
107  ScanFreq1250 = 0, // "Scan frequency 12.5 Hz"
108  ScanFreq2500 = 1, // "Scan frequency 25.0 Hz"
109  ScanFreq5000 = 2 // "Scan frequency 25.0 Hz"
110  };
111 
112  enum contour_enum // "Contour point density"
113  {
114  ClosestPointOnly = 0, // "Closest point only"
115  LowDensity = 1, // "Low density"
116  HighDensity = 2 // "High density"
117  };
118 
119  enum angular_res_enum // "Angular resolution type"
120  {
121  FocusedRes = 0, // "Focused resolution"
122  ConstantRes = 1, // "Constant resolution"
123  FlexRes = 2 // "Flexible resolution"
124  };
125 
126  enum range_reduction_enum // "Layer range reduction"
127  {
128  RangeFull = 0, // "All layers full range"
129  RangeLowerReduced = 1, // "Lower 4 layers reduced range"
130  RangeUpperReduced = 2, // "Upper 4 layers reduced range"
131  RangeAllReduced = 3 // "All 8 layers reduced range"
132  };
133 
134  enum resolution_enum // "FlexRes angular resolution"
135  {
136  Res0125 = 4, // "Angular resolution 0.125 degrees"
137  Res0250 = 8, // "Angular resolution 0.25 degrees"
138  Res0500 = 16, // "Angular resolution 0.5 degrees"
139  Res1000 = 32 // "Angular resolution 1.0 degrees"
140  };
141 
142  /*
143  * @brief Constructor of SICK LDMRS driver configuration.
144  * Initializes the configuration with default values.
145  */
147 
148  bool set_parameter(const std::string & name, const bool & value);
149  bool set_parameter(const std::string & name, const int64_t & value);
150  bool set_parameter(const std::string & name, const double & value);
151  bool set_parameter(const std::string & name, const std::string & value);
152 
153  // ROS parameters
154  std::string frame_id; // gen.add("frame_id", str_t, 0, "The TF frame in which point clouds will be returned.", "cloud")
155  // Measurement parameters
156  double start_angle; // gen.add("start_angle", double_t, 0, "The angle of the first range measurement [rad].", 1600 * tics2rad, -1918 * tics2rad, 1600 * tics2rad) # 50 deg
157  double end_angle; // gen.add("end_angle", double_t, 0, "The angle of the last range measurement [rad].", -1920 * tics2rad, -1920 * tics2rad, 1598 * tics2rad) # -60 deg
158  int scan_frequency; // gen.add("scan_frequency", int_t, 0, "Scan frequency, 0 = 12.5Hz, 1 = 25 Hz, 2 = 50 Hz", 0, 0, 2, edit_method=scan_freq_enum)
159  double sync_angle_offset; // gen.add("sync_angle_offset", double_t, 0, "Angle under which the LD-MRS measures at the time of the sync pulse [rad].", 0, -5760 * tics2rad, 5759 * tics2rad) # -180...179.96 deg
160  int angular_resolution_type; // gen.add("angular_resolution_type", int_t, 0, "Angular resolution type: 0 = focused, 1 = constant, 2 = flexible", 1, 0, 2, edit_method=angular_res_enum)
161  int layer_range_reduction; // gen.add("layer_range_reduction", int_t, 0, "0: Full range, 1: lower 4 reduced, 2: upper 4 reduced, 3: all reduced", 0, 0, 3, edit_method=range_reduction_enum)
162  bool ignore_near_range; // gen.add("ignore_near_range", bool_t, 0, "Ignore scan points up to 15m. Requires layer_range_reduction = lower 4 reduced.", False)
163  bool sensitivity_control; // gen.add("sensitivity_control", bool_t, 0, "Reduce the sensitivity automatically in case of extraneous light.", False)
164 
165  // FlexRes parameters
166  double flexres_start_angle1; // gen.add("flexres_start_angle1", double_t, 0, "FlexRes: start angle of sector 1.", 1600 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
167  double flexres_start_angle2; // gen.add("flexres_start_angle2", double_t, 0, "FlexRes: start angle of sector 2.", 1120 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
168  double flexres_start_angle3; // gen.add("flexres_start_angle3", double_t, 0, "FlexRes: start angle of sector 3.", 960 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
169  double flexres_start_angle4; // gen.add("flexres_start_angle4", double_t, 0, "FlexRes: start angle of sector 4.", 640 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
170  double flexres_start_angle5; // gen.add("flexres_start_angle5", double_t, 0, "FlexRes: start angle of sector 5.", 0 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
171  double flexres_start_angle6; // gen.add("flexres_start_angle6", double_t, 0, "FlexRes: start angle of sector 6.", -640 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
172  double flexres_start_angle7; // gen.add("flexres_start_angle7", double_t, 0, "FlexRes: start angle of sector 7.", -960 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
173  double flexres_start_angle8; // gen.add("flexres_start_angle8", double_t, 0, "FlexRes: start angle of sector 8.", -1280 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
174  int flexres_resolution1; // gen.add("flexres_resolution1", int_t, 0, "FlexRes: angular resolution of sector 1.", 32, 4, 32, edit_method=resolution_enum)
175  int flexres_resolution2; // gen.add("flexres_resolution2", int_t, 0, "FlexRes: angular resolution of sector 2.", 16, 4, 32, edit_method=resolution_enum)
176  int flexres_resolution3; // gen.add("flexres_resolution3", int_t, 0, "FlexRes: angular resolution of sector 3.", 8, 4, 32, edit_method=resolution_enum)
177  int flexres_resolution4; // gen.add("flexres_resolution4", int_t, 0, "FlexRes: angular resolution of sector 4.", 4, 4, 32, edit_method=resolution_enum)
178  int flexres_resolution5; // gen.add("flexres_resolution5", int_t, 0, "FlexRes: angular resolution of sector 5.", 8, 4, 32, edit_method=resolution_enum)
179  int flexres_resolution6; // gen.add("flexres_resolution6", int_t, 0, "FlexRes: angular resolution of sector 6.", 16, 4, 32, edit_method=resolution_enum)
180  int flexres_resolution7; // gen.add("flexres_resolution7", int_t, 0, "FlexRes: angular resolution of sector 7.", 32, 4, 32, edit_method=resolution_enum)
181  int flexres_resolution8; // gen.add("flexres_resolution8", int_t, 0, "FlexRes: angular resolution of sector 8.", 16, 4, 32, edit_method=resolution_enum)
182  // Object tracking parameters
183  int contour_point_density; // gen.add("contour_point_density", int_t, 0, "Contour point density, 0: closest point only, 1: low density, 2: high density", 2, 0, 2, edit_method=contour_enum)
184  int min_object_age; // gen.add("min_object_age", int_t, 0, "Minimum tracking age (number of scans) of an object to be transmitted.", 0, 0, 65535)
185  int max_prediction_age; // gen.add("max_prediction_age", int_t, 0, "Maximum prediction age (number of scans) of an object to be transmitted.", 0, 0, 65535)
186 
187  }; // class SickLDMRSDriverConfig
188 
189 } // namespace sick_ldmrs_driver
190 
191 #endif // __SICK_LDMRS_CONFIG_H__
sick_ldmrs_driver::SickLDMRSDriverConfig::scan_frequency
int scan_frequency
Definition: sick_ldmrs_config.hpp:158
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle8
double flexres_start_angle8
Definition: sick_ldmrs_config.hpp:173
sick_ldmrs_driver::SickLDMRSDriverConfig::Res0500
@ Res0500
Definition: sick_ldmrs_config.hpp:138
sick_ldmrs_driver::SickLDMRSDriverConfig::frame_id
std::string frame_id
Definition: sick_ldmrs_config.hpp:154
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
sick_ldmrs_driver::SickLDMRSDriverConfig::ignore_near_range
bool ignore_near_range
Definition: sick_ldmrs_config.hpp:162
sick_ldmrs_driver::SickLDMRSDriverConfig::RangeAllReduced
@ RangeAllReduced
Definition: sick_ldmrs_config.hpp:131
sick_ldmrs_driver::SickLDMRSDriverConfig::ClosestPointOnly
@ ClosestPointOnly
Definition: sick_ldmrs_config.hpp:114
sick_ldmrs_driver::param
bool param(rosNodePtr node, const std::string &param_name, T &value, const T &default_value)
Definition: sick_ldmrs_config.hpp:71
sick_ldmrs_driver::SickLDMRSDriverConfig::resolution_enum
resolution_enum
Definition: sick_ldmrs_config.hpp:134
sick_ldmrs_driver::SickLDMRSDriverConfig::sensitivity_control
bool sensitivity_control
Definition: sick_ldmrs_config.hpp:163
sick_ldmrs_driver::SickLDMRSDriverConfig::contour_point_density
int contour_point_density
Definition: sick_ldmrs_config.hpp:183
sick_ldmrs_driver::SickLDMRSDriverConfig::max_prediction_age
int max_prediction_age
Definition: sick_ldmrs_config.hpp:185
sick_ldmrs_driver::SickLDMRSDriverConfig::FlexRes
@ FlexRes
Definition: sick_ldmrs_config.hpp:123
sick_ldmrs_driver::SickLDMRSDriverConfig::ConstantRes
@ ConstantRes
Definition: sick_ldmrs_config.hpp:122
sick_ldmrs_driver::SickLDMRSDriverConfig::Res0250
@ Res0250
Definition: sick_ldmrs_config.hpp:137
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle5
double flexres_start_angle5
Definition: sick_ldmrs_config.hpp:170
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution4
int flexres_resolution4
Definition: sick_ldmrs_config.hpp:177
sick_ldmrs_driver::SickLDMRSDriverConfig::Res1000
@ Res1000
Definition: sick_ldmrs_config.hpp:139
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution1
int flexres_resolution1
Definition: sick_ldmrs_config.hpp:174
default_value
string default_value
sick_ldmrs_driver::SickLDMRSDriverConfig::scan_freq_enum
scan_freq_enum
Definition: sick_ldmrs_config.hpp:105
sick_ros_wrapper.h
sick_ldmrs_driver::SickLDMRSDriverConfig::deg2rad
static const double deg2rad(double angle)
Definition: sick_ldmrs_config.hpp:102
sick_ldmrs_driver::SickLDMRSDriverConfig::FocusedRes
@ FocusedRes
Definition: sick_ldmrs_config.hpp:121
sick_ldmrs_driver::SickLDMRSDriverConfig::tics2rad
static const double tics2rad(double tics)
Definition: sick_ldmrs_config.hpp:103
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
Definition: sick_scan_logging.h:123
sick_ldmrs_driver::SickLDMRSDriverConfig::RangeFull
@ RangeFull
Definition: sick_ldmrs_config.hpp:128
ROS_INFO_STREAM
#define ROS_INFO_STREAM(...)
Definition: sick_scan_ros2_example.cpp:71
api.setup.name
name
Definition: python/api/setup.py:12
polar_to_cartesian_pointcloud_ros1.node
node
Definition: polar_to_cartesian_pointcloud_ros1.py:81
sick_ldmrs_driver::SickLDMRSDriverConfig::start_angle
double start_angle
Definition: sick_ldmrs_config.hpp:156
sick_ldmrs_driver::SickLDMRSDriverConfig::RangeUpperReduced
@ RangeUpperReduced
Definition: sick_ldmrs_config.hpp:130
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle7
double flexres_start_angle7
Definition: sick_ldmrs_config.hpp:172
sick_ldmrs_driver::SickLDMRSDriverConfig::angular_res_enum
angular_res_enum
Definition: sick_ldmrs_config.hpp:119
sick_ldmrs_driver::SickLDMRSDriverConfig::range_reduction_enum
range_reduction_enum
Definition: sick_ldmrs_config.hpp:126
sick_ldmrs_driver::SickLDMRSDriverConfig::ScanFreq5000
@ ScanFreq5000
Definition: sick_ldmrs_config.hpp:109
sick_ldmrs_driver::SickLDMRSDriverConfig::end_angle
double end_angle
Definition: sick_ldmrs_config.hpp:157
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution8
int flexres_resolution8
Definition: sick_ldmrs_config.hpp:181
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
Definition: sick_scan_logging.h:113
ros::NodeHandle
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle1
double flexres_start_angle1
Definition: sick_ldmrs_config.hpp:166
rosGetParam
bool rosGetParam(rosNodePtr nh, const std::string &param_name, T &param_value)
Definition: sick_ros_wrapper.h:167
sick_ldmrs_driver::SickLDMRSDriverConfig::SickLDMRSDriverConfig
SickLDMRSDriverConfig(rosNodePtr nh=0)
Definition: sick_ldmrs_config.cpp:64
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution7
int flexres_resolution7
Definition: sick_ldmrs_config.hpp:180
sick_ldmrs_driver::SickLDMRSDriverConfig::contour_enum
contour_enum
Definition: sick_ldmrs_config.hpp:112
sick_ldmrs_driver::SickLDMRSDriverConfig::sync_angle_offset
double sync_angle_offset
Definition: sick_ldmrs_config.hpp:159
sick_ldmrs_driver::SickLDMRSDriverConfig::set_parameter
bool set_parameter(const std::string &name, const bool &value)
Definition: sick_ldmrs_config.cpp:105
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle4
double flexres_start_angle4
Definition: sick_ldmrs_config.hpp:169
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution3
int flexres_resolution3
Definition: sick_ldmrs_config.hpp:176
sick_ldmrs_driver
Definition: sick_ldmrs_driver.cpp:60
sick_ldmrs_driver::SickLDMRSDriverConfig::Res0125
@ Res0125
Definition: sick_ldmrs_config.hpp:136
sick_ldmrs_driver::SickLDMRSDriverConfig::ScanFreq2500
@ ScanFreq2500
Definition: sick_ldmrs_config.hpp:108
sick_ldmrs_driver::SickLDMRSDriverConfig::HighDensity
@ HighDensity
Definition: sick_ldmrs_config.hpp:116
sick_ldmrs_driver::SickLDMRSDriverConfig::layer_range_reduction
int layer_range_reduction
Definition: sick_ldmrs_config.hpp:161
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle3
double flexres_start_angle3
Definition: sick_ldmrs_config.hpp:168
sick_scan_base.h
sick_ldmrs_driver::SickLDMRSDriverConfig::angular_resolution_type
int angular_resolution_type
Definition: sick_ldmrs_config.hpp:160
sick_ldmrs_driver::SickLDMRSDriverConfig::RangeLowerReduced
@ RangeLowerReduced
Definition: sick_ldmrs_config.hpp:129
sick_ldmrs_driver::SickLDMRSDriverConfig::ScanFreq1250
@ ScanFreq1250
Definition: sick_ldmrs_config.hpp:107
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution2
int flexres_resolution2
Definition: sick_ldmrs_config.hpp:175
sick_ldmrs_driver::SickLDMRSDriverConfig
Definition: sick_ldmrs_config.hpp:98
sick_ldmrs_driver::SickLDMRSDriverConfig::min_object_age
int min_object_age
Definition: sick_ldmrs_config.hpp:184
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle2
double flexres_start_angle2
Definition: sick_ldmrs_config.hpp:167
sick_ldmrs_driver::SickLDMRSDriverConfig::LowDensity
@ LowDensity
Definition: sick_ldmrs_config.hpp:115
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution6
int flexres_resolution6
Definition: sick_ldmrs_config.hpp:179
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle6
double flexres_start_angle6
Definition: sick_ldmrs_config.hpp:171
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution5
int flexres_resolution5
Definition: sick_ldmrs_config.hpp:178


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