Go to the documentation of this file.
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;
const static int ComponentIntensity
const static int ComponentError
virtual void requiresComponents(int &components, bool &color)=0
Adds components and if color images are required to the given values.
GenICam2RosPublisher & operator=(const GenICam2RosPublisher &)
const static int ComponentConfidence
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
const static int ComponentDisparity
std::function< void()> sub_callback
virtual ~GenICam2RosPublisher()
virtual void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat)=0
Offers a buffer for publication.
Interface for all publishers relating to images, point clouds or other stereo-camera data.
GenICam2RosPublisher(const std::string &_frame_id)
void setNodemap(const std::shared_ptr< GenApi::CNodeMapRef > &_nodemap)
Set nodemap to be used.
void subChangedIt(const image_transport::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
virtual bool used()=0
Returns true if there are subscribers to the topic.
void clearNodemap()
Clear nodemap.
const static int ComponentIntensityCombined
std::shared_ptr< GenApi::CNodeMapRef > nodemap
rc_genicam_driver
Author(s): Heiko Hirschmueller
, Felix Ruess
autogenerated on Sat Oct 26 2024 02:04:09