34 #ifndef RC_VISARD_ROS_GENICAM2ROS_PUBLISHER_H 35 #define RC_VISARD_ROS_GENICAM2ROS_PUBLISHER_H 82 void setNodemap(
const std::shared_ptr<GenApi::CNodeMapRef>& _nodemap)
108 virtual void publish(
const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat) = 0;
116 virtual bool used() = 0;
Interface for all publishers relating to images, point clouds or other stereo-camera data...
virtual void requiresComponents(int &components, bool &color)=0
Adds components and if color images are required to the given values.
static const int ComponentDisparity
std::function< void()> sub_callback
static const int ComponentError
static const int ComponentConfidence
GenICam2RosPublisher & operator=(const GenICam2RosPublisher &)
static const int ComponentIntensity
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
virtual ~GenICam2RosPublisher()
void setNodemap(const std::shared_ptr< GenApi::CNodeMapRef > &_nodemap)
Set nodemap to be used.
virtual void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat)=0
Offers a buffer for publication.
virtual bool used()=0
Returns true if there are subscribers to the topic.
GenICam2RosPublisher(const std::string &_frame_id)
void clearNodemap()
Clear nodemap.
void subChangedIt(const image_transport::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
std::shared_ptr< GenApi::CNodeMapRef > nodemap
static const int ComponentIntensityCombined