#include <camera_info_publisher.h>
Definition at line 45 of file camera_info_publisher.h.
◆ CameraInfoPublisher() [1/2]
rcgccam::CameraInfoPublisher::CameraInfoPublisher |
( |
| ) |
|
◆ CameraInfoPublisher() [2/2]
◆ init()
void rcgccam::CameraInfoPublisher::init |
( |
ros::NodeHandle & |
nh, |
|
|
const char * |
calib_file, |
|
|
int |
id |
|
) |
| |
Initialization of publisher.
- Parameters
-
nh | Node handle. |
calib_file | Path and name of calibration file. The topic is not advertised and nothing is published if the calibration cannot be loaded from this file. |
id | Camera ID, i.e. < 0 for no ID, 0 for left and 1 for right camera. |
Definition at line 343 of file camera_info_publisher.cc.
◆ operator=()
◆ publish()
void rcgccam::CameraInfoPublisher::publish |
( |
const sensor_msgs::ImagePtr & |
image | ) |
|
◆ used()
bool rcgccam::CameraInfoPublisher::used |
( |
| ) |
|
◆ info_
sensor_msgs::CameraInfo rcgccam::CameraInfoPublisher::info_ |
|
private |
◆ pub_
The documentation for this class was generated from the following files: