Go to the documentation of this file.
31 #ifndef SICK_SAFEVISIONARY_DRIVER_SICK_SAFEVISIONARY_H_INCLUDED
32 #define SICK_SAFEVISIONARY_DRIVER_SICK_SAFEVISIONARY_H_INCLUDED
34 #include <sick_safevisionary_base/SafeVisionaryData.h>
35 #include <sick_safevisionary_base/SafeVisionaryDataStream.h>
38 #include <boost/lockfree/policies.hpp>
39 #include <boost/lockfree/spsc_queue.hpp>
80 boost::lockfree::spsc_queue<visionary::SafeVisionaryData, boost::lockfree::capacity<10> >
std::shared_ptr< visionary::SafeVisionaryData > data_handle_
A compound publisher for the driver's topics.
void publishThread()
Thread for publishing sensor data.
virtual ~SickSafeVisionary()
std::unique_ptr< std::thread > publish_thread_ptr_
void receiveThread()
Thread for receiving sensor data.
boost::lockfree::spsc_queue< visionary::SafeVisionaryData, boost::lockfree::capacity< 10 > > spsc_queue_
std::unique_ptr< std::thread > receive_thread_ptr_
CompoundPublisher compound_publisher_
std::shared_ptr< visionary::SafeVisionaryDataStream > data_stream_
void stop()
Stops the driver functionality.
void run()
Starts the driver functionality.
std::atomic< bool > data_available_