rgbd
server.cpp
Go to the documentation of this file.
1 #include "rgbd/server.h"
2 #include "rgbd/utility.h"
3 
4 #include <std_msgs/String.h>
5 
6 #include <functional>
7 
8 namespace rgbd {
9 
10 // ----------------------------------------------------------------------------------------
11 
12 Server::Server(ros::NodeHandle nh) : nh_(nh), pub_hostname_thread_ptr_(nullptr)
13 {
14  const std::string& hostname = get_hostname();
15  hostname_ = hostname;
16 }
17 
18 // ----------------------------------------------------------------------------------------
19 
21 {
22  nh_.shutdown();
25 }
26 
27 // ----------------------------------------------------------------------------------------
28 
29 void Server::initialize(const std::string& name, RGBStorageType rgb_type, DepthStorageType depth_type, const float service_freq)
30 {
31  name_= name;
32  server_rgbd_.initialize(name_, rgb_type, depth_type, service_freq);
34 }
35 
36 // ----------------------------------------------------------------------------------------
37 
38 void Server::send(const Image& image, bool)
39 {
40  // Publisher is created here, because shared memory is opened as the first image is send. Because the image size is unknown before.
41  // Creating the publisher earlier will cause the client to initialize the client_shm, while the shared memory doesn't exist yet.
43  pub_hostname_thread_ptr_ = std::make_unique<std::thread>(rgbd::pubHostnameThreadFunc, std::ref(nh_), name_, hostname_, 20);
44  server_rgbd_.send(image);
45  server_shm_.send(image);
46 }
47 
48 }
rgbd::Server::~Server
virtual ~Server()
Destructor.
Definition: server.cpp:20
rgbd::ServerRGBD::initialize
void initialize(const std::string &name, RGBStorageType rgb_type=RGB_STORAGE_LOSSLESS, DepthStorageType depth_type=DEPTH_STORAGE_LOSSLESS, const float service_freq=10)
Initialize server.
Definition: server_rgbd.cpp:43
std::string
rgbd::Server::send
void send(const Image &image, bool threaded=false)
send Write a new image to all interfaces
Definition: server.cpp:38
rgbd::Server::nh_
ros::NodeHandle nh_
Definition: server.h:57
functional
rgbd::get_hostname
std::string get_hostname()
Get the hostname of the current machine.
Definition: utility.cpp:13
utility.h
rgbd::pubHostnameThreadFunc
void pubHostnameThreadFunc(ros::NodeHandle &nh, const std::string server_name, const std::string hostname, const float frequency)
Definition: server_shm.cpp:154
rgbd::DepthStorageType
DepthStorageType
Definition: image.h:36
rgbd::Image
Definition: image.h:43
rgbd::Server::hostname_
std::string hostname_
Definition: server.h:60
rgbd::Server::name_
std::string name_
Definition: server.h:59
rgbd::Server::initialize
void initialize(const std::string &name, RGBStorageType rgb_type=RGB_STORAGE_LOSSLESS, DepthStorageType depth_type=DEPTH_STORAGE_LOSSLESS, const float service_freq=10)
initialize initialize server
Definition: server.cpp:29
rgbd
Definition: client.h:24
rgbd::RGBStorageType
RGBStorageType
Definition: image.h:29
rgbd::ServerSHM::send
void send(const Image &image)
send Write a new image to the shared memory
Definition: server_shm.cpp:48
rgbd::Server::Server
Server(ros::NodeHandle nh=ros::NodeHandle())
Constructor.
Definition: server.cpp:12
rgbd::ServerSHM::initialize
void initialize(const std::string &name)
initialize Initialize shared memory server
Definition: server_shm.cpp:40
rgbd::Server::server_shm_
ServerSHM server_shm_
Definition: server.h:55
server.h
rgbd::Server::pub_hostname_thread_ptr_
std::unique_ptr< std::thread > pub_hostname_thread_ptr_
Definition: server.h:63
std::ref
T ref(T... args)
rgbd::Server::server_rgbd_
ServerRGBD server_rgbd_
Definition: server.h:53
rgbd::ServerRGBD::send
void send(const Image &image)
Write a new image to all interfaces.
Definition: server_rgbd.cpp:56