rgbd
Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
rgbd::Client Class Reference

Client which uses the interfaces of ClientRGBD and ClientSHM. More...

#include <client.h>

Public Member Functions

 Client ()
 Constructor. More...
 
bool deinitialize ()
 Calls deinitialize on implementation clients. Shutsdown both implementations and deletes nh_. initialized will now return false. More...
 
bool initialize (const std::string &server_name, float timeout=5.0)
 Initialize the client. More...
 
bool initialized ()
 Check if the client is initialized. Checks if nh_ is exists. nextImage will not return an image if client is not initialized. More...
 
ImagePtr nextImage ()
 Get a new Image. If no new image has been received since the last call, The ImagePtr will be a nullptr. More...
 
bool nextImage (Image &image)
 Get a new Image. If no new image has been received since the last call, no image will be written and false will be returned. More...
 
virtual ~Client ()
 Destructor. More...
 

Protected Types

enum  ClientImplMode { ClientImplMode::shm, ClientImplMode::rgbd }
 

Protected Member Functions

void hostsCallback (const std_msgs::StringConstPtr &msg)
 
void subHostsThreadFunc (const float frequency)
 

Protected Attributes

ros::CallbackQueue cb_queue_
 
ClientImplMode client_impl_mode_
 
ClientRGBD client_rgbd_
 
ClientSHM client_shm_
 
std::string hostname_
 
ros::WallTime last_time_shm_server_online_
 
std::unique_ptr< ros::NodeHandle > nh_
 
std::string server_name_
 
std::thread sub_hosts_thread_
 
ros::Subscriber sub_shm_hosts_
 
std::mutex switch_impl_mutex_
 

Detailed Description

Client which uses the interfaces of ClientRGBD and ClientSHM.

Definition at line 29 of file client.h.

Member Enumeration Documentation

◆ ClientImplMode

enum rgbd::Client::ClientImplMode
strongprotected
Enumerator
shm 
rgbd 

Definition at line 81 of file client.h.

Constructor & Destructor Documentation

◆ Client()

rgbd::Client::Client ( )

Constructor.

Definition at line 20 of file client.cpp.

◆ ~Client()

rgbd::Client::~Client ( )
virtual

Destructor.

Definition at line 27 of file client.cpp.

Member Function Documentation

◆ deinitialize()

bool rgbd::Client::deinitialize ( )

Calls deinitialize on implementation clients. Shutsdown both implementations and deletes nh_. initialized will now return false.

Returns
indicates success

Definition at line 54 of file client.cpp.

◆ hostsCallback()

void rgbd::Client::hostsCallback ( const std_msgs::StringConstPtr &  msg)
protected

Definition at line 98 of file client.cpp.

◆ initialize()

bool rgbd::Client::initialize ( const std::string server_name,
float  timeout = 5.0 
)

Initialize the client.

Parameters
server_nameFully resolved server name
timeoutTimeout used to initialize each interface, currently only the ClientSHM interface requires a timeout
Returns
indicates success

Definition at line 34 of file client.cpp.

◆ initialized()

bool rgbd::Client::initialized ( )
inline

Check if the client is initialized. Checks if nh_ is exists. nextImage will not return an image if client is not initialized.

Returns
initialized or not

Definition at line 62 of file client.h.

◆ nextImage() [1/2]

ImagePtr rgbd::Client::nextImage ( )

Get a new Image. If no new image has been received since the last call, The ImagePtr will be a nullptr.

Returns
ImagePtr to an Image or a nullptr

Definition at line 87 of file client.cpp.

◆ nextImage() [2/2]

bool rgbd::Client::nextImage ( Image image)

Get a new Image. If no new image has been received since the last call, no image will be written and false will be returned.

Parameters
imageImage reference which will be written.
Returns
valid image written

Definition at line 76 of file client.cpp.

◆ subHostsThreadFunc()

void rgbd::Client::subHostsThreadFunc ( const float  frequency)
protected

Definition at line 109 of file client.cpp.

Member Data Documentation

◆ cb_queue_

ros::CallbackQueue rgbd::Client::cb_queue_
protected

Definition at line 91 of file client.h.

◆ client_impl_mode_

ClientImplMode rgbd::Client::client_impl_mode_
protected

Definition at line 101 of file client.h.

◆ client_rgbd_

ClientRGBD rgbd::Client::client_rgbd_
protected

Definition at line 86 of file client.h.

◆ client_shm_

ClientSHM rgbd::Client::client_shm_
protected

Definition at line 88 of file client.h.

◆ hostname_

std::string rgbd::Client::hostname_
protected

Definition at line 94 of file client.h.

◆ last_time_shm_server_online_

ros::WallTime rgbd::Client::last_time_shm_server_online_
protected

Definition at line 97 of file client.h.

◆ nh_

std::unique_ptr<ros::NodeHandle> rgbd::Client::nh_
protected

Definition at line 90 of file client.h.

◆ server_name_

std::string rgbd::Client::server_name_
protected

Definition at line 95 of file client.h.

◆ sub_hosts_thread_

std::thread rgbd::Client::sub_hosts_thread_
protected

Definition at line 99 of file client.h.

◆ sub_shm_hosts_

ros::Subscriber rgbd::Client::sub_shm_hosts_
protected

Definition at line 92 of file client.h.

◆ switch_impl_mutex_

std::mutex rgbd::Client::switch_impl_mutex_
protected

Definition at line 102 of file client.h.


The documentation for this class was generated from the following files: