sick_safevisionary.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
20 // -- END LICENSE BLOCK ------------------------------------------------
21 
22 //----------------------------------------------------------------------
29 //----------------------------------------------------------------------
30 
31 #ifndef SICK_SAFEVISIONARY_DRIVER_SICK_SAFEVISIONARY_H_INCLUDED
32 #define SICK_SAFEVISIONARY_DRIVER_SICK_SAFEVISIONARY_H_INCLUDED
33 
34 #include <sick_safevisionary_base/SafeVisionaryData.h>
35 #include <sick_safevisionary_base/SafeVisionaryDataStream.h>
37 
38 #include <boost/lockfree/policies.hpp>
39 #include <boost/lockfree/spsc_queue.hpp>
40 #include <ros/ros.h>
41 #include <thread>
42 
43 
45 {
46 public:
48  virtual ~SickSafeVisionary(){};
52  void run();
56  void stop();
57 
58 private:
62  void receiveThread();
66  void publishThread();
67 
69 
70  std::shared_ptr<visionary::SafeVisionaryData> data_handle_;
71  std::shared_ptr<visionary::SafeVisionaryDataStream> data_stream_;
72 
74  std::string frame_id_;
75  int udp_port_;
76  std::unique_ptr<std::thread> receive_thread_ptr_;
77  std::unique_ptr<std::thread> publish_thread_ptr_;
78  std::atomic<bool> data_available_;
79 
80  boost::lockfree::spsc_queue<visionary::SafeVisionaryData, boost::lockfree::capacity<10> >
82 };
83 
84 #endif /* SICK_SAFEVISIONARY_DRIVER_SICK_SAFEVISIONARY_H_INCLUDED */
SickSafeVisionary::data_handle_
std::shared_ptr< visionary::SafeVisionaryData > data_handle_
Definition: sick_safevisionary.h:70
SickSafeVisionary::priv_nh_
ros::NodeHandle priv_nh_
Definition: sick_safevisionary.h:73
CompoundPublisher
A compound publisher for the driver's topics.
Definition: compound_publisher.h:61
SickSafeVisionary::publishThread
void publishThread()
Thread for publishing sensor data.
Definition: sick_safevisionary.cpp:100
ros.h
SickSafeVisionary::udp_port_
int udp_port_
Definition: sick_safevisionary.h:75
SickSafeVisionary::~SickSafeVisionary
virtual ~SickSafeVisionary()
Definition: sick_safevisionary.h:48
SickSafeVisionary::publish_thread_ptr_
std::unique_ptr< std::thread > publish_thread_ptr_
Definition: sick_safevisionary.h:77
SickSafeVisionary::frame_id_
std::string frame_id_
Definition: sick_safevisionary.h:74
SickSafeVisionary::receiveThread
void receiveThread()
Thread for receiving sensor data.
Definition: sick_safevisionary.cpp:83
compound_publisher.h
SickSafeVisionary::spsc_queue_
boost::lockfree::spsc_queue< visionary::SafeVisionaryData, boost::lockfree::capacity< 10 > > spsc_queue_
Definition: sick_safevisionary.h:81
SickSafeVisionary
Definition: sick_safevisionary.h:44
SickSafeVisionary::SickSafeVisionary
SickSafeVisionary()
Definition: sick_safevisionary.cpp:34
SickSafeVisionary::receive_thread_ptr_
std::unique_ptr< std::thread > receive_thread_ptr_
Definition: sick_safevisionary.h:76
SickSafeVisionary::compound_publisher_
CompoundPublisher compound_publisher_
Definition: sick_safevisionary.h:68
SickSafeVisionary::data_stream_
std::shared_ptr< visionary::SafeVisionaryDataStream > data_stream_
Definition: sick_safevisionary.h:71
SickSafeVisionary::stop
void stop()
Stops the driver functionality.
Definition: sick_safevisionary.cpp:76
SickSafeVisionary::run
void run()
Starts the driver functionality.
Definition: sick_safevisionary.cpp:70
ros::NodeHandle
SickSafeVisionary::data_available_
std::atomic< bool > data_available_
Definition: sick_safevisionary.h:78


sick_safevisionary_driver
Author(s):
autogenerated on Fri Oct 20 2023 02:09:16