Go to the documentation of this file.    1 #ifndef RGBD_SERVER_ROS_H_ 
    2 #define RGBD_SERVER_ROS_H_ 
    6 #include <ros/node_handle.h> 
    7 #include <ros/publisher.h> 
   23     ServerROS(ros::NodeHandle nh=ros::NodeHandle());
 
   37     void initialize(
std::string ns = 
"", 
const bool publish_rgb = 
false, 
const bool publish_depth = 
false, 
const bool publish_pc = 
false);
 
   58 #endif // RGBD_SERVER_ROS_H_ 
 
std::shared_ptr< ros::Publisher > pub_rgb_img_
virtual ~ServerROS()
Destructor.
ServerROS(ros::NodeHandle nh=ros::NodeHandle())
Constructor.
Server which publishes ROS rgb image, depth image and pointcloud messages.
std::shared_ptr< ros::Publisher > pub_rgb_info_
void send(const Image &image)
Publish a new image to the selected ROS topics.
void initialize(std::string ns="", const bool publish_rgb=false, const bool publish_depth=false, const bool publish_pc=false)
initialize server
std::shared_ptr< ros::Publisher > pub_depth_pc_
std::shared_ptr< ros::Publisher > pub_depth_img_
std::shared_ptr< ros::Publisher > pub_depth_info_