ros_wrapper.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 ros_wrapper encapsulates the ROS API and switches ROS specific implementation
4  * between ROS 1 and ROS 2.
5  *
6  * Copyright (C) 2020 Ing.-Buero Dr. Michael Lehning, Hildesheim
7  * Copyright (C) 2020 SICK AG, Waldkirch
8  *
9  * Licensed under the Apache License, Version 2.0 (the "License");
10  * you may not use this file except in compliance with the License.
11  * You may obtain a copy of the License at
12  *
13  * http://www.apache.org/licenses/LICENSE-2.0
14  *
15  * Unless required by applicable law or agreed to in writing, software
16  * distributed under the License is distributed on an "AS IS" BASIS,
17  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
18  * See the License for the specific language governing permissions and
19  * limitations under the License.
20  *
21  * All rights reserved.
22  *
23  * Redistribution and use in source and binary forms, with or without
24  * modification, are permitted provided that the following conditions are met:
25  *
26  * * Redistributions of source code must retain the above copyright
27  * notice, this list of conditions and the following disclaimer.
28  * * Redistributions in binary form must reproduce the above copyright
29  * notice, this list of conditions and the following disclaimer in the
30  * documentation and/or other materials provided with the distribution.
31  * * Neither the name of SICK AG nor the names of its
32  * contributors may be used to endorse or promote products derived from
33  * this software without specific prior written permission
34  * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
35  * contributors may be used to endorse or promote products derived from
36  * this software without specific prior written permission
37  *
38  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
39  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
40  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
41  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
42  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
43  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
44  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
45  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
46  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
47  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
48  * POSSIBILITY OF SUCH DAMAGE.
49  *
50  * Authors:
51  * Michael Lehning <michael.lehning@lehning.de>
52  *
53  * Copyright 2020 SICK AG
54  * Copyright 2020 Ing.-Buero Dr. Michael Lehning
55  *
56  */
57 #ifndef __SIM_LOC_ROS_WRAPPER_H_INCLUDED
58 #define __SIM_LOC_ROS_WRAPPER_H_INCLUDED
59 
60 #include <cfloat>
61 #include <chrono>
62 #include <future>
63 #include <memory>
64 
65 #if defined __ROS_VERSION && __ROS_VERSION == 0 // native Linux or Windows uses ros simu
67 #endif
68 
69 #if defined __ROS_VERSION && __ROS_VERSION <= 1
70 /*
71  * Support for ROS 1 API
72  */
73 #include <ros/ros.h>
74 #include <std_msgs/Header.h>
75 #include <geometry_msgs/Point.h>
77 #include <nav_msgs/Odometry.h>
79 #include <tf2/LinearMath/Quaternion.h>
80 #include <tf2_ros/transform_broadcaster.h>
81 
82 #define RCLCPP_DEBUG_STREAM(logger,msgstream) ROS_DEBUG_STREAM(msgstream)
83 #define RCLCPP_INFO_STREAM(logger,msgstream) ROS_INFO_STREAM(msgstream)
84 #define RCLCPP_WARN_STREAM(logger,msgstream) ROS_WARN_STREAM(msgstream)
85 #define RCLCPP_ERROR_STREAM(logger,msgstream) ROS_ERROR_STREAM(msgstream)
86 
87 // Message header
95 // Services supported in release 3 and later
110 // Services supported in release 4 and later
148 
149 namespace sick_scan_xd
150 {
151  /*
152  typedef sensor_msgs::PointCloud2 PointCloud2Msg;
153  typedef ros::Publisher PointCloud2MsgPublisher;
154 
155  typedef nav_msgs::Odometry OdomMsg;
156  typedef ros::Subscriber OdomMsgSubscriber;
157  */
158  typedef ros::Publisher SickLocResultPortTelegramMsgPublisher;
159  typedef ros::Publisher SickLocDiagnosticMsgPublisher;
160  typedef ros::Publisher SickLocResultPortTestcaseMsgPublisher;
161 
162  typedef ros::Subscriber SickLocResultPortTelegramMsgSubscriber;
163  typedef ros::Subscriber SickLocResultPortTestcaseMsgSubscriber;
164 
165  // Service types supported in release 3 and later
166  typedef ros::ServiceClient SickLocColaTelegramSrvClient;
167  typedef ros::ServiceServer SickLocColaTelegramSrvServer;
168  typedef ros::ServiceClient SickLocIsSystemReadySrvClient;
169  typedef ros::ServiceServer SickLocIsSystemReadySrvServer;
170  typedef ros::ServiceClient SickLocRequestResultDataSrvClient;
171  typedef ros::ServiceServer SickLocRequestResultDataSrvServer;
172  typedef ros::ServiceClient SickLocRequestTimestampSrvClient;
173  typedef ros::ServiceServer SickLocRequestTimestampSrvServer;
174  typedef ros::ServiceClient SickLocSetPoseSrvClient;
175  typedef ros::ServiceServer SickLocSetPoseSrvServer;
176  typedef ros::ServiceClient SickLocSetResultEndiannessSrvClient;
177  typedef ros::ServiceServer SickLocSetResultEndiannessSrvServer;
178  typedef ros::ServiceClient SickLocSetResultModeSrvClient;
179  typedef ros::ServiceServer SickLocSetResultModeSrvServer;
180  typedef ros::ServiceClient SickLocSetResultPortSrvClient;
181  typedef ros::ServiceServer SickLocSetResultPortSrvServer;
182  typedef ros::ServiceClient SickLocSetResultPoseEnabledSrvClient;
183  typedef ros::ServiceServer SickLocSetResultPoseEnabledSrvServer;
184  typedef ros::ServiceClient SickLocSetResultPoseIntervalSrvClient;
185  typedef ros::ServiceServer SickLocSetResultPoseIntervalSrvServer;
186  typedef ros::ServiceClient SickLocStartLocalizingSrvClient;
187  typedef ros::ServiceServer SickLocStartLocalizingSrvServer;
188  typedef ros::ServiceClient SickLocStateSrvClient;
189  typedef ros::ServiceServer SickLocStateSrvServer;
190  typedef ros::ServiceClient SickLocStopSrvClient;
191  typedef ros::ServiceServer SickLocStopSrvServer;
192  typedef ros::ServiceClient SickLocTimeSyncSrvClient;
193  typedef ros::ServiceServer SickLocTimeSyncSrvServer;
194  // Service types supported in release 4 and later
195  typedef ros::ServiceClient SickDevGetLidarConfigSrvClient;
196  typedef ros::ServiceServer SickDevGetLidarConfigSrvServer;
197  typedef ros::ServiceClient SickDevGetLidarIdentSrvClient;
198  typedef ros::ServiceServer SickDevGetLidarIdentSrvServer;
199  typedef ros::ServiceClient SickDevGetLidarStateSrvClient;
200  typedef ros::ServiceServer SickDevGetLidarStateSrvServer;
201  typedef ros::ServiceClient SickDevSetLidarConfigSrvClient;
202  typedef ros::ServiceServer SickDevSetLidarConfigSrvServer;
203  typedef ros::ServiceClient SickGetSoftwareVersionSrvClient;
204  typedef ros::ServiceServer SickGetSoftwareVersionSrvServer;
205  typedef ros::ServiceClient SickLocAutoStartActiveSrvClient;
206  typedef ros::ServiceServer SickLocAutoStartActiveSrvServer;
207  typedef ros::ServiceClient SickLocAutoStartSavePoseIntervalSrvClient;
208  typedef ros::ServiceServer SickLocAutoStartSavePoseIntervalSrvServer;
209  typedef ros::ServiceClient SickLocAutoStartSavePoseSrvClient;
210  typedef ros::ServiceServer SickLocAutoStartSavePoseSrvServer;
211  typedef ros::ServiceClient SickLocForceUpdateSrvClient;
212  typedef ros::ServiceServer SickLocForceUpdateSrvServer;
213  typedef ros::ServiceClient SickLocInitializePoseSrvClient;
214  typedef ros::ServiceServer SickLocInitializePoseSrvServer;
215  typedef ros::ServiceClient SickLocInitialPoseSrvClient;
216  typedef ros::ServiceServer SickLocInitialPoseSrvServer;
217  typedef ros::ServiceClient SickLocMapSrvClient;
218  typedef ros::ServiceServer SickLocMapSrvServer;
219  typedef ros::ServiceClient SickLocMapStateSrvClient;
220  typedef ros::ServiceServer SickLocMapStateSrvServer;
221  typedef ros::ServiceClient SickLocOdometryActiveSrvClient;
222  typedef ros::ServiceServer SickLocOdometryActiveSrvServer;
223  typedef ros::ServiceClient SickLocOdometryPortSrvClient;
224  typedef ros::ServiceServer SickLocOdometryPortSrvServer;
225  typedef ros::ServiceClient SickLocOdometryRestrictYMotionSrvClient;
226  typedef ros::ServiceServer SickLocOdometryRestrictYMotionSrvServer;
227  typedef ros::ServiceClient SickLocReflectorsForSupportActiveSrvClient;
228  typedef ros::ServiceServer SickLocReflectorsForSupportActiveSrvServer;
229  typedef ros::ServiceClient SickLocResultEndiannessSrvClient;
230  typedef ros::ServiceServer SickLocResultEndiannessSrvServer;
231  typedef ros::ServiceClient SickLocResultModeSrvClient;
232  typedef ros::ServiceServer SickLocResultModeSrvServer;
233  typedef ros::ServiceClient SickLocResultPortSrvClient;
234  typedef ros::ServiceServer SickLocResultPortSrvServer;
235  typedef ros::ServiceClient SickLocResultPoseIntervalSrvClient;
236  typedef ros::ServiceServer SickLocResultPoseIntervalSrvServer;
237  typedef ros::ServiceClient SickLocResultStateSrvClient;
238  typedef ros::ServiceServer SickLocResultStateSrvServer;
239  typedef ros::ServiceClient SickLocRingBufferRecordingActiveSrvClient;
240  typedef ros::ServiceServer SickLocRingBufferRecordingActiveSrvServer;
241  typedef ros::ServiceClient SickLocSaveRingBufferRecordingSrvClient;
242  typedef ros::ServiceServer SickLocSaveRingBufferRecordingSrvServer;
243  typedef ros::ServiceClient SickLocSetAutoStartActiveSrvClient;
244  typedef ros::ServiceServer SickLocSetAutoStartActiveSrvServer;
245  typedef ros::ServiceClient SickLocSetAutoStartSavePoseIntervalSrvClient;
246  typedef ros::ServiceServer SickLocSetAutoStartSavePoseIntervalSrvServer;
247  typedef ros::ServiceClient SickLocSetMapSrvClient;
248  typedef ros::ServiceServer SickLocSetMapSrvServer;
249  typedef ros::ServiceClient SickLocSetOdometryActiveSrvClient;
250  typedef ros::ServiceServer SickLocSetOdometryActiveSrvServer;
251  typedef ros::ServiceClient SickLocSetOdometryPortSrvClient;
252  typedef ros::ServiceServer SickLocSetOdometryPortSrvServer;
253  typedef ros::ServiceClient SickLocSetOdometryRestrictYMotionSrvClient;
254  typedef ros::ServiceServer SickLocSetOdometryRestrictYMotionSrvServer;
255  typedef ros::ServiceClient SickLocSetReflectorsForSupportActiveSrvClient;
256  typedef ros::ServiceServer SickLocSetReflectorsForSupportActiveSrvServer;
257  typedef ros::ServiceClient SickLocSetRingBufferRecordingActiveSrvClient;
258  typedef ros::ServiceServer SickLocSetRingBufferRecordingActiveSrvServer;
259  typedef ros::ServiceClient SickLocStartDemoMappingSrvClient;
260  typedef ros::ServiceServer SickLocStartDemoMappingSrvServer;
261  typedef ros::ServiceClient SickReportUserMessageSrvClient;
262  typedef ros::ServiceServer SickReportUserMessageSrvServer;
263  typedef ros::ServiceClient SickSavePermanentSrvClient;
264  typedef ros::ServiceServer SickSavePermanentSrvServer;
265  typedef ros::ServiceClient SickDevSetIMUActiveSrvClient;
266  typedef ros::ServiceServer SickDevSetIMUActiveSrvServer;
267  typedef ros::ServiceClient SickDevIMUActiveSrvClient;
268  typedef ros::ServiceServer SickDevIMUActiveSrvServer;
269 
270 } // namespace sick_scan_xd
271 
272 namespace ROS
273 {
274  using namespace ros; // map namespace ROS to ros in ROS1 and to rclcpp in ROS2, f.e. ROS::ok() to ROS::ok() in ROS1 and rclcpp::ok() in ROS2
275  typedef ros::NodeHandle* NodePtr;
276 
277  template<typename T> bool param(ROS::NodePtr & node, const std::string & param_name, T& value, const T& default_value)
278  {
279  #if __ROS_VERSION == 0
280  ROS_WARN_STREAM("ROS::param(" << param_name << "," << value << "," << default_value << ") not supported (__ROS_VERSION=" << __ROS_VERSION << ", ROS::param requires __ROS_VERSION > 0), set " << param_name << " to default value " << default_value);
281  value = default_value;
282  return false;
283  #else
284  return ros::param::param<T>(param_name, value, default_value);
285  #endif
286  }
287 
289  void spin(ROS:: NodePtr nh = 0);
290 
291 } // namespace ROS
292 
293 #define ROS_CREATE_SRV_CLIENT(nh,srv,name) nh->serviceClient<srv>(name)
294 #define ROS_CREATE_SRV_SERVER(nh,srv,name,cbfunction,cbobject) nh->advertiseService(name,cbfunction,cbobject)
295 
296 #define ROS_CREATE_PUBLISHER(nh,msgtype,topic) nh->advertise<msgtype>(topic,1);
297 #define ROS_PUBLISH(publisher,message) publisher.publish(message);
298 
299 #define ROS_CREATE_SUBSCRIBER(nh,msgtype,topic,cbfunction,cbobject) nh->subscribe(topic,1,cbfunction,cbobject)
300 
301 #define NSEC nsec // maps nanoseconds in std_msgs::Header::stamp to stamp.nsec in ROS1 resp. stamp.nanosec in ROS2
302 
303 #elif defined __ROS_VERSION && __ROS_VERSION == 2
304 /*
305  * Support for ROS 2 API
306  */
307 #include <rclcpp/rclcpp.hpp>
308 #include <rclcpp/executor.hpp>
309 #include <std_msgs/msg/header.hpp>
310 #include <geometry_msgs/msg/point.hpp>
311 #include <geometry_msgs/msg/transform_stamped.hpp>
312 #include <nav_msgs/msg/odometry.hpp>
313 #include <sensor_msgs/msg/point_cloud2.hpp>
314 #include <sensor_msgs/msg/laser_scan.hpp>
315 #include <tf2/LinearMath/Quaternion.h>
316 #include <tf2_ros/transform_broadcaster.h>
317 
318 #define ROS_DEBUG_STREAM(msgstream) RCLCPP_DEBUG_STREAM(rclcpp::get_logger("sick_scan_xd"),msgstream)
319 #define ROS_INFO_STREAM(msgstream) RCLCPP_INFO_STREAM(rclcpp::get_logger("sick_scan_xd"),msgstream)
320 #define ROS_WARN_STREAM(msgstream) RCLCPP_WARN_STREAM(rclcpp::get_logger("sick_scan_xd"),msgstream)
321 #define ROS_ERROR_STREAM(msgstream) RCLCPP_ERROR_STREAM(rclcpp::get_logger("sick_scan_xd"),msgstream)
322 
323 // Message header
324 #include "sick_scan_xd/msg/sick_loc_cola_telegram_msg.hpp"
325 #include "sick_scan_xd/msg/sick_loc_diagnostic_msg.hpp"
326 #include "sick_scan_xd/msg/sick_loc_result_port_crc_msg.hpp"
327 #include "sick_scan_xd/msg/sick_loc_result_port_header_msg.hpp"
328 #include "sick_scan_xd/msg/sick_loc_result_port_payload_msg.hpp"
329 #include "sick_scan_xd/msg/sick_loc_result_port_telegram_msg.hpp"
330 #include "sick_scan_xd/msg/sick_loc_result_port_testcase_msg.hpp"
331 // Services supported in release 3 and later
332 #include "sick_scan_xd/srv/sick_loc_cola_telegram_srv.hpp"
333 #include "sick_scan_xd/srv/sick_loc_is_system_ready_srv.hpp"
334 #include "sick_scan_xd/srv/sick_loc_request_result_data_srv.hpp"
335 #include "sick_scan_xd/srv/sick_loc_request_timestamp_srv.hpp"
336 #include "sick_scan_xd/srv/sick_loc_set_pose_srv.hpp"
337 #include "sick_scan_xd/srv/sick_loc_set_result_endianness_srv.hpp"
338 #include "sick_scan_xd/srv/sick_loc_set_result_mode_srv.hpp"
339 #include "sick_scan_xd/srv/sick_loc_set_result_port_srv.hpp"
340 #include "sick_scan_xd/srv/sick_loc_set_result_pose_enabled_srv.hpp"
341 #include "sick_scan_xd/srv/sick_loc_set_result_pose_interval_srv.hpp"
342 #include "sick_scan_xd/srv/sick_loc_start_localizing_srv.hpp"
343 #include "sick_scan_xd/srv/sick_loc_state_srv.hpp"
344 #include "sick_scan_xd/srv/sick_loc_stop_srv.hpp"
345 #include "sick_scan_xd/srv/sick_loc_time_sync_srv.hpp"
346 // Services supported in release 4 and later
347 #include "sick_scan_xd/srv/sick_dev_get_lidar_config_srv.hpp"
348 #include "sick_scan_xd/srv/sick_dev_get_lidar_ident_srv.hpp"
349 #include "sick_scan_xd/srv/sick_dev_get_lidar_state_srv.hpp"
350 #include "sick_scan_xd/srv/sick_dev_set_lidar_config_srv.hpp"
351 #include "sick_scan_xd/srv/sick_get_software_version_srv.hpp"
352 #include "sick_scan_xd/srv/sick_loc_auto_start_active_srv.hpp"
353 #include "sick_scan_xd/srv/sick_loc_auto_start_save_pose_interval_srv.hpp"
354 #include "sick_scan_xd/srv/sick_loc_auto_start_save_pose_srv.hpp"
355 #include "sick_scan_xd/srv/sick_loc_force_update_srv.hpp"
356 #include "sick_scan_xd/srv/sick_loc_initialize_pose_srv.hpp"
357 #include "sick_scan_xd/srv/sick_loc_initial_pose_srv.hpp"
358 #include "sick_scan_xd/srv/sick_loc_map_srv.hpp"
359 #include "sick_scan_xd/srv/sick_loc_map_state_srv.hpp"
360 #include "sick_scan_xd/srv/sick_loc_odometry_active_srv.hpp"
361 #include "sick_scan_xd/srv/sick_loc_odometry_port_srv.hpp"
362 #include "sick_scan_xd/srv/sick_loc_odometry_restrict_y_motion_srv.hpp"
363 #include "sick_scan_xd/srv/sick_loc_reflectors_for_support_active_srv.hpp"
364 #include "sick_scan_xd/srv/sick_loc_result_endianness_srv.hpp"
365 #include "sick_scan_xd/srv/sick_loc_result_mode_srv.hpp"
366 #include "sick_scan_xd/srv/sick_loc_result_port_srv.hpp"
367 #include "sick_scan_xd/srv/sick_loc_result_pose_interval_srv.hpp"
368 #include "sick_scan_xd/srv/sick_loc_result_state_srv.hpp"
369 #include "sick_scan_xd/srv/sick_loc_ring_buffer_recording_active_srv.hpp"
370 #include "sick_scan_xd/srv/sick_loc_save_ring_buffer_recording_srv.hpp"
371 #include "sick_scan_xd/srv/sick_loc_set_auto_start_active_srv.hpp"
372 #include "sick_scan_xd/srv/sick_loc_set_auto_start_save_pose_interval_srv.hpp"
373 #include "sick_scan_xd/srv/sick_loc_set_map_srv.hpp"
374 #include "sick_scan_xd/srv/sick_loc_set_odometry_active_srv.hpp"
375 #include "sick_scan_xd/srv/sick_loc_set_odometry_port_srv.hpp"
376 #include "sick_scan_xd/srv/sick_loc_set_odometry_restrict_y_motion_srv.hpp"
377 #include "sick_scan_xd/srv/sick_loc_set_reflectors_for_support_active_srv.hpp"
378 #include "sick_scan_xd/srv/sick_loc_set_ring_buffer_recording_active_srv.hpp"
379 #include "sick_scan_xd/srv/sick_loc_start_demo_mapping_srv.hpp"
380 #include "sick_scan_xd/srv/sick_report_user_message_srv.hpp"
381 #include "sick_scan_xd/srv/sick_save_permanent_srv.hpp"
382 #include "sick_scan_xd/srv/sick_dev_set_imu_active_srv.hpp"
383 #include "sick_scan_xd/srv/sick_dev_imu_active_srv.hpp"
384 
385 namespace geometry_msgs
386 {
387  using namespace msg; // maps ROS2-namespace geometry_msgs::msg to ROS1-namespace geometry_msgs, f.e. geometry_msgs::Point works on both ROS1 and ROS2
388 }
389 
390 namespace sensor_msgs
391 {
392  using namespace msg; // maps ROS2-namespace sensor_msgs::msg to ROS1-namespace sensor_msgs, f.e. sensor_msgs::PointCloud2 works on both ROS1 and ROS2
393 }
394 
395 namespace nav_msgs
396 {
397  using namespace msg; // maps ROS2-namespace nav_msgs::msg to ROS1-namespace nav_msgs, f.e. nav_msgs::Odometry works on both ROS1 and ROS2
398 }
399 
400 namespace std_msgs
401 {
402  using namespace msg; // maps ROS2-namespace std_msgs::msg to ROS1-namespace std_msgs, f.e. std_msgs::Header works on both ROS1 and ROS2
403 }
404 
405 namespace sick_scan_xd
406 {
407  using namespace msg;
408  using namespace srv;
409 
411  typedef rclcpp::Publisher<PointCloud2Msg>::SharedPtr PointCloud2MsgPublisher;
412 
414  typedef rclcpp::Publisher<LaserScanMsg>::SharedPtr LaserscanMsgPublisher;
415 
416  typedef nav_msgs::msg::Odometry OdomMsg;
417  typedef rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr OdomMsgSubscriber;
418 
419  typedef rclcpp::Publisher<sick_scan_xd::SickLocResultPortTelegramMsg>::SharedPtr SickLocResultPortTelegramMsgPublisher;
420  typedef rclcpp::Publisher<sick_scan_xd::SickLocDiagnosticMsg>::SharedPtr SickLocDiagnosticMsgPublisher;
421  typedef rclcpp::Publisher<sick_scan_xd::SickLocResultPortTestcaseMsg>::SharedPtr SickLocResultPortTestcaseMsgPublisher;
422 
423  typedef rclcpp::Subscription<sick_scan_xd::SickLocResultPortTelegramMsg>::SharedPtr SickLocResultPortTelegramMsgSubscriber;
424  typedef rclcpp::Subscription<sick_scan_xd::SickLocResultPortTestcaseMsg>::SharedPtr SickLocResultPortTestcaseMsgSubscriber;
425 
426  // Service types supported in release 3 and later
427  typedef rclcpp::Client<sick_scan_xd::SickLocColaTelegramSrv>::SharedPtr SickLocColaTelegramSrvClient;
428  typedef rclcpp::Service<sick_scan_xd::SickLocColaTelegramSrv>::SharedPtr SickLocColaTelegramSrvServer;
429  typedef rclcpp::Client<sick_scan_xd::SickLocIsSystemReadySrv>::SharedPtr SickLocIsSystemReadySrvClient;
430  typedef rclcpp::Service<sick_scan_xd::SickLocIsSystemReadySrv>::SharedPtr SickLocIsSystemReadySrvServer;
431  typedef rclcpp::Client<sick_scan_xd::SickLocRequestResultDataSrv>::SharedPtr SickLocRequestResultDataSrvClient;
432  typedef rclcpp::Service<sick_scan_xd::SickLocRequestResultDataSrv>::SharedPtr SickLocRequestResultDataSrvServer;
433  typedef rclcpp::Client<sick_scan_xd::SickLocRequestTimestampSrv>::SharedPtr SickLocRequestTimestampSrvClient;
434  typedef rclcpp::Service<sick_scan_xd::SickLocRequestTimestampSrv>::SharedPtr SickLocRequestTimestampSrvServer;
435  typedef rclcpp::Client<sick_scan_xd::SickLocSetPoseSrv>::SharedPtr SickLocSetPoseSrvClient;
436  typedef rclcpp::Service<sick_scan_xd::SickLocSetPoseSrv>::SharedPtr SickLocSetPoseSrvServer;
437  typedef rclcpp::Client<sick_scan_xd::SickLocSetResultEndiannessSrv>::SharedPtr SickLocSetResultEndiannessSrvClient;
438  typedef rclcpp::Service<sick_scan_xd::SickLocSetResultEndiannessSrv>::SharedPtr SickLocSetResultEndiannessSrvServer;
439  typedef rclcpp::Client<sick_scan_xd::SickLocSetResultModeSrv>::SharedPtr SickLocSetResultModeSrvClient;
440  typedef rclcpp::Service<sick_scan_xd::SickLocSetResultModeSrv>::SharedPtr SickLocSetResultModeSrvServer;
441  typedef rclcpp::Client<sick_scan_xd::SickLocSetResultPortSrv>::SharedPtr SickLocSetResultPortSrvClient;
442  typedef rclcpp::Service<sick_scan_xd::SickLocSetResultPortSrv>::SharedPtr SickLocSetResultPortSrvServer;
443  typedef rclcpp::Client<sick_scan_xd::SickLocSetResultPoseEnabledSrv>::SharedPtr SickLocSetResultPoseEnabledSrvClient;
444  typedef rclcpp::Service<sick_scan_xd::SickLocSetResultPoseEnabledSrv>::SharedPtr SickLocSetResultPoseEnabledSrvServer;
445  typedef rclcpp::Client<sick_scan_xd::SickLocSetResultPoseIntervalSrv>::SharedPtr SickLocSetResultPoseIntervalSrvClient;
446  typedef rclcpp::Service<sick_scan_xd::SickLocSetResultPoseIntervalSrv>::SharedPtr SickLocSetResultPoseIntervalSrvServer;
447  typedef rclcpp::Client<sick_scan_xd::SickLocStartLocalizingSrv>::SharedPtr SickLocStartLocalizingSrvClient;
448  typedef rclcpp::Service<sick_scan_xd::SickLocStartLocalizingSrv>::SharedPtr SickLocStartLocalizingSrvServer;
449  typedef rclcpp::Client<sick_scan_xd::SickLocStateSrv>::SharedPtr SickLocStateSrvClient;
450  typedef rclcpp::Service<sick_scan_xd::SickLocStateSrv>::SharedPtr SickLocStateSrvServer;
451  typedef rclcpp::Client<sick_scan_xd::SickLocStopSrv>::SharedPtr SickLocStopSrvClient;
452  typedef rclcpp::Service<sick_scan_xd::SickLocStopSrv>::SharedPtr SickLocStopSrvServer;
453  typedef rclcpp::Client<sick_scan_xd::SickLocTimeSyncSrv>::SharedPtr SickLocTimeSyncSrvClient;
454  typedef rclcpp::Service<sick_scan_xd::SickLocTimeSyncSrv>::SharedPtr SickLocTimeSyncSrvServer;
455  // Service types supported in release 4 and later
456  typedef rclcpp::Client <sick_scan_xd::SickDevGetLidarConfigSrv>::SharedPtr SickDevGetLidarConfigSrvClient;
457  typedef rclcpp::Service<sick_scan_xd::SickDevGetLidarConfigSrv>::SharedPtr SickDevGetLidarConfigSrvServer;
458  typedef rclcpp::Client <sick_scan_xd::SickDevGetLidarIdentSrv>::SharedPtr SickDevGetLidarIdentSrvClient;
459  typedef rclcpp::Service<sick_scan_xd::SickDevGetLidarIdentSrv>::SharedPtr SickDevGetLidarIdentSrvServer;
460  typedef rclcpp::Client <sick_scan_xd::SickDevGetLidarStateSrv>::SharedPtr SickDevGetLidarStateSrvClient;
461  typedef rclcpp::Service<sick_scan_xd::SickDevGetLidarStateSrv>::SharedPtr SickDevGetLidarStateSrvServer;
462  typedef rclcpp::Client <sick_scan_xd::SickDevSetLidarConfigSrv>::SharedPtr SickDevSetLidarConfigSrvClient;
463  typedef rclcpp::Service<sick_scan_xd::SickDevSetLidarConfigSrv>::SharedPtr SickDevSetLidarConfigSrvServer;
464  typedef rclcpp::Client <sick_scan_xd::SickGetSoftwareVersionSrv>::SharedPtr SickGetSoftwareVersionSrvClient;
465  typedef rclcpp::Service<sick_scan_xd::SickGetSoftwareVersionSrv>::SharedPtr SickGetSoftwareVersionSrvServer;
466  typedef rclcpp::Client <sick_scan_xd::SickLocAutoStartActiveSrv>::SharedPtr SickLocAutoStartActiveSrvClient;
467  typedef rclcpp::Service<sick_scan_xd::SickLocAutoStartActiveSrv>::SharedPtr SickLocAutoStartActiveSrvServer;
468  typedef rclcpp::Client <sick_scan_xd::SickLocAutoStartSavePoseIntervalSrv>::SharedPtr SickLocAutoStartSavePoseIntervalSrvClient;
469  typedef rclcpp::Service<sick_scan_xd::SickLocAutoStartSavePoseIntervalSrv>::SharedPtr SickLocAutoStartSavePoseIntervalSrvServer;
470  typedef rclcpp::Client <sick_scan_xd::SickLocAutoStartSavePoseSrv>::SharedPtr SickLocAutoStartSavePoseSrvClient;
471  typedef rclcpp::Service<sick_scan_xd::SickLocAutoStartSavePoseSrv>::SharedPtr SickLocAutoStartSavePoseSrvServer;
472  typedef rclcpp::Client <sick_scan_xd::SickLocForceUpdateSrv>::SharedPtr SickLocForceUpdateSrvClient;
473  typedef rclcpp::Service<sick_scan_xd::SickLocForceUpdateSrv>::SharedPtr SickLocForceUpdateSrvServer;
474  typedef rclcpp::Client <sick_scan_xd::SickLocInitializePoseSrv>::SharedPtr SickLocInitializePoseSrvClient;
475  typedef rclcpp::Service<sick_scan_xd::SickLocInitializePoseSrv>::SharedPtr SickLocInitializePoseSrvServer;
476  typedef rclcpp::Client <sick_scan_xd::SickLocInitialPoseSrv>::SharedPtr SickLocInitialPoseSrvClient;
477  typedef rclcpp::Service<sick_scan_xd::SickLocInitialPoseSrv>::SharedPtr SickLocInitialPoseSrvServer;
478  typedef rclcpp::Client <sick_scan_xd::SickLocMapSrv>::SharedPtr SickLocMapSrvClient;
479  typedef rclcpp::Service<sick_scan_xd::SickLocMapSrv>::SharedPtr SickLocMapSrvServer;
480  typedef rclcpp::Client <sick_scan_xd::SickLocMapStateSrv>::SharedPtr SickLocMapStateSrvClient;
481  typedef rclcpp::Service<sick_scan_xd::SickLocMapStateSrv>::SharedPtr SickLocMapStateSrvServer;
482  typedef rclcpp::Client <sick_scan_xd::SickLocOdometryActiveSrv>::SharedPtr SickLocOdometryActiveSrvClient;
483  typedef rclcpp::Service<sick_scan_xd::SickLocOdometryActiveSrv>::SharedPtr SickLocOdometryActiveSrvServer;
484  typedef rclcpp::Client <sick_scan_xd::SickLocOdometryPortSrv>::SharedPtr SickLocOdometryPortSrvClient;
485  typedef rclcpp::Service<sick_scan_xd::SickLocOdometryPortSrv>::SharedPtr SickLocOdometryPortSrvServer;
486  typedef rclcpp::Client <sick_scan_xd::SickLocOdometryRestrictYMotionSrv>::SharedPtr SickLocOdometryRestrictYMotionSrvClient;
487  typedef rclcpp::Service<sick_scan_xd::SickLocOdometryRestrictYMotionSrv>::SharedPtr SickLocOdometryRestrictYMotionSrvServer;
488  typedef rclcpp::Client <sick_scan_xd::SickLocReflectorsForSupportActiveSrv>::SharedPtr SickLocReflectorsForSupportActiveSrvClient;
489  typedef rclcpp::Service<sick_scan_xd::SickLocReflectorsForSupportActiveSrv>::SharedPtr SickLocReflectorsForSupportActiveSrvServer;
490  typedef rclcpp::Client <sick_scan_xd::SickLocResultEndiannessSrv>::SharedPtr SickLocResultEndiannessSrvClient;
491  typedef rclcpp::Service<sick_scan_xd::SickLocResultEndiannessSrv>::SharedPtr SickLocResultEndiannessSrvServer;
492  typedef rclcpp::Client <sick_scan_xd::SickLocResultModeSrv>::SharedPtr SickLocResultModeSrvClient;
493  typedef rclcpp::Service<sick_scan_xd::SickLocResultModeSrv>::SharedPtr SickLocResultModeSrvServer;
494  typedef rclcpp::Client <sick_scan_xd::SickLocResultPortSrv>::SharedPtr SickLocResultPortSrvClient;
495  typedef rclcpp::Service<sick_scan_xd::SickLocResultPortSrv>::SharedPtr SickLocResultPortSrvServer;
496  typedef rclcpp::Client <sick_scan_xd::SickLocResultPoseIntervalSrv>::SharedPtr SickLocResultPoseIntervalSrvClient;
497  typedef rclcpp::Service<sick_scan_xd::SickLocResultPoseIntervalSrv>::SharedPtr SickLocResultPoseIntervalSrvServer;
498  typedef rclcpp::Client <sick_scan_xd::SickLocResultStateSrv>::SharedPtr SickLocResultStateSrvClient;
499  typedef rclcpp::Service<sick_scan_xd::SickLocResultStateSrv>::SharedPtr SickLocResultStateSrvServer;
500  typedef rclcpp::Client <sick_scan_xd::SickLocRingBufferRecordingActiveSrv>::SharedPtr SickLocRingBufferRecordingActiveSrvClient;
501  typedef rclcpp::Service<sick_scan_xd::SickLocRingBufferRecordingActiveSrv>::SharedPtr SickLocRingBufferRecordingActiveSrvServer;
502  typedef rclcpp::Client <sick_scan_xd::SickLocSaveRingBufferRecordingSrv>::SharedPtr SickLocSaveRingBufferRecordingSrvClient;
503  typedef rclcpp::Service<sick_scan_xd::SickLocSaveRingBufferRecordingSrv>::SharedPtr SickLocSaveRingBufferRecordingSrvServer;
504  typedef rclcpp::Client <sick_scan_xd::SickLocSetAutoStartActiveSrv>::SharedPtr SickLocSetAutoStartActiveSrvClient;
505  typedef rclcpp::Service<sick_scan_xd::SickLocSetAutoStartActiveSrv>::SharedPtr SickLocSetAutoStartActiveSrvServer;
506  typedef rclcpp::Client <sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrv>::SharedPtr SickLocSetAutoStartSavePoseIntervalSrvClient;
507  typedef rclcpp::Service<sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrv>::SharedPtr SickLocSetAutoStartSavePoseIntervalSrvServer;
508  typedef rclcpp::Client <sick_scan_xd::SickLocSetMapSrv>::SharedPtr SickLocSetMapSrvClient;
509  typedef rclcpp::Service<sick_scan_xd::SickLocSetMapSrv>::SharedPtr SickLocSetMapSrvServer;
510  typedef rclcpp::Client <sick_scan_xd::SickLocSetOdometryActiveSrv>::SharedPtr SickLocSetOdometryActiveSrvClient;
511  typedef rclcpp::Service<sick_scan_xd::SickLocSetOdometryActiveSrv>::SharedPtr SickLocSetOdometryActiveSrvServer;
512  typedef rclcpp::Client <sick_scan_xd::SickLocSetOdometryPortSrv>::SharedPtr SickLocSetOdometryPortSrvClient;
513  typedef rclcpp::Service<sick_scan_xd::SickLocSetOdometryPortSrv>::SharedPtr SickLocSetOdometryPortSrvServer;
514  typedef rclcpp::Client <sick_scan_xd::SickLocSetOdometryRestrictYMotionSrv>::SharedPtr SickLocSetOdometryRestrictYMotionSrvClient;
515  typedef rclcpp::Service<sick_scan_xd::SickLocSetOdometryRestrictYMotionSrv>::SharedPtr SickLocSetOdometryRestrictYMotionSrvServer;
516  typedef rclcpp::Client <sick_scan_xd::SickLocSetReflectorsForSupportActiveSrv>::SharedPtr SickLocSetReflectorsForSupportActiveSrvClient;
517  typedef rclcpp::Service<sick_scan_xd::SickLocSetReflectorsForSupportActiveSrv>::SharedPtr SickLocSetReflectorsForSupportActiveSrvServer;
518  typedef rclcpp::Client <sick_scan_xd::SickLocSetRingBufferRecordingActiveSrv>::SharedPtr SickLocSetRingBufferRecordingActiveSrvClient;
519  typedef rclcpp::Service<sick_scan_xd::SickLocSetRingBufferRecordingActiveSrv>::SharedPtr SickLocSetRingBufferRecordingActiveSrvServer;
520  typedef rclcpp::Client <sick_scan_xd::SickLocStartDemoMappingSrv>::SharedPtr SickLocStartDemoMappingSrvClient;
521  typedef rclcpp::Service<sick_scan_xd::SickLocStartDemoMappingSrv>::SharedPtr SickLocStartDemoMappingSrvServer;
522  typedef rclcpp::Client <sick_scan_xd::SickReportUserMessageSrv>::SharedPtr SickReportUserMessageSrvClient;
523  typedef rclcpp::Service<sick_scan_xd::SickReportUserMessageSrv>::SharedPtr SickReportUserMessageSrvServer;
524  typedef rclcpp::Client <sick_scan_xd::SickSavePermanentSrv>::SharedPtr SickSavePermanentSrvClient;
525  typedef rclcpp::Service<sick_scan_xd::SickSavePermanentSrv>::SharedPtr SickSavePermanentSrvServer;
526  typedef rclcpp::Client <sick_scan_xd::SickDevSetIMUActiveSrv>::SharedPtr SickDevSetIMUActiveSrvClient;
527  typedef rclcpp::Service<sick_scan_xd::SickDevSetIMUActiveSrv>::SharedPtr SickDevSetIMUActiveSrvServer;
528  typedef rclcpp::Client <sick_scan_xd::SickDevIMUActiveSrv>::SharedPtr SickDevIMUActiveSrvClient;
529  typedef rclcpp::Service<sick_scan_xd::SickDevIMUActiveSrv>::SharedPtr SickDevIMUActiveSrvServer;
530 
531 } // namespace sick_scan_xd
532 
533 namespace ROS
534 {
535  using namespace rclcpp; // map namespace ROS to ros in ROS1 and to rclcpp in ROS2, f.e. ROS::ok() to ros::ok() in ROS1 and rclcpp::ok() in ROS2
536  typedef rclcpp::Node::SharedPtr NodePtr;
537 
538  template<typename T> bool param(ROS::NodePtr & node, const std::string & param_name, T& value, const T& default_value)
539  {
540  ROS_INFO_STREAM("ROS::param(" << node->get_name() << "," << param_name << "," << default_value << ")");
541  try
542  {
543  if(!node->has_parameter(param_name))
544  {
545  node->declare_parameter<T>(param_name, default_value);
546  }
547  }
548  catch(const std::exception& exc)
549  {
550  ROS_WARN_STREAM("## ERROR ROS::param: declare_parameter(" << param_name << "," << default_value << ") failed, exception " << exc.what());
551  }
552  try
553  {
554  return node->get_parameter(param_name, value);
555  }
556  catch(const std::exception& exc)
557  {
558  ROS_WARN_STREAM("## ERROR ROS::param: get_parameter(" << param_name << "," << default_value << ") failed, exception " << exc.what());
559  }
560  return false;
561  }
562 
564  void init(int argc, char** argv, const std::string nodename = "");
565 
566 } // namespace ROS
567 
568 #define ROS_CREATE_SRV_CLIENT(nh,srv,name) nh->create_client<srv>(name)
569 #define ROS_CREATE_SRV_SERVER(nh,srv,name,cbfunction,cbobject) nh->create_service<srv>(name,std::bind(cbfunction,cbobject,std::placeholders::_1,std::placeholders::_2))
570 
571 #define ROS_CREATE_PUBLISHER(nh,msgtype,topic) nh->create_publisher<msgtype>(topic,rclcpp::SystemDefaultsQoS());
572 #define ROS_PUBLISH(publisher,message) publisher->publish(message);
573 
574 #define ROS_CREATE_SUBSCRIBER(nh,msgtype,topic,cbfunction,cbobject) nh->create_subscription<msgtype>(topic,10,std::bind(cbfunction,cbobject,std::placeholders::_1))
575 
576 #define NSEC nanosec // maps nanoseconds in std_msgs::Header::stamp to stamp.nsec in ROS1 resp. stamp.nanosec in ROS2
577 
578 #else
579 #error __ROS_VERSION not defined, build with "--cmake-args -DROS_VERSION=1" or "--cmake-args -DROS_VERSION=2"
580 #endif
581 
582 namespace ROS
583 {
585  ROS::NodePtr createNode(const std::string& node_name = "sick_scan_xd");
586 
588  void deleteNode(ROS::NodePtr & node);
589 
591  void sleep(double seconds);
592 
594  ROS::Time now(void);
595 
597  void splitTime(ROS::Duration time, uint32_t& seconds, uint32_t& nanoseconds);
598 
600  void splitTime(ROS::Time time, uint32_t& seconds, uint32_t& nanoseconds);
601 
603  ROS::Time timeFromHeader(const std_msgs::Header* msg_header);
604 
609  ROS::Time timeFromSec(double seconds);
610 
616 
618  double seconds(ROS::Duration duration);
619 
621  double secondsSinceStart(const ROS::Time& time);
622 
624  uint64_t timestampMilliseconds(const ROS::Time& time);
625 
626 } // namespace ROS
627 
628 #endif // __SIM_LOC_ROS_WRAPPER_H_INCLUDED
SickLocStartDemoMappingSrv.h
ROS::durationFromSec
ROS::Duration durationFromSec(double seconds)
Definition: ros_wrapper.cpp:172
ROS
Definition: ros_wrapper.h:582
SickLocAutoStartSavePoseSrv.h
SickLocResultModeSrv.h
SickLocResultPoseIntervalSrv.h
SickLocForceUpdateSrv.h
roswrap::spin
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: rossimu.cpp:260
SickLocOdometryRestrictYMotionSrv.h
SickLocSetAutoStartSavePoseIntervalSrv.h
Point.h
msg
msg
ros::Publisher
SickLocSetAutoStartActiveSrv.h
ROS::sleep
void sleep(double seconds)
Definition: ros_wrapper.cpp:110
LaserScanMsg
ros_sensor_msgs::LaserScan LaserScanMsg
Definition: include/sick_scansegment_xd/common.h:123
SickLocSetReflectorsForSupportActiveSrv.h
ROS::timeFromSec
ROS::Time timeFromSec(double seconds)
Definition: ros_wrapper.cpp:161
ROS::secondsSinceStart
double secondsSinceStart(const ROS::Time &time)
Definition: ros_wrapper.cpp:192
SickLocIsSystemReadySrv.h
PointCloud2Msg
ros_sensor_msgs::PointCloud2 PointCloud2Msg
Definition: include/sick_scansegment_xd/common.h:121
SickLocRequestTimestampSrv.h
ros
PointCloud2MsgPublisher
rosPublisher< PointCloud2Msg > PointCloud2MsgPublisher
Definition: include/sick_scansegment_xd/common.h:122
SickLocInitializePoseSrv.h
ROS::splitTime
void splitTime(ROS::Duration time, uint32_t &seconds, uint32_t &nanoseconds)
Definition: ros_wrapper.cpp:128
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
sensor_msgs::PointCloud2
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
Definition: PointCloud2.h:90
SickLocAutoStartSavePoseIntervalSrv.h
geometry_msgs
SickLocStartLocalizingSrv.h
SickGetSoftwareVersionSrv.h
SickLocInitialPoseSrv.h
SickLocSetResultPortSrv.h
SickSavePermanentSrv.h
SickLocResultPortPayloadMsg.h
SickLocResultEndiannessSrv.h
default_value
string default_value
sick_scan_xd
Definition: abstract_parser.cpp:65
ros::ServiceServer
ROS::createNode
ROS::NodePtr createNode(const std::string &node_name="sick_scan_xd")
Definition: ros_wrapper.cpp:65
nav_msgs::Odometry
::nav_msgs::Odometry_< std::allocator< void > > Odometry
Definition: Odometry.h:67
SickLocSetResultEndiannessSrv.h
Odometry.h
SickLocReflectorsForSupportActiveSrv.h
SickDevSetIMUActiveSrv.h
SickDevIMUActiveSrv.h
ROS::now
ROS::Time now(void)
Definition: ros_wrapper.cpp:116
roswrap::param::init
void init(const M_string &remappings)
Definition: param_modi.cpp:809
ROS::deleteNode
void deleteNode(ROS::NodePtr &node)
Definition: ros_wrapper.cpp:98
std_msgs::Duration
::std_msgs::Duration_< std::allocator< void > > Duration
Definition: Duration.h:48
LaserscanMsgPublisher
rosPublisher< LaserScanMsg > LaserscanMsgPublisher
Definition: include/sick_scansegment_xd/common.h:124
SickLocResultPortHeaderMsg.h
sensor_msgs::LaserScan
::sensor_msgs::LaserScan_< std::allocator< void > > LaserScan
Definition: LaserScan.h:94
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
Definition: sick_scan_logging.h:123
ROS::timeFromHeader
ROS::Time timeFromHeader(const std_msgs::Header *msg_header)
Definition: ros_wrapper.cpp:152
ROS_INFO_STREAM
#define ROS_INFO_STREAM(...)
Definition: sick_scan_ros2_example.cpp:71
SickReportUserMessageSrv.h
SickLocAutoStartActiveSrv.h
polar_to_cartesian_pointcloud_ros1.node
node
Definition: polar_to_cartesian_pointcloud_ros1.py:81
std_msgs
PointCloud2.h
SickLocOdometryPortSrv.h
SickLocResultPortTestcaseMsg.h
SickLocRequestResultDataSrv.h
SickLocResultPortSrv.h
SickLocMapStateSrv.h
SickLocResultPortTelegramMsg.h
SickLocColaTelegramSrv.h
ros::ServiceClient
ROS::timestampMilliseconds
uint64_t timestampMilliseconds(const ROS::Time &time)
Definition: ros_wrapper.cpp:199
SickLocStateSrv.h
SickLocMapSrv.h
SickLocSetOdometryPortSrv.h
std_msgs::Header_< std::allocator< void > >
std_msgs::Time
::std_msgs::Time_< std::allocator< void > > Time
Definition: Time.h:48
SickLocSetResultModeSrv.h
SickDevGetLidarConfigSrv.h
nav_msgs
Definition: GetMap.h:16
SickLocSetOdometryActiveSrv.h
SickLocDiagnosticMsg.h
SickLocResultStateSrv.h
SickLocRingBufferRecordingActiveSrv.h
SickDevGetLidarIdentSrv.h
SickLocSaveRingBufferRecordingSrv.h
TransformStamped.h
SickDevGetLidarStateSrv.h
SickLocSetMapSrv.h
ROS::seconds
double seconds(ROS::Duration duration)
Definition: ros_wrapper.cpp:180
sick_scan_base.h
SickLocSetRingBufferRecordingActiveSrv.h
SickLocSetPoseSrv.h
SickLocSetOdometryRestrictYMotionSrv.h
SickDevSetLidarConfigSrv.h
SickLocOdometryActiveSrv.h
SickLocResultPortCrcMsg.h
SickLocSetResultPoseEnabledSrv.h
SickLocTimeSyncSrv.h
sensor_msgs
Tools for manipulating sensor_msgs.
rosconsole_simu.hpp
Header.h
SickLocColaTelegramMsg.h
__ROS_VERSION
#define __ROS_VERSION
Definition: sick_ros_wrapper.h:82
ros::NodeHandle
SickLocStopSrv.h
ros::Subscriber
SickLocSetResultPoseIntervalSrv.h


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