57 #ifndef __SIM_LOC_ROS_WRAPPER_H_INCLUDED
58 #define __SIM_LOC_ROS_WRAPPER_H_INCLUDED
65 #if defined __ROS_VERSION && __ROS_VERSION == 0 // native Linux or Windows uses ros simu
69 #if defined __ROS_VERSION && __ROS_VERSION <= 1
79 #include <tf2/LinearMath/Quaternion.h>
80 #include <tf2_ros/transform_broadcaster.h>
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)
277 template<
typename T>
bool param(ROS::NodePtr &
node,
const std::string & param_name, T& value,
const T& default_value)
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);
284 return ros::param::param<T>(param_name, value, default_value);
289 void spin(ROS:: NodePtr nh = 0);
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)
296 #define ROS_CREATE_PUBLISHER(nh,msgtype,topic) nh->advertise<msgtype>(topic,1);
297 #define ROS_PUBLISH(publisher,message) publisher.publish(message);
299 #define ROS_CREATE_SUBSCRIBER(nh,msgtype,topic,cbfunction,cbobject) nh->subscribe(topic,1,cbfunction,cbobject)
301 #define NSEC nsec // maps nanoseconds in std_msgs::Header::stamp to stamp.nsec in ROS1 resp. stamp.nanosec in ROS2
303 #elif defined __ROS_VERSION && __ROS_VERSION == 2
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>
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)
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"
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"
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"
417 typedef rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr OdomMsgSubscriber;
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;
423 typedef rclcpp::Subscription<sick_scan_xd::SickLocResultPortTelegramMsg>::SharedPtr SickLocResultPortTelegramMsgSubscriber;
424 typedef rclcpp::Subscription<sick_scan_xd::SickLocResultPortTestcaseMsg>::SharedPtr SickLocResultPortTestcaseMsgSubscriber;
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;
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;
535 using namespace rclcpp;
536 typedef rclcpp::Node::SharedPtr NodePtr;
538 template<
typename T>
bool param(ROS::NodePtr &
node,
const std::string & param_name, T& value,
const T& default_value)
540 ROS_INFO_STREAM(
"ROS::param(" <<
node->get_name() <<
"," << param_name <<
"," << default_value <<
")");
543 if(!
node->has_parameter(param_name))
548 catch(
const std::exception& exc)
550 ROS_WARN_STREAM(
"## ERROR ROS::param: declare_parameter(" << param_name <<
"," << default_value <<
") failed, exception " << exc.what());
554 return node->get_parameter(param_name, value);
556 catch(
const std::exception& exc)
558 ROS_WARN_STREAM(
"## ERROR ROS::param: get_parameter(" << param_name <<
"," << default_value <<
") failed, exception " << exc.what());
564 void init(
int argc,
char** argv,
const std::string nodename =
"");
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))
571 #define ROS_CREATE_PUBLISHER(nh,msgtype,topic) nh->create_publisher<msgtype>(topic,rclcpp::SystemDefaultsQoS());
572 #define ROS_PUBLISH(publisher,message) publisher->publish(message);
574 #define ROS_CREATE_SUBSCRIBER(nh,msgtype,topic,cbfunction,cbobject) nh->create_subscription<msgtype>(topic,10,std::bind(cbfunction,cbobject,std::placeholders::_1))
576 #define NSEC nanosec // maps nanoseconds in std_msgs::Header::stamp to stamp.nsec in ROS1 resp. stamp.nanosec in ROS2
579 #error __ROS_VERSION not defined, build with "--cmake-args -DROS_VERSION=1" or "--cmake-args -DROS_VERSION=2"
585 ROS::NodePtr
createNode(
const std::string& node_name =
"sick_scan_xd");
628 #endif // __SIM_LOC_ROS_WRAPPER_H_INCLUDED