Go to the documentation of this file.
59 #ifndef SICK_GENERIC_MONITORING_H_
60 #define SICK_GENERIC_MONITORING_H_
157 #endif // SICK_GENERIC_MONITORING_H_
std::string m_ros_cloud_topic
void stopPointCloudMonitoring(void)
std::thread * m_monitoring_thread
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
SickScanMonitor(int read_timeout_millisec=READ_TIMEOUT_MILLISEC_DEFAULT)
NodeRunState m_lastRunState
void messageCbPointCloudROS2(const std::shared_ptr< ros_sensor_msgs::PointCloud2 > msg)
sick_scan_xd::ExitCode checkStateReinitOnError(rosNodePtr nh, NodeRunState runState, SickScanCommonTcp *scanner, sick_scan_xd::SickGenericParser *parser, sick_scan_xd::SickScanServices *services)
#define READ_TIMEOUT_MILLISEC_DEFAULT
uint64_t m_last_msg_timestamp_nanosec
bool m_monitoring_thread_running
int m_read_timeout_millisec
void runMonitoringThreadCb(void)
bool startPointCloudMonitoring(rosNodePtr nh, int timeout_millisec=READ_TIMEOUT_MILLISEC_KILL_NODE, const std::string &ros_cloud_topic="cloud")
sick_scan_xd::ExitCode checkState(NodeRunState runState, SickScanCommonTcp *scanner, sick_scan_xd::SickGenericParser *parser, sick_scan_xd::SickScanServices *services)
void messageCbPointCloud(const ros_sensor_msgs::PointCloud2 &msg)
#define READ_TIMEOUT_MILLISEC_KILL_NODE
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10