sick_ldmrs_config.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020, Ing.-Buero Dr. Michael Lehning, Hildesheim
3  * Copyright (C) 2020, SICK AG, Waldkirch
4  * All rights reserved.
5  *
6 * Licensed under the Apache License, Version 2.0 (the "License");
7 * you may not use this file except in compliance with the License.
8 * You may obtain a copy of the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS,
14 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 * See the License for the specific language governing permissions and
16 * limitations under the License.
17 *
18 *
19 * All rights reserved.
20 *
21 * Redistribution and use in source and binary forms, with or without
22 * modification, are permitted provided that the following conditions are met:
23 *
24 * * Redistributions of source code must retain the above copyright
25 * notice, this list of conditions and the following disclaimer.
26 * * Redistributions in binary form must reproduce the above copyright
27 * notice, this list of conditions and the following disclaimer in the
28 * documentation and/or other materials provided with the distribution.
29 * * Neither the name of Osnabrueck University nor the names of its
30 * contributors may be used to endorse or promote products derived from
31 * this software without specific prior written permission.
32 * * Neither the name of SICK AG nor the names of its
33 * contributors may be used to endorse or promote products derived from
34 * this software without specific prior written permission
35 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
36 * contributors may be used to endorse or promote products derived from
37 * this software without specific prior written permission
38 *
39 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
40 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
41 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
42 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
43 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
44 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
45 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
46 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
47 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
48 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
49 * POSSIBILITY OF SUCH DAMAGE.
50  *
51  * Created on: 2nd Oct 2020
52  *
53  * Authors:
54  * Michael Lehning <michael.lehning@lehning.de>
55  *
56  */
57 
59 
60 /*
61  * @brief Constructor of SICK LDMRS driver configuration.
62  * Initializes the configuration with default values.
63  */
65 {
66  if(nh)
67  {
68  // ROS parameters
69  sick_ldmrs_driver::param<std::string>(nh, "frame_id", frame_id, "cloud"); // gen.add("frame_id", str_t, 0, "The TF frame in which point clouds will be returned.", "cloud")
70  // Measurement parameters
71  sick_ldmrs_driver::param<double>(nh, "start_angle", start_angle, 0.872664); // gen.add("start_angle", double_t, 0, "The angle of the first range measurement [rad].", 1600 * tics2rad, -1918 * tics2rad, 1600 * tics2rad) # 50 deg
72  sick_ldmrs_driver::param<double>(nh, "end_angle", end_angle, -1.047197); // gen.add("end_angle", double_t, 0, "The angle of the last range measurement [rad].", -1920 * tics2rad, -1920 * tics2rad, 1598 * tics2rad) # -60 deg
73  sick_ldmrs_driver::param<int> (nh, "scan_frequency", scan_frequency, 0 ); // 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)
74  sick_ldmrs_driver::param<double>(nh, "sync_angle_offset", sync_angle_offset, 0 ); // 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
75  sick_ldmrs_driver::param<int> (nh, "angular_resolution_type", angular_resolution_type, 1 ); // 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)
76  sick_ldmrs_driver::param<int> (nh, "layer_range_reduction", layer_range_reduction, 0 ); // 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)
77  sick_ldmrs_driver::param<bool> (nh, "ignore_near_range", ignore_near_range, false ); // gen.add("ignore_near_range", bool_t, 0, "Ignore scan points up to 15m. Requires layer_range_reduction = lower 4 reduced.", False)
78  sick_ldmrs_driver::param<bool> (nh, "sensitivity_control", sensitivity_control, false ); // gen.add("sensitivity_control", bool_t, 0, "Reduce the sensitivity automatically in case of extraneous light.", False)
79  // FlexRes parameters
80  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle1", flexres_start_angle1, 0.872664); // gen.add("flexres_start_angle1", double_t, 0, "FlexRes: start angle of sector 1.", 1600 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
81  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle2", flexres_start_angle2, 0.610865); // gen.add("flexres_start_angle2", double_t, 0, "FlexRes: start angle of sector 2.", 1120 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
82  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle3", flexres_start_angle3, 0.523598); // gen.add("flexres_start_angle3", double_t, 0, "FlexRes: start angle of sector 3.", 960 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
83  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle4", flexres_start_angle4, 0.349065); // gen.add("flexres_start_angle4", double_t, 0, "FlexRes: start angle of sector 4.", 640 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
84  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle5", flexres_start_angle5, 0.000000); // gen.add("flexres_start_angle5", double_t, 0, "FlexRes: start angle of sector 5.", 0 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
85  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle6", flexres_start_angle6, -0.349065); // gen.add("flexres_start_angle6", double_t, 0, "FlexRes: start angle of sector 6.", -640 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
86  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle7", flexres_start_angle7, -0.523598); // gen.add("flexres_start_angle7", double_t, 0, "FlexRes: start angle of sector 7.", -960 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
87  sick_ldmrs_driver::param<double>(nh, "flexres_start_angle8", flexres_start_angle8, -0.698131); // gen.add("flexres_start_angle8", double_t, 0, "FlexRes: start angle of sector 8.", -1280 * tics2rad, -1918 * tics2rad, 1600 * tics2rad)
88  sick_ldmrs_driver::param<int> (nh, "flexres_resolution1", flexres_resolution1, 32 ); // gen.add("flexres_resolution1", int_t, 0, "FlexRes: angular resolution of sector 1.", 32, 4, 32, edit_method=resolution_enum)
89  sick_ldmrs_driver::param<int> (nh, "flexres_resolution2", flexres_resolution2, 16 ); // gen.add("flexres_resolution2", int_t, 0, "FlexRes: angular resolution of sector 2.", 16, 4, 32, edit_method=resolution_enum)
90  sick_ldmrs_driver::param<int> (nh, "flexres_resolution3", flexres_resolution3, 8 ); // gen.add("flexres_resolution3", int_t, 0, "FlexRes: angular resolution of sector 3.", 8, 4, 32, edit_method=resolution_enum)
91  sick_ldmrs_driver::param<int> (nh, "flexres_resolution4", flexres_resolution4, 4 ); // gen.add("flexres_resolution4", int_t, 0, "FlexRes: angular resolution of sector 4.", 4, 4, 32, edit_method=resolution_enum)
92  sick_ldmrs_driver::param<int> (nh, "flexres_resolution5", flexres_resolution5, 8 ); // gen.add("flexres_resolution5", int_t, 0, "FlexRes: angular resolution of sector 5.", 8, 4, 32, edit_method=resolution_enum)
93  sick_ldmrs_driver::param<int> (nh, "flexres_resolution6", flexres_resolution6, 16 ); // gen.add("flexres_resolution6", int_t, 0, "FlexRes: angular resolution of sector 6.", 16, 4, 32, edit_method=resolution_enum)
94  sick_ldmrs_driver::param<int> (nh, "flexres_resolution7", flexres_resolution7, 32 ); // gen.add("flexres_resolution7", int_t, 0, "FlexRes: angular resolution of sector 7.", 32, 4, 32, edit_method=resolution_enum)
95  sick_ldmrs_driver::param<int> (nh, "flexres_resolution8", flexres_resolution8, 16 ); // gen.add("flexres_resolution8", int_t, 0, "FlexRes: angular resolution of sector 8.", 16, 4, 32, edit_method=resolution_enum)
96  // Object tracking parameters
97  sick_ldmrs_driver::param<int>(nh, "contour_point_density", contour_point_density, 2); // 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)
98  sick_ldmrs_driver::param<int>(nh, "min_object_age", min_object_age, 0); // gen.add("min_object_age", int_t, 0, "Minimum tracking age (number of scans) of an object to be transmitted.", 0, 0, 65535)
99  sick_ldmrs_driver::param<int>(nh, "max_prediction_age", max_prediction_age, 0); // gen.add("max_prediction_age", int_t, 0, "Maximum prediction age (number of scans) of an object to be transmitted.", 0, 0, 65535)
100  }
101 }
102 
103 #define SET_PARAMETER(param_name,parameter,name,value) if(name==param_name){ parameter = value; return true; }
104 
105 bool sick_ldmrs_driver::SickLDMRSDriverConfig::set_parameter(const std::string & name, const bool & value)
106 {
107  SET_PARAMETER("ignore_near_range", ignore_near_range, name, value);
108  SET_PARAMETER("sensitivity_control", sensitivity_control, name, value);
109  return false;
110 }
111 
112 bool sick_ldmrs_driver::SickLDMRSDriverConfig::set_parameter(const std::string & name, const int64_t & value)
113 {
114  SET_PARAMETER("angular_resolution_type", angular_resolution_type, name, value);
115  SET_PARAMETER("layer_range_reduction", layer_range_reduction, name, value);
116  SET_PARAMETER("flexres_resolution1", flexres_resolution1, name, value);
117  SET_PARAMETER("flexres_resolution2", flexres_resolution2, name, value);
118  SET_PARAMETER("flexres_resolution3", flexres_resolution3, name, value);
119  SET_PARAMETER("flexres_resolution4", flexres_resolution4, name, value);
120  SET_PARAMETER("flexres_resolution5", flexres_resolution5, name, value);
121  SET_PARAMETER("flexres_resolution6", flexres_resolution6, name, value);
122  SET_PARAMETER("flexres_resolution7", flexres_resolution7, name, value);
123  SET_PARAMETER("flexres_resolution8", flexres_resolution8, name, value);
124  SET_PARAMETER("contour_point_density", contour_point_density, name, value);
125  SET_PARAMETER("min_object_age", min_object_age, name, value);
126  SET_PARAMETER("max_prediction_age", max_prediction_age, name, value);
127  return false;
128 }
129 
130 bool sick_ldmrs_driver::SickLDMRSDriverConfig::set_parameter(const std::string & name, const double & value)
131 {
132  SET_PARAMETER("start_angle", start_angle, name, value);
133  SET_PARAMETER("end_angle", end_angle, name, value);
134  SET_PARAMETER("sync_angle_offset", sync_angle_offset, name, value);
135  SET_PARAMETER("flexres_start_angle1", flexres_start_angle1, name, value);
136  SET_PARAMETER("flexres_start_angle2", flexres_start_angle2, name, value);
137  SET_PARAMETER("flexres_start_angle3", flexres_start_angle3, name, value);
138  SET_PARAMETER("flexres_start_angle4", flexres_start_angle4, name, value);
139  SET_PARAMETER("flexres_start_angle5", flexres_start_angle5, name, value);
140  SET_PARAMETER("flexres_start_angle6", flexres_start_angle6, name, value);
141  SET_PARAMETER("flexres_start_angle7", flexres_start_angle7, name, value);
142  SET_PARAMETER("flexres_start_angle8", flexres_start_angle8, name, value);
143  return false;
144 }
145 
146 bool sick_ldmrs_driver::SickLDMRSDriverConfig::set_parameter(const std::string & name, const std::string & value)
147 {
148  SET_PARAMETER("frame_id", frame_id, name, value);
149  return false;
150 }
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::frame_id
std::string frame_id
Definition: sick_ldmrs_config.hpp:154
sick_ldmrs_driver::SickLDMRSDriverConfig::ignore_near_range
bool ignore_near_range
Definition: sick_ldmrs_config.hpp:162
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_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::flexres_resolution1
int flexres_resolution1
Definition: sick_ldmrs_config.hpp:174
api.setup.name
name
Definition: python/api/setup.py:12
sick_ldmrs_driver::SickLDMRSDriverConfig::start_angle
double start_angle
Definition: sick_ldmrs_config.hpp:156
sick_ldmrs_config.hpp
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle7
double flexres_start_angle7
Definition: sick_ldmrs_config.hpp:172
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::NodeHandle
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle1
double flexres_start_angle1
Definition: sick_ldmrs_config.hpp:166
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::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::SickLDMRSDriverConfig::layer_range_reduction
int layer_range_reduction
Definition: sick_ldmrs_config.hpp:161
SET_PARAMETER
#define SET_PARAMETER(param_name, parameter, name, value)
Definition: sick_ldmrs_config.cpp:103
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_start_angle3
double flexres_start_angle3
Definition: sick_ldmrs_config.hpp:168
sick_ldmrs_driver::SickLDMRSDriverConfig::angular_resolution_type
int angular_resolution_type
Definition: sick_ldmrs_config.hpp:160
sick_ldmrs_driver::SickLDMRSDriverConfig::flexres_resolution2
int flexres_resolution2
Definition: sick_ldmrs_config.hpp:175
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::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