#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, |
|
|
bool |
left, |
|
|
std::function< void()> & |
sub_changed |
|
) |
| |
Initialization of publisher.
- Parameters
-
nh | Node handle. |
left | True for left and false for right camera. |
sub_changed | Function that is called when the subscription changes. |
Definition at line 41 of file camera_info_publisher.cpp.
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. The buffer is already attached to the nodemap for accessing the chunk data. |
part | Part index of image. |
pixelformat | The pixelformat as given by buffer->getPixelFormat(part). |
Implements rc::GenICam2RosPublisher.
Definition at line 125 of file camera_info_publisher.cpp.
void rc::CameraInfoPublisher::requiresComponents |
( |
int & |
components, |
|
|
bool & |
color |
|
) |
| |
|
overridevirtual |
Adds components and if color images are required to the given values.
Nothing will be changed if there are no subscribers, i.e. used() == false.
- Parameters
-
components | Components Flags that will be updated according to the needs of this publisher. |
color | Value that will be updated if this publisher needs color. |
Implements rc::GenICam2RosPublisher.
Definition at line 117 of file camera_info_publisher.cpp.
bool rc::CameraInfoPublisher::used |
( |
| ) |
|
|
overridevirtual |
sensor_msgs::CameraInfo rc::CameraInfoPublisher::info |
|
private |
bool rc::CameraInfoPublisher::left |
|
private |
The documentation for this class was generated from the following files: