#include <camera_info_publisher.h>

| Public Member Functions | |
| CameraInfoPublisher (ros::NodeHandle &nh, std::string _frame_id, double f, double t, bool left) | |
| void | publish (const rcg::Buffer *buffer, uint64_t pixelformat) override | 
| bool | used () override | 
| Private Member Functions | |
| CameraInfoPublisher (const CameraInfoPublisher &) | |
| CameraInfoPublisher & | operator= (const CameraInfoPublisher &) | 
| Private Attributes | |
| float | f | 
| sensor_msgs::CameraInfo | info | 
| ros::Publisher | pub | 
Definition at line 45 of file camera_info_publisher.h.
| rc::CameraInfoPublisher::CameraInfoPublisher | ( | ros::NodeHandle & | nh, | 
| std::string | _frame_id, | ||
| double | f, | ||
| double | t, | ||
| bool | left | ||
| ) | 
Initialization of publisher.
| nh | Node handle. | 
| f | Focal length, normalized to image width 1. | 
| t | Baseline in m. | 
| left | True for left and false for right camera. | 
Definition at line 41 of file camera_info_publisher.cc.
| rc::CameraInfoPublisher::CameraInfoPublisher | ( | const CameraInfoPublisher & | ) |  [private] | 
| CameraInfoPublisher& rc::CameraInfoPublisher::operator= | ( | const CameraInfoPublisher & | ) |  [private] | 
| void rc::CameraInfoPublisher::publish | ( | const rcg::Buffer * | buffer, | 
| uint64_t | pixelformat | ||
| ) |  [override, virtual] | 
Offers a buffer for publication. It depends on the the kind of buffer data and the implementation and configuration of the sub-class if the data is published.
| buffer | Buffer with data to be published. | 
| pixelformat | The pixelformat as given by buffer.getPixelFormat(). | 
Implements rc::GenICam2RosPublisher.
Definition at line 89 of file camera_info_publisher.cc.
| bool rc::CameraInfoPublisher::used | ( | ) |  [override, virtual] | 
Returns true if there are subscribers to the topic.
Implements rc::GenICam2RosPublisher.
Definition at line 84 of file camera_info_publisher.cc.
| float rc::CameraInfoPublisher::f  [private] | 
Definition at line 69 of file camera_info_publisher.h.
| sensor_msgs::CameraInfo rc::CameraInfoPublisher::info  [private] | 
Definition at line 71 of file camera_info_publisher.h.
| ros::Publisher rc::CameraInfoPublisher::pub  [private] | 
Definition at line 72 of file camera_info_publisher.h.