56 #ifndef __SIM_LOC_ROS_WRAPPER_H_INCLUDED
57 #define __SIM_LOC_ROS_WRAPPER_H_INCLUDED
64 #if defined __ROS_VERSION && __ROS_VERSION == 1
69 #include <std_msgs/Header.h>
70 #include <geometry_msgs/Point.h>
71 #include <geometry_msgs/TransformStamped.h>
72 #include <nav_msgs/Odometry.h>
73 #include <sensor_msgs/PointCloud2.h>
77 #define RCLCPP_DEBUG_STREAM(logger,msgstream) ROS_DEBUG_STREAM(msgstream)
78 #define RCLCPP_INFO_STREAM(logger,msgstream) ROS_INFO_STREAM(msgstream)
79 #define RCLCPP_WARN_STREAM(logger,msgstream) ROS_WARN_STREAM(msgstream)
80 #define RCLCPP_ERROR_STREAM(logger,msgstream) ROS_ERROR_STREAM(msgstream)
83 #include "sick_scan/SickLocColaTelegramMsg.h"
84 #include "sick_scan/SickLocDiagnosticMsg.h"
85 #include "sick_scan/SickLocResultPortCrcMsg.h"
86 #include "sick_scan/SickLocResultPortHeaderMsg.h"
87 #include "sick_scan/SickLocResultPortPayloadMsg.h"
88 #include "sick_scan/SickLocResultPortTelegramMsg.h"
89 #include "sick_scan/SickLocResultPortTestcaseMsg.h"
91 #include "sick_scan/SickLocColaTelegramSrv.h"
92 #include "sick_scan/SickLocIsSystemReadySrv.h"
93 #include "sick_scan/SickLocRequestResultDataSrv.h"
94 #include "sick_scan/SickLocRequestTimestampSrv.h"
95 #include "sick_scan/SickLocSetPoseSrv.h"
96 #include "sick_scan/SickLocSetResultEndiannessSrv.h"
97 #include "sick_scan/SickLocSetResultModeSrv.h"
98 #include "sick_scan/SickLocSetResultPortSrv.h"
99 #include "sick_scan/SickLocSetResultPoseEnabledSrv.h"
100 #include "sick_scan/SickLocSetResultPoseIntervalSrv.h"
101 #include "sick_scan/SickLocStartLocalizingSrv.h"
102 #include "sick_scan/SickLocStateSrv.h"
103 #include "sick_scan/SickLocStopSrv.h"
104 #include "sick_scan/SickLocTimeSyncSrv.h"
106 #include "sick_scan/SickDevGetLidarConfigSrv.h"
107 #include "sick_scan/SickDevGetLidarIdentSrv.h"
108 #include "sick_scan/SickDevGetLidarStateSrv.h"
109 #include "sick_scan/SickDevSetLidarConfigSrv.h"
110 #include "sick_scan/SickGetSoftwareVersionSrv.h"
111 #include "sick_scan/SickLocAutoStartActiveSrv.h"
112 #include "sick_scan/SickLocAutoStartSavePoseIntervalSrv.h"
113 #include "sick_scan/SickLocAutoStartSavePoseSrv.h"
114 #include "sick_scan/SickLocForceUpdateSrv.h"
115 #include "sick_scan/SickLocInitializePoseSrv.h"
116 #include "sick_scan/SickLocInitialPoseSrv.h"
117 #include "sick_scan/SickLocMapSrv.h"
118 #include "sick_scan/SickLocMapStateSrv.h"
119 #include "sick_scan/SickLocOdometryActiveSrv.h"
120 #include "sick_scan/SickLocOdometryPortSrv.h"
121 #include "sick_scan/SickLocOdometryRestrictYMotionSrv.h"
122 #include "sick_scan/SickLocReflectorsForSupportActiveSrv.h"
123 #include "sick_scan/SickLocResultEndiannessSrv.h"
124 #include "sick_scan/SickLocResultModeSrv.h"
125 #include "sick_scan/SickLocResultPortSrv.h"
126 #include "sick_scan/SickLocResultPoseIntervalSrv.h"
127 #include "sick_scan/SickLocResultStateSrv.h"
128 #include "sick_scan/SickLocRingBufferRecordingActiveSrv.h"
129 #include "sick_scan/SickLocSaveRingBufferRecordingSrv.h"
130 #include "sick_scan/SickLocSetAutoStartActiveSrv.h"
131 #include "sick_scan/SickLocSetAutoStartSavePoseIntervalSrv.h"
132 #include "sick_scan/SickLocSetMapSrv.h"
133 #include "sick_scan/SickLocSetOdometryActiveSrv.h"
134 #include "sick_scan/SickLocSetOdometryPortSrv.h"
135 #include "sick_scan/SickLocSetOdometryRestrictYMotionSrv.h"
136 #include "sick_scan/SickLocSetReflectorsForSupportActiveSrv.h"
137 #include "sick_scan/SickLocSetRingBufferRecordingActiveSrv.h"
138 #include "sick_scan/SickLocStartDemoMappingSrv.h"
139 #include "sick_scan/SickReportUserMessageSrv.h"
140 #include "sick_scan/SickSavePermanentSrv.h"
141 #include "sick_scan/SickDevSetIMUActiveSrv.h"
142 #include "sick_scan/SickDevIMUActiveSrv.h"
272 template<
typename T>
bool param(ROS::NodePtr & node,
const std::string & param_name, T& value,
const T& default_value)
274 return ros::param::param<T>(param_name, value, default_value);
278 void spin(ROS:: NodePtr nh = 0);
282 #define ROS_CREATE_SRV_CLIENT(nh,srv,name) nh->serviceClient<srv>(name)
283 #define ROS_CREATE_SRV_SERVER(nh,srv,name,cbfunction,cbobject) nh->advertiseService(name,cbfunction,cbobject)
285 #define ROS_CREATE_PUBLISHER(nh,msgtype,topic) nh->advertise<msgtype>(topic,1);
286 #define ROS_PUBLISH(publisher,message) publisher.publish(message);
288 #define ROS_CREATE_SUBSCRIBER(nh,msgtype,topic,cbfunction,cbobject) nh->subscribe(topic,1,cbfunction,cbobject)
290 #define NSEC nsec // maps nanoseconds in std_msgs::Header::stamp to stamp.nsec in ROS1 resp. stamp.nanosec in ROS2
292 #elif defined __ROS_VERSION && __ROS_VERSION == 2
296 #include <rclcpp/rclcpp.hpp>
297 #include <rclcpp/executor.hpp>
298 #include <std_msgs/msg/header.hpp>
299 #include <geometry_msgs/msg/point.hpp>
300 #include <geometry_msgs/msg/transform_stamped.hpp>
301 #include <nav_msgs/msg/odometry.hpp>
302 #include <sensor_msgs/msg/point_cloud2.hpp>
306 #define ROS_DEBUG_STREAM(msgstream) RCLCPP_DEBUG_STREAM(rclcpp::get_logger("sick_scan"),msgstream)
307 #define ROS_INFO_STREAM(msgstream) RCLCPP_INFO_STREAM(rclcpp::get_logger("sick_scan"),msgstream)
308 #define ROS_WARN_STREAM(msgstream) RCLCPP_WARN_STREAM(rclcpp::get_logger("sick_scan"),msgstream)
309 #define ROS_ERROR_STREAM(msgstream) RCLCPP_ERROR_STREAM(rclcpp::get_logger("sick_scan"),msgstream)
312 #include "sick_scan/msg/sick_loc_cola_telegram_msg.hpp"
313 #include "sick_scan/msg/sick_loc_diagnostic_msg.hpp"
314 #include "sick_scan/msg/sick_loc_result_port_crc_msg.hpp"
315 #include "sick_scan/msg/sick_loc_result_port_header_msg.hpp"
316 #include "sick_scan/msg/sick_loc_result_port_payload_msg.hpp"
317 #include "sick_scan/msg/sick_loc_result_port_telegram_msg.hpp"
318 #include "sick_scan/msg/sick_loc_result_port_testcase_msg.hpp"
320 #include "sick_scan/srv/sick_loc_cola_telegram_srv.hpp"
321 #include "sick_scan/srv/sick_loc_is_system_ready_srv.hpp"
322 #include "sick_scan/srv/sick_loc_request_result_data_srv.hpp"
323 #include "sick_scan/srv/sick_loc_request_timestamp_srv.hpp"
324 #include "sick_scan/srv/sick_loc_set_pose_srv.hpp"
325 #include "sick_scan/srv/sick_loc_set_result_endianness_srv.hpp"
326 #include "sick_scan/srv/sick_loc_set_result_mode_srv.hpp"
327 #include "sick_scan/srv/sick_loc_set_result_port_srv.hpp"
328 #include "sick_scan/srv/sick_loc_set_result_pose_enabled_srv.hpp"
329 #include "sick_scan/srv/sick_loc_set_result_pose_interval_srv.hpp"
330 #include "sick_scan/srv/sick_loc_start_localizing_srv.hpp"
331 #include "sick_scan/srv/sick_loc_state_srv.hpp"
332 #include "sick_scan/srv/sick_loc_stop_srv.hpp"
333 #include "sick_scan/srv/sick_loc_time_sync_srv.hpp"
335 #include "sick_scan/srv/sick_dev_get_lidar_config_srv.hpp"
336 #include "sick_scan/srv/sick_dev_get_lidar_ident_srv.hpp"
337 #include "sick_scan/srv/sick_dev_get_lidar_state_srv.hpp"
338 #include "sick_scan/srv/sick_dev_set_lidar_config_srv.hpp"
339 #include "sick_scan/srv/sick_get_software_version_srv.hpp"
340 #include "sick_scan/srv/sick_loc_auto_start_active_srv.hpp"
341 #include "sick_scan/srv/sick_loc_auto_start_save_pose_interval_srv.hpp"
342 #include "sick_scan/srv/sick_loc_auto_start_save_pose_srv.hpp"
343 #include "sick_scan/srv/sick_loc_force_update_srv.hpp"
344 #include "sick_scan/srv/sick_loc_initialize_pose_srv.hpp"
345 #include "sick_scan/srv/sick_loc_initial_pose_srv.hpp"
346 #include "sick_scan/srv/sick_loc_map_srv.hpp"
347 #include "sick_scan/srv/sick_loc_map_state_srv.hpp"
348 #include "sick_scan/srv/sick_loc_odometry_active_srv.hpp"
349 #include "sick_scan/srv/sick_loc_odometry_port_srv.hpp"
350 #include "sick_scan/srv/sick_loc_odometry_restrict_y_motion_srv.hpp"
351 #include "sick_scan/srv/sick_loc_reflectors_for_support_active_srv.hpp"
352 #include "sick_scan/srv/sick_loc_result_endianness_srv.hpp"
353 #include "sick_scan/srv/sick_loc_result_mode_srv.hpp"
354 #include "sick_scan/srv/sick_loc_result_port_srv.hpp"
355 #include "sick_scan/srv/sick_loc_result_pose_interval_srv.hpp"
356 #include "sick_scan/srv/sick_loc_result_state_srv.hpp"
357 #include "sick_scan/srv/sick_loc_ring_buffer_recording_active_srv.hpp"
358 #include "sick_scan/srv/sick_loc_save_ring_buffer_recording_srv.hpp"
359 #include "sick_scan/srv/sick_loc_set_auto_start_active_srv.hpp"
360 #include "sick_scan/srv/sick_loc_set_auto_start_save_pose_interval_srv.hpp"
361 #include "sick_scan/srv/sick_loc_set_map_srv.hpp"
362 #include "sick_scan/srv/sick_loc_set_odometry_active_srv.hpp"
363 #include "sick_scan/srv/sick_loc_set_odometry_port_srv.hpp"
364 #include "sick_scan/srv/sick_loc_set_odometry_restrict_y_motion_srv.hpp"
365 #include "sick_scan/srv/sick_loc_set_reflectors_for_support_active_srv.hpp"
366 #include "sick_scan/srv/sick_loc_set_ring_buffer_recording_active_srv.hpp"
367 #include "sick_scan/srv/sick_loc_start_demo_mapping_srv.hpp"
368 #include "sick_scan/srv/sick_report_user_message_srv.hpp"
369 #include "sick_scan/srv/sick_save_permanent_srv.hpp"
370 #include "sick_scan/srv/sick_dev_set_imu_active_srv.hpp"
371 #include "sick_scan/srv/sick_dev_imu_active_srv.hpp"
398 typedef sensor_msgs::msg::PointCloud2 PointCloud2Msg;
399 typedef rclcpp::Publisher<PointCloud2Msg>::SharedPtr PointCloud2MsgPublisher;
401 typedef nav_msgs::msg::Odometry OdomMsg;
402 typedef rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr OdomMsgSubscriber;
404 typedef rclcpp::Publisher<sick_scan::SickLocResultPortTelegramMsg>::SharedPtr SickLocResultPortTelegramMsgPublisher;
405 typedef rclcpp::Publisher<sick_scan::SickLocDiagnosticMsg>::SharedPtr SickLocDiagnosticMsgPublisher;
406 typedef rclcpp::Publisher<sick_scan::SickLocResultPortTestcaseMsg>::SharedPtr SickLocResultPortTestcaseMsgPublisher;
408 typedef rclcpp::Subscription<sick_scan::SickLocResultPortTelegramMsg>::SharedPtr SickLocResultPortTelegramMsgSubscriber;
409 typedef rclcpp::Subscription<sick_scan::SickLocResultPortTestcaseMsg>::SharedPtr SickLocResultPortTestcaseMsgSubscriber;
412 typedef rclcpp::Client<sick_scan::SickLocColaTelegramSrv>::SharedPtr SickLocColaTelegramSrvClient;
413 typedef rclcpp::Service<sick_scan::SickLocColaTelegramSrv>::SharedPtr SickLocColaTelegramSrvServer;
414 typedef rclcpp::Client<sick_scan::SickLocIsSystemReadySrv>::SharedPtr SickLocIsSystemReadySrvClient;
415 typedef rclcpp::Service<sick_scan::SickLocIsSystemReadySrv>::SharedPtr SickLocIsSystemReadySrvServer;
416 typedef rclcpp::Client<sick_scan::SickLocRequestResultDataSrv>::SharedPtr SickLocRequestResultDataSrvClient;
417 typedef rclcpp::Service<sick_scan::SickLocRequestResultDataSrv>::SharedPtr SickLocRequestResultDataSrvServer;
418 typedef rclcpp::Client<sick_scan::SickLocRequestTimestampSrv>::SharedPtr SickLocRequestTimestampSrvClient;
419 typedef rclcpp::Service<sick_scan::SickLocRequestTimestampSrv>::SharedPtr SickLocRequestTimestampSrvServer;
420 typedef rclcpp::Client<sick_scan::SickLocSetPoseSrv>::SharedPtr SickLocSetPoseSrvClient;
421 typedef rclcpp::Service<sick_scan::SickLocSetPoseSrv>::SharedPtr SickLocSetPoseSrvServer;
422 typedef rclcpp::Client<sick_scan::SickLocSetResultEndiannessSrv>::SharedPtr SickLocSetResultEndiannessSrvClient;
423 typedef rclcpp::Service<sick_scan::SickLocSetResultEndiannessSrv>::SharedPtr SickLocSetResultEndiannessSrvServer;
424 typedef rclcpp::Client<sick_scan::SickLocSetResultModeSrv>::SharedPtr SickLocSetResultModeSrvClient;
425 typedef rclcpp::Service<sick_scan::SickLocSetResultModeSrv>::SharedPtr SickLocSetResultModeSrvServer;
426 typedef rclcpp::Client<sick_scan::SickLocSetResultPortSrv>::SharedPtr SickLocSetResultPortSrvClient;
427 typedef rclcpp::Service<sick_scan::SickLocSetResultPortSrv>::SharedPtr SickLocSetResultPortSrvServer;
428 typedef rclcpp::Client<sick_scan::SickLocSetResultPoseEnabledSrv>::SharedPtr SickLocSetResultPoseEnabledSrvClient;
429 typedef rclcpp::Service<sick_scan::SickLocSetResultPoseEnabledSrv>::SharedPtr SickLocSetResultPoseEnabledSrvServer;
430 typedef rclcpp::Client<sick_scan::SickLocSetResultPoseIntervalSrv>::SharedPtr SickLocSetResultPoseIntervalSrvClient;
431 typedef rclcpp::Service<sick_scan::SickLocSetResultPoseIntervalSrv>::SharedPtr SickLocSetResultPoseIntervalSrvServer;
432 typedef rclcpp::Client<sick_scan::SickLocStartLocalizingSrv>::SharedPtr SickLocStartLocalizingSrvClient;
433 typedef rclcpp::Service<sick_scan::SickLocStartLocalizingSrv>::SharedPtr SickLocStartLocalizingSrvServer;
434 typedef rclcpp::Client<sick_scan::SickLocStateSrv>::SharedPtr SickLocStateSrvClient;
435 typedef rclcpp::Service<sick_scan::SickLocStateSrv>::SharedPtr SickLocStateSrvServer;
436 typedef rclcpp::Client<sick_scan::SickLocStopSrv>::SharedPtr SickLocStopSrvClient;
437 typedef rclcpp::Service<sick_scan::SickLocStopSrv>::SharedPtr SickLocStopSrvServer;
438 typedef rclcpp::Client<sick_scan::SickLocTimeSyncSrv>::SharedPtr SickLocTimeSyncSrvClient;
439 typedef rclcpp::Service<sick_scan::SickLocTimeSyncSrv>::SharedPtr SickLocTimeSyncSrvServer;
441 typedef rclcpp::Client <sick_scan::SickDevGetLidarConfigSrv>::SharedPtr SickDevGetLidarConfigSrvClient;
442 typedef rclcpp::Service<sick_scan::SickDevGetLidarConfigSrv>::SharedPtr SickDevGetLidarConfigSrvServer;
443 typedef rclcpp::Client <sick_scan::SickDevGetLidarIdentSrv>::SharedPtr SickDevGetLidarIdentSrvClient;
444 typedef rclcpp::Service<sick_scan::SickDevGetLidarIdentSrv>::SharedPtr SickDevGetLidarIdentSrvServer;
445 typedef rclcpp::Client <sick_scan::SickDevGetLidarStateSrv>::SharedPtr SickDevGetLidarStateSrvClient;
446 typedef rclcpp::Service<sick_scan::SickDevGetLidarStateSrv>::SharedPtr SickDevGetLidarStateSrvServer;
447 typedef rclcpp::Client <sick_scan::SickDevSetLidarConfigSrv>::SharedPtr SickDevSetLidarConfigSrvClient;
448 typedef rclcpp::Service<sick_scan::SickDevSetLidarConfigSrv>::SharedPtr SickDevSetLidarConfigSrvServer;
449 typedef rclcpp::Client <sick_scan::SickGetSoftwareVersionSrv>::SharedPtr SickGetSoftwareVersionSrvClient;
450 typedef rclcpp::Service<sick_scan::SickGetSoftwareVersionSrv>::SharedPtr SickGetSoftwareVersionSrvServer;
451 typedef rclcpp::Client <sick_scan::SickLocAutoStartActiveSrv>::SharedPtr SickLocAutoStartActiveSrvClient;
452 typedef rclcpp::Service<sick_scan::SickLocAutoStartActiveSrv>::SharedPtr SickLocAutoStartActiveSrvServer;
453 typedef rclcpp::Client <sick_scan::SickLocAutoStartSavePoseIntervalSrv>::SharedPtr SickLocAutoStartSavePoseIntervalSrvClient;
454 typedef rclcpp::Service<sick_scan::SickLocAutoStartSavePoseIntervalSrv>::SharedPtr SickLocAutoStartSavePoseIntervalSrvServer;
455 typedef rclcpp::Client <sick_scan::SickLocAutoStartSavePoseSrv>::SharedPtr SickLocAutoStartSavePoseSrvClient;
456 typedef rclcpp::Service<sick_scan::SickLocAutoStartSavePoseSrv>::SharedPtr SickLocAutoStartSavePoseSrvServer;
457 typedef rclcpp::Client <sick_scan::SickLocForceUpdateSrv>::SharedPtr SickLocForceUpdateSrvClient;
458 typedef rclcpp::Service<sick_scan::SickLocForceUpdateSrv>::SharedPtr SickLocForceUpdateSrvServer;
459 typedef rclcpp::Client <sick_scan::SickLocInitializePoseSrv>::SharedPtr SickLocInitializePoseSrvClient;
460 typedef rclcpp::Service<sick_scan::SickLocInitializePoseSrv>::SharedPtr SickLocInitializePoseSrvServer;
461 typedef rclcpp::Client <sick_scan::SickLocInitialPoseSrv>::SharedPtr SickLocInitialPoseSrvClient;
462 typedef rclcpp::Service<sick_scan::SickLocInitialPoseSrv>::SharedPtr SickLocInitialPoseSrvServer;
463 typedef rclcpp::Client <sick_scan::SickLocMapSrv>::SharedPtr SickLocMapSrvClient;
464 typedef rclcpp::Service<sick_scan::SickLocMapSrv>::SharedPtr SickLocMapSrvServer;
465 typedef rclcpp::Client <sick_scan::SickLocMapStateSrv>::SharedPtr SickLocMapStateSrvClient;
466 typedef rclcpp::Service<sick_scan::SickLocMapStateSrv>::SharedPtr SickLocMapStateSrvServer;
467 typedef rclcpp::Client <sick_scan::SickLocOdometryActiveSrv>::SharedPtr SickLocOdometryActiveSrvClient;
468 typedef rclcpp::Service<sick_scan::SickLocOdometryActiveSrv>::SharedPtr SickLocOdometryActiveSrvServer;
469 typedef rclcpp::Client <sick_scan::SickLocOdometryPortSrv>::SharedPtr SickLocOdometryPortSrvClient;
470 typedef rclcpp::Service<sick_scan::SickLocOdometryPortSrv>::SharedPtr SickLocOdometryPortSrvServer;
471 typedef rclcpp::Client <sick_scan::SickLocOdometryRestrictYMotionSrv>::SharedPtr SickLocOdometryRestrictYMotionSrvClient;
472 typedef rclcpp::Service<sick_scan::SickLocOdometryRestrictYMotionSrv>::SharedPtr SickLocOdometryRestrictYMotionSrvServer;
473 typedef rclcpp::Client <sick_scan::SickLocReflectorsForSupportActiveSrv>::SharedPtr SickLocReflectorsForSupportActiveSrvClient;
474 typedef rclcpp::Service<sick_scan::SickLocReflectorsForSupportActiveSrv>::SharedPtr SickLocReflectorsForSupportActiveSrvServer;
475 typedef rclcpp::Client <sick_scan::SickLocResultEndiannessSrv>::SharedPtr SickLocResultEndiannessSrvClient;
476 typedef rclcpp::Service<sick_scan::SickLocResultEndiannessSrv>::SharedPtr SickLocResultEndiannessSrvServer;
477 typedef rclcpp::Client <sick_scan::SickLocResultModeSrv>::SharedPtr SickLocResultModeSrvClient;
478 typedef rclcpp::Service<sick_scan::SickLocResultModeSrv>::SharedPtr SickLocResultModeSrvServer;
479 typedef rclcpp::Client <sick_scan::SickLocResultPortSrv>::SharedPtr SickLocResultPortSrvClient;
480 typedef rclcpp::Service<sick_scan::SickLocResultPortSrv>::SharedPtr SickLocResultPortSrvServer;
481 typedef rclcpp::Client <sick_scan::SickLocResultPoseIntervalSrv>::SharedPtr SickLocResultPoseIntervalSrvClient;
482 typedef rclcpp::Service<sick_scan::SickLocResultPoseIntervalSrv>::SharedPtr SickLocResultPoseIntervalSrvServer;
483 typedef rclcpp::Client <sick_scan::SickLocResultStateSrv>::SharedPtr SickLocResultStateSrvClient;
484 typedef rclcpp::Service<sick_scan::SickLocResultStateSrv>::SharedPtr SickLocResultStateSrvServer;
485 typedef rclcpp::Client <sick_scan::SickLocRingBufferRecordingActiveSrv>::SharedPtr SickLocRingBufferRecordingActiveSrvClient;
486 typedef rclcpp::Service<sick_scan::SickLocRingBufferRecordingActiveSrv>::SharedPtr SickLocRingBufferRecordingActiveSrvServer;
487 typedef rclcpp::Client <sick_scan::SickLocSaveRingBufferRecordingSrv>::SharedPtr SickLocSaveRingBufferRecordingSrvClient;
488 typedef rclcpp::Service<sick_scan::SickLocSaveRingBufferRecordingSrv>::SharedPtr SickLocSaveRingBufferRecordingSrvServer;
489 typedef rclcpp::Client <sick_scan::SickLocSetAutoStartActiveSrv>::SharedPtr SickLocSetAutoStartActiveSrvClient;
490 typedef rclcpp::Service<sick_scan::SickLocSetAutoStartActiveSrv>::SharedPtr SickLocSetAutoStartActiveSrvServer;
491 typedef rclcpp::Client <sick_scan::SickLocSetAutoStartSavePoseIntervalSrv>::SharedPtr SickLocSetAutoStartSavePoseIntervalSrvClient;
492 typedef rclcpp::Service<sick_scan::SickLocSetAutoStartSavePoseIntervalSrv>::SharedPtr SickLocSetAutoStartSavePoseIntervalSrvServer;
493 typedef rclcpp::Client <sick_scan::SickLocSetMapSrv>::SharedPtr SickLocSetMapSrvClient;
494 typedef rclcpp::Service<sick_scan::SickLocSetMapSrv>::SharedPtr SickLocSetMapSrvServer;
495 typedef rclcpp::Client <sick_scan::SickLocSetOdometryActiveSrv>::SharedPtr SickLocSetOdometryActiveSrvClient;
496 typedef rclcpp::Service<sick_scan::SickLocSetOdometryActiveSrv>::SharedPtr SickLocSetOdometryActiveSrvServer;
497 typedef rclcpp::Client <sick_scan::SickLocSetOdometryPortSrv>::SharedPtr SickLocSetOdometryPortSrvClient;
498 typedef rclcpp::Service<sick_scan::SickLocSetOdometryPortSrv>::SharedPtr SickLocSetOdometryPortSrvServer;
499 typedef rclcpp::Client <sick_scan::SickLocSetOdometryRestrictYMotionSrv>::SharedPtr SickLocSetOdometryRestrictYMotionSrvClient;
500 typedef rclcpp::Service<sick_scan::SickLocSetOdometryRestrictYMotionSrv>::SharedPtr SickLocSetOdometryRestrictYMotionSrvServer;
501 typedef rclcpp::Client <sick_scan::SickLocSetReflectorsForSupportActiveSrv>::SharedPtr SickLocSetReflectorsForSupportActiveSrvClient;
502 typedef rclcpp::Service<sick_scan::SickLocSetReflectorsForSupportActiveSrv>::SharedPtr SickLocSetReflectorsForSupportActiveSrvServer;
503 typedef rclcpp::Client <sick_scan::SickLocSetRingBufferRecordingActiveSrv>::SharedPtr SickLocSetRingBufferRecordingActiveSrvClient;
504 typedef rclcpp::Service<sick_scan::SickLocSetRingBufferRecordingActiveSrv>::SharedPtr SickLocSetRingBufferRecordingActiveSrvServer;
505 typedef rclcpp::Client <sick_scan::SickLocStartDemoMappingSrv>::SharedPtr SickLocStartDemoMappingSrvClient;
506 typedef rclcpp::Service<sick_scan::SickLocStartDemoMappingSrv>::SharedPtr SickLocStartDemoMappingSrvServer;
507 typedef rclcpp::Client <sick_scan::SickReportUserMessageSrv>::SharedPtr SickReportUserMessageSrvClient;
508 typedef rclcpp::Service<sick_scan::SickReportUserMessageSrv>::SharedPtr SickReportUserMessageSrvServer;
509 typedef rclcpp::Client <sick_scan::SickSavePermanentSrv>::SharedPtr SickSavePermanentSrvClient;
510 typedef rclcpp::Service<sick_scan::SickSavePermanentSrv>::SharedPtr SickSavePermanentSrvServer;
511 typedef rclcpp::Client <sick_scan::SickDevSetIMUActiveSrv>::SharedPtr SickDevSetIMUActiveSrvClient;
512 typedef rclcpp::Service<sick_scan::SickDevSetIMUActiveSrv>::SharedPtr SickDevSetIMUActiveSrvServer;
513 typedef rclcpp::Client <sick_scan::SickDevIMUActiveSrv>::SharedPtr SickDevIMUActiveSrvClient;
514 typedef rclcpp::Service<sick_scan::SickDevIMUActiveSrv>::SharedPtr SickDevIMUActiveSrvServer;
520 using namespace rclcpp;
521 typedef rclcpp::Node::SharedPtr NodePtr;
523 template<
typename T>
bool param(ROS::NodePtr & node,
const std::string & param_name, T& value,
const T& default_value)
525 ROS_INFO_STREAM(
"ROS::param(" << node->get_name() <<
"," << param_name <<
"," << default_value <<
")");
528 if(!node->has_parameter(param_name))
533 catch(
const std::exception& exc)
535 ROS_WARN_STREAM(
"## ERROR ROS::param: declare_parameter(" << param_name <<
"," << default_value <<
") failed, exception " << exc.what());
539 return node->get_parameter(param_name, value);
541 catch(
const std::exception& exc)
543 ROS_WARN_STREAM(
"## ERROR ROS::param: get_parameter(" << param_name <<
"," << default_value <<
") failed, exception " << exc.what());
549 void init(
int argc,
char** argv,
const std::string nodename =
"");
553 #define ROS_CREATE_SRV_CLIENT(nh,srv,name) nh->create_client<srv>(name)
554 #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))
556 #define ROS_CREATE_PUBLISHER(nh,msgtype,topic) nh->create_publisher<msgtype>(topic,rclcpp::SystemDefaultsQoS());
557 #define ROS_PUBLISH(publisher,message) publisher->publish(message);
559 #define ROS_CREATE_SUBSCRIBER(nh,msgtype,topic,cbfunction,cbobject) nh->create_subscription<msgtype>(topic,10,std::bind(cbfunction,cbobject,std::placeholders::_1))
561 #define NSEC nanosec // maps nanoseconds in std_msgs::Header::stamp to stamp.nsec in ROS1 resp. stamp.nanosec in ROS2
564 #error __ROS_VERSION not defined, build with "--cmake-args -DROS_VERSION=1" or "--cmake-args -DROS_VERSION=2"
570 ROS::NodePtr
createNode(
const std::string& node_name =
"sick_scan");
582 void splitTime(ROS::Duration time, uint32_t&
seconds, uint32_t& nanoseconds);
603 double seconds(ROS::Duration duration);
613 #endif // __SIM_LOC_ROS_WRAPPER_H_INCLUDED