config.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  * @brief config.h implements the configuration (yaml, commandline and default parameters) for project sick_scansegment_xd.
4  *
5  * Copyright (C) 2020 Ing.-Buero Dr. Michael Lehning, Hildesheim
6  * Copyright (C) 2020 SICK AG, Waldkirch
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13  *
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
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 SICK AG 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 Ing.-Buero Dr. Michael Lehning 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  *
37  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
38  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
39  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
40  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
41  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
42  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
43  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
44  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
45  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
46  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
47  * POSSIBILITY OF SUCH DAMAGE.
48  *
49  * Authors:
50  * Michael Lehning <michael.lehning@lehning.de>
51  *
52  * Copyright 2020 SICK AG
53  * Copyright 2020 Ing.-Buero Dr. Michael Lehning
54  *
55  */
56 #ifndef __SICK_SCANSEGMENT_XD_CONFIG_H
57 #define __SICK_SCANSEGMENT_XD_CONFIG_H
58 
63 
64 namespace sick_scansegment_xd
65 {
66  /*
67  * @brief Container for filter settings for msgpack validator, returned from by queryMultiScanFiltersettings()
68  */
70  {
71  public:
72  std::vector<int> msgpack_validator_required_echos; // { 0, 1, 2 }
73  float msgpack_validator_azimuth_start; // default for full scan: -M_PI;
74  float msgpack_validator_azimuth_end; // default for full scan: +M_PI;
75  float msgpack_validator_elevation_start; // default for full scan: -M_PI/2.0;
76  float msgpack_validator_elevation_end; // default for full scan: +M_PI/2.0;
77  std::vector<int> msgpack_validator_layer_filter; // default for full scan: 16 layer active, i.e. { 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 }
78  };
79 
80  /*
81  * @brief class sick_scansegment_xd::Config implements the configuration
82  * (yaml, commandline and default parameters) for project sick_scansegment_xd.
83  */
84  class Config
85  {
86  public:
87 
89  static bool SystemIsBigEndian(void);
90 
91  /*
92  * @brief Default constructor, initializes the configuration with default values
93  */
94  Config();
95 
96  /*
97  * @brief Destructor
98  */
99  ~Config();
100 
101  /*
102  * @brief Initializes sick_scansegment_xd configuration by commandline arguments and yaml-file.
103  */
104  bool Init(int argc, char** argv);
105 
106  /*
107  * @brief Initializes sick_scansegment_xd configuration
108  * @param[in] node ROS node handle (always 0 on non-ros-targets)
109  */
110  bool Init(rosNodePtr node);
111 
112  /*
113  * @brief Prints the commandline arguments.
114  */
115  void PrintHelp(void);
116 
117  /*
118  * @brief Prints the current settings.
119  */
120  void PrintConfig(void);
121 
122  /*
123  * sick_scansegment_xd configuration
124  */
125 
126  std::string scanner_type; // currently supported: "sick_multiscan" and "sick_picoscan"
127 
128  std::string udp_sender; // = ""; // Use "" (default) to receive msgpacks from any udp sender, use "127.0.0.1" to restrict to localhost (loopback device), or use the ip-address of a Multiscan136 lidar or Multiscan136 emulator
129  int udp_port; // = 2115; // default udp port for multiScan136 resp. multiScan136 emulator is 2115
130 
131  bool check_udp_receiver_ip = false; // check udp_receiver_ip by sending and receiving a udp test message
132  int check_udp_receiver_port = 2116; // udp port to check udp_receiver_ip
133 
134  double all_segments_min_deg = -180; // -180 // angle range covering all segments: all segments pointcloud on topic publish_topic_all_segments is published,
135  double all_segments_max_deg = +180; // +180 // if received segments cover angle range from all_segments_min_deg to all_segments_max_deg. -180...+180 for MultiScan136 (360 deg fullscan)
136 
137  std::string publish_frame_id; // = "world"; // frame id of ros Laserscan messages, default: "world"
138  std::string publish_laserscan_segment_topic; // topic of ros Laserscan segment messages
139  std::string publish_laserscan_fullframe_topic; //topic of ros Laserscan fullframe messages
140  int udp_input_fifolength; // = 20; // max. udp input fifo length(-1: unlimited, default: 20 for buffering 1 second at 20 Hz), elements will be removed from front if number of elements exceeds the fifo_length
141  int msgpack_output_fifolength; // = 20; // max. msgpack output fifo length(-1: unlimited, default: 20 for buffering 1 second at 20 Hz), elements will be removed from front if number of elements exceeds the fifo_length
142  int verbose_level; // = 1; // verbose_level <= 0: quiet mode, verbose_level == 1: print statistics, verbose_level == 2: print details incl. msgpack data, default: 1
143  bool measure_timing; // = true; // measure_timing == true: duration and latency of msgpack conversion and export is measured, default: true
144  bool export_csv; // = false; // export msgpack data to csv file, default: false
145  bool export_udp_msg; // = false; // true : export binary udpand msgpack data to file(*.udp and* .msg), default: false
146  std::string logfolder; // = "./logfiles"; // output folder for logfiles, default: "."
147  std::string hostname; // IP address of multiScan136 to post start and stop commands
148  std::string udp_receiver_ip; // UDP destination IP address (ip address of udp receiver)
149  // int port; // IP port of multiScan136 to post start and stop commands
150  // bool send_udp_start; // Send udp start string to multiScan136, default: False (obsolete)
151  // std::string send_udp_start_string; // udp string to start multiScan136, default: "magicalActivate"
152  int udp_timeout_ms; // Timeout for udp messages in milliseconds, default: 10*1000
153  int udp_timeout_ms_initial; // Initial timeout for udp messages after start in milliseconds, default: 60*1000
154  int scandataformat; // ScanDataFormat: 1 for msgpack or 2 for compact scandata, default: 1
155  int performanceprofilenumber; // Set performance profile by sending "sWN PerformanceProfileNumber" if performanceprofilenumber >= 0 (picoScan), default: -1
156  bool imu_enable; // IMU enabled or disabled
157  std::string imu_topic; // ROS topic for IMU messages
158  int imu_udp_port; // default udp port for multiScan imu data is 7503
159  int imu_latency_microsec; // imu latency in microseconds
160 
161  // SOPAS settings
162  std::string sopas_tcp_port; // TCP port for SOPAS commands, default port: 2111
163  bool start_sopas_service; // True: sopas services for CoLa-commands are started (ROS only), default: true
164  bool send_sopas_start_stop_cmd; // True: multiScan136 start and stop command sequece ("sWN ScanDataEnable 0/1" etc.) are sent after driver start and stop, default: true
165  bool sopas_cola_binary; // False: SOPAS uses CoLa-A (ascii, default, recommended), CoLa-B (true, binary) currently experimental
166  int sopas_timeout_ms; // Timeout for SOPAS response in milliseconds, default: 5000
167  std::string client_authorization_pw = "F4724744"; // Default password for client authorization
168 
169  // MSR100 filter settings
170  bool host_read_filtersettings; // True // Read multiScan136 settings for FREchoFilter, LFPangleRangeFilter and LFPlayerFilter at startup, default: true
171  int host_FREchoFilter; // 1 // Optionally set FREchoFilter with 0 for FIRST_ECHO (EchoCount=1), 1 for ALL_ECHOS (EchoCount=3), or 2 for LAST_ECHO (EchoCount=1)
172  bool host_set_FREchoFilter; // False // If true, FREchoFilter is set at startup (default: false)
173  std::string host_LFPangleRangeFilter; // "0 -180.0 +180.0 -90.0 +90.0 1" // Optionally set LFPangleRangeFilter to "<enabled> <azimuth_start> <azimuth_stop> <elevation_start> <elevation_stop> <beam_increment>" with azimuth and elevation given in degree
174  bool host_set_LFPangleRangeFilter; // False // If true, LFPangleRangeFilter is set at startup (default: false)
175  std::string host_LFPlayerFilter; // "0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1" (Multiscan136 only, not for picoscan) // Optionally set LFPlayerFilter to "<enabled> <layer0-enabled> <layer1-enabled> <layer2-enabled> ... <layer15-enabled>" with 1 for enabled and 0 for disabled
176  bool host_set_LFPlayerFilter; // False // If true (Multiscan136 only, always false for picoscan), LFPlayerFilter is set at startup (default: false)
177  std::string host_LFPintervalFilter; // "0 0" (Multiscan136 only, not for picoscan) // OOptionally set LFPintervalFilter to "<enabled> <N>" with 1 for enabled and 0 for disabled and N to reduce output to every N-th scan
178  bool host_set_LFPintervalFilter; // False // If true (Multiscan136 only, always false for picoscan), LFPintervalFilter is set at startup (default: false)
179  // msgpack validation
180  bool msgpack_validator_enabled; // true: check msgpack data for out of bounds and missing scan data, false: no msgpack validation
181  int msgpack_validator_verbose; // 0: print error messages, 1: print error and informational messages, 2: print error and all messages
182  bool msgpack_validator_discard_msgpacks_out_of_bounds; // true: msgpacks are discarded if scan data out of bounds detected, false: error message if a msgpack is not validated
183  int msgpack_validator_check_missing_scandata_interval; // check msgpack for missing scandata after collecting N msgpacks, default: N = 12 segments. Increase this value to tolerate udp packet drops. Use 12 to check each full scan.
184  MsgpackValidatorFilterConfig msgpack_validator_filter_settings; // required_echos, azimuth_start, azimuth_end. elevation_start, elevation_end, layer_filter
185  std::vector<int> msgpack_validator_valid_segments; // indices of valid segmentes, default for full scan: 12 segments, i.e. { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11 }
186 
187  // Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform)
189 
190  // Configuration of laserscan messages (ROS only), activate/deactivate laserscan messages for each layer
191  std::vector<int> laserscan_layer_filter; // Default: { 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }, i.e. laserscan messages for layer 5 activated (elevation -0.07 degree, max number of scan points)
192 
193  rosNodePtr node; // NodePtr node; // ROS node handle (always 0 on non-ros-targets)
194 
195  }; // class Config
196 
197  /*
198  * @brief Config utility functions
199  */
200  namespace util
201  {
202 
204  inline void parseVector(const std::string str, std::vector<std::string>& vec, char delim = ' ')
205  {
206  vec.clear();
207  std::istringstream in_stream(str);
208  std::string token;
209  while (std::getline(in_stream, token, delim))
210  {
211  vec.push_back(token);
212  }
213  }
214 
216  inline void parseVector(const std::string str, std::vector<float>& vec, char delim = ' ')
217  {
218  vec.clear();
219  std::vector<std::string> token;
220  sick_scansegment_xd::util::parseVector(str, token, delim);
221  for(int n = 0; n < token.size(); n++)
222  vec.push_back(std::stof(token[n]));
223  }
224 
226  inline void parseVector(const std::string str, std::vector<int>& vec, char delim = ' ')
227  {
228  vec.clear();
229  std::vector<std::string> token;
230  sick_scansegment_xd::util::parseVector(str, token, delim);
231  for(int n = 0; n < token.size(); n++)
232  vec.push_back(std::stoi(token[n]));
233  }
234 
236  template <typename T> inline std::string printVector(const std::vector<T>& vec, const std::string& delim = " ")
237  {
238  std::stringstream s;
239  for(int n = 0; n < vec.size(); n++)
240  s << (n > 0 ? delim : "") << vec[n];
241  return s.str();
242  }
243 
244 
245  } // namespace util
246 
247 } // namespace sick_scansegment_xd
248 #endif // __SICK_SCANSEGMENT_XD_COMMON_H
common.h
sick_cloud_transform.h
sick_scansegment_xd::Config::msgpack_validator_verbose
int msgpack_validator_verbose
Definition: config.h:181
sick_scansegment_xd::Config::scandataformat
int scandataformat
Definition: config.h:154
sick_scansegment_xd::Config::~Config
~Config()
Definition: config.cpp:215
sick_scansegment_xd::Config::Init
bool Init(int argc, char **argv)
Definition: config.cpp:360
sick_scansegment_xd::Config::host_LFPintervalFilter
std::string host_LFPintervalFilter
Definition: config.h:177
sick_scansegment_xd::MsgpackValidatorFilterConfig::msgpack_validator_elevation_start
float msgpack_validator_elevation_start
Definition: config.h:75
sick_scansegment_xd::Config::msgpack_validator_filter_settings
MsgpackValidatorFilterConfig msgpack_validator_filter_settings
Definition: config.h:184
sick_scan_xd::SickCloudTransform
Definition: sick_cloud_transform.h:85
sick_scansegment_xd::Config::add_transform_xyz_rpy
sick_scan_xd::SickCloudTransform add_transform_xyz_rpy
Definition: config.h:188
sick_scansegment_xd::Config::msgpack_validator_enabled
bool msgpack_validator_enabled
Definition: config.h:180
sick_scansegment_xd::Config::host_set_LFPangleRangeFilter
bool host_set_LFPangleRangeFilter
Definition: config.h:174
sick_scansegment_xd::Config::check_udp_receiver_ip
bool check_udp_receiver_ip
Definition: config.h:131
s
XmlRpcServer s
sick_scansegment_xd::Config::imu_topic
std::string imu_topic
Definition: config.h:157
sick_scansegment_xd::MsgpackValidatorFilterConfig::msgpack_validator_required_echos
std::vector< int > msgpack_validator_required_echos
Definition: config.h:72
sick_scansegment_xd::Config::udp_sender
std::string udp_sender
Definition: config.h:128
sick_scansegment_xd
Definition: include/sick_scansegment_xd/common.h:138
sick_scansegment_xd::Config::msgpack_validator_discard_msgpacks_out_of_bounds
bool msgpack_validator_discard_msgpacks_out_of_bounds
Definition: config.h:182
sick_scansegment_xd::Config::publish_frame_id
std::string publish_frame_id
Definition: config.h:137
sick_scansegment_xd::util::parseVector
void parseVector(const std::string str, std::vector< std::string > &vec, char delim=' ')
Definition: config.h:204
sick_scansegment_xd::Config::verbose_level
int verbose_level
Definition: config.h:142
sick_scansegment_xd::Config::host_set_FREchoFilter
bool host_set_FREchoFilter
Definition: config.h:172
sick_scansegment_xd::util::printVector
std::string printVector(const std::vector< T > &vec, const std::string &delim=" ")
Definition: config.h:236
sick_scansegment_xd::Config::msgpack_output_fifolength
int msgpack_output_fifolength
Definition: config.h:141
sick_scansegment_xd::Config::Config
Config()
Definition: config.cpp:143
sick_scansegment_xd::Config::start_sopas_service
bool start_sopas_service
Definition: config.h:163
sick_range_filter.h
sick_scansegment_xd::Config::imu_latency_microsec
int imu_latency_microsec
Definition: config.h:159
sick_scansegment_xd::Config::all_segments_min_deg
double all_segments_min_deg
Definition: config.h:134
sick_scansegment_xd::Config::publish_laserscan_fullframe_topic
std::string publish_laserscan_fullframe_topic
Definition: config.h:139
sick_ros_wrapper.h
sick_scansegment_xd::Config::udp_timeout_ms_initial
int udp_timeout_ms_initial
Definition: config.h:153
sick_scansegment_xd::MsgpackValidatorFilterConfig
Definition: config.h:69
sick_scansegment_xd::Config::sopas_timeout_ms
int sopas_timeout_ms
Definition: config.h:166
sick_scansegment_xd::Config::sopas_tcp_port
std::string sopas_tcp_port
Definition: config.h:162
sick_scansegment_xd::Config::udp_timeout_ms
int udp_timeout_ms
Definition: config.h:152
sick_scansegment_xd::Config::imu_udp_port
int imu_udp_port
Definition: config.h:158
sick_scansegment_xd::Config::host_set_LFPintervalFilter
bool host_set_LFPintervalFilter
Definition: config.h:178
sick_scansegment_xd::Config::check_udp_receiver_port
int check_udp_receiver_port
Definition: config.h:132
sick_scansegment_xd::MsgpackValidatorFilterConfig::msgpack_validator_layer_filter
std::vector< int > msgpack_validator_layer_filter
Definition: config.h:77
sick_scansegment_xd::Config::host_LFPangleRangeFilter
std::string host_LFPangleRangeFilter
Definition: config.h:173
sick_scansegment_xd::Config::logfolder
std::string logfolder
Definition: config.h:146
sick_scansegment_xd::Config::host_read_filtersettings
bool host_read_filtersettings
Definition: config.h:170
sick_scansegment_xd::Config::node
rosNodePtr node
Definition: config.h:193
ros::NodeHandle
sick_scansegment_xd::Config
Definition: config.h:84
sick_scansegment_xd::Config::host_FREchoFilter
int host_FREchoFilter
Definition: config.h:171
sick_scansegment_xd::Config::host_LFPlayerFilter
std::string host_LFPlayerFilter
Definition: config.h:175
sick_scansegment_xd::Config::measure_timing
bool measure_timing
Definition: config.h:143
sick_scansegment_xd::Config::PrintHelp
void PrintHelp(void)
Definition: config.cpp:222
sick_scansegment_xd::Config::client_authorization_pw
std::string client_authorization_pw
Definition: config.h:167
sick_scansegment_xd::Config::performanceprofilenumber
int performanceprofilenumber
Definition: config.h:155
sick_scansegment_xd::Config::udp_receiver_ip
std::string udp_receiver_ip
Definition: config.h:148
sick_scansegment_xd::MsgpackValidatorFilterConfig::msgpack_validator_elevation_end
float msgpack_validator_elevation_end
Definition: config.h:76
sick_scansegment_xd::Config::scanner_type
std::string scanner_type
Definition: config.h:126
sick_scansegment_xd::Config::export_udp_msg
bool export_udp_msg
Definition: config.h:145
sick_scansegment_xd::Config::msgpack_validator_check_missing_scandata_interval
int msgpack_validator_check_missing_scandata_interval
Definition: config.h:183
sick_scan_base.h
sick_scansegment_xd::MsgpackValidatorFilterConfig::msgpack_validator_azimuth_start
float msgpack_validator_azimuth_start
Definition: config.h:73
sick_scansegment_xd::MsgpackValidatorFilterConfig::msgpack_validator_azimuth_end
float msgpack_validator_azimuth_end
Definition: config.h:74
sick_scansegment_xd::Config::send_sopas_start_stop_cmd
bool send_sopas_start_stop_cmd
Definition: config.h:164
sick_scansegment_xd::Config::laserscan_layer_filter
std::vector< int > laserscan_layer_filter
Definition: config.h:191
sick_scansegment_xd::Config::hostname
std::string hostname
Definition: config.h:147
sick_scansegment_xd::Config::host_set_LFPlayerFilter
bool host_set_LFPlayerFilter
Definition: config.h:176
sick_scansegment_xd::Config::udp_port
int udp_port
Definition: config.h:129
sick_scansegment_xd::Config::all_segments_max_deg
double all_segments_max_deg
Definition: config.h:135
sick_scansegment_xd::Config::imu_enable
bool imu_enable
Definition: config.h:156
sick_scansegment_xd::Config::msgpack_validator_valid_segments
std::vector< int > msgpack_validator_valid_segments
Definition: config.h:185
sick_scansegment_xd::Config::export_csv
bool export_csv
Definition: config.h:144
sick_scansegment_xd::Config::publish_laserscan_segment_topic
std::string publish_laserscan_segment_topic
Definition: config.h:138
sick_scansegment_xd::Config::SystemIsBigEndian
static bool SystemIsBigEndian(void)
Definition: config.cpp:127
sick_scansegment_xd::Config::PrintConfig
void PrintConfig(void)
Definition: config.cpp:483
sick_scansegment_xd::Config::sopas_cola_binary
bool sopas_cola_binary
Definition: config.h:165
sick_scansegment_xd::Config::udp_input_fifolength
int udp_input_fifolength
Definition: config.h:140


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