Go to the documentation of this file.    1 #ifndef RGBD_SERVER_SHM_H_ 
    2 #define RGBD_SERVER_SHM_H_ 
    4 #include <boost/interprocess/shared_memory_object.hpp> 
    5 #include <boost/interprocess/mapped_region.hpp> 
    7 #include <ros/node_handle.h> 
   57     boost::interprocess::shared_memory_object 
shm_;
 
   85 #endif // RGBD_SERVER_SHM_H_ 
 
BufferHeader * buffer_header_
void pubHostnameThreadFunc(ros::NodeHandle &nh, const std::string server_name, const std::string hostname, const float frequency)
void checkSHMThreadFunc(const float frequency)
Check if the SHM can be opened.
std::unique_ptr< std::thread > check_shm_thread_ptr_
void send(const Image &image)
send Write a new image to the shared memory
uint64_t image_data_size_
uint64_t depth_data_size_
void initialize(const std::string &name)
initialize Initialize shared memory server
unsigned char * image_data_
std::string shared_mem_name_
boost::interprocess::shared_memory_object shm_
boost::interprocess::mapped_region mem_buffer_header_
boost::interprocess::mapped_region mem_image_
Server which uses shared memory, this only works for clients on the same machine.