#include <confidence_publisher.h>
Definition at line 44 of file confidence_publisher.h.
◆ ConfidencePublisher() [1/2]
rc::ConfidencePublisher::ConfidencePublisher |
( |
ros::NodeHandle & |
nh, |
|
|
const std::string & |
frame_id_prefix |
|
) |
| |
◆ ConfidencePublisher() [2/2]
◆ operator=()
◆ publish()
void rc::ConfidencePublisher::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 53 of file confidence_publisher.cc.
◆ used()
bool rc::ConfidencePublisher::used |
( |
| ) |
|
|
overridevirtual |
◆ pub
◆ seq
uint32_t rc::ConfidencePublisher::seq |
|
private |
The documentation for this class was generated from the following files: