#include <camera_info_publisher.h>
Definition at line 44 of file camera_info_publisher.h.
rc::CameraInfoPublisher::CameraInfoPublisher |
( |
ros::NodeHandle & |
nh, |
|
|
const std::string & |
frame_id_prefix, |
|
|
double |
f, |
|
|
double |
t, |
|
|
bool |
left |
|
) |
| |
Initialization of publisher.
- Parameters
-
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 40 of file camera_info_publisher.cc.
void rc::CameraInfoPublisher::publish |
( |
const rcg::Buffer * |
buffer, |
|
|
uint32_t |
part, |
|
|
uint64_t |
pixelformat |
|
) |
| |
|
overridevirtual |
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.
- Parameters
-
buffer | Buffer with data to be published. |
part | Part index of image. |
pixelformat | The pixelformat as given by buffer.getPixelFormat(). |
Implements rc::GenICam2RosPublisher.
Definition at line 110 of file camera_info_publisher.cc.
bool rc::CameraInfoPublisher::used |
( |
| ) |
|
|
overridevirtual |
float rc::CameraInfoPublisher::f |
|
private |
sensor_msgs::CameraInfo rc::CameraInfoPublisher::info |
|
private |
float rc::CameraInfoPublisher::p3_factor |
|
private |
The documentation for this class was generated from the following files: