captures by cv::VideoCapture and publishes to ROS topic. More...
#include <capture.h>
Public Member Functions | |
Capture (ros::NodeHandle &node, const std::string &topic_name, int32_t buffer_size, const std::string &frame_id, const std::string &camera_name) | |
costruct with ros node and topic settings More... | |
bool | capture () |
capture an image and store. More... | |
const cv::Mat & | getCvImage () const |
accessor of cv::Mat More... | |
const sensor_msgs::ImagePtr | getImageMsgPtr () const |
accessor of ROS Image message. More... | |
const sensor_msgs::CameraInfo & | getInfo () const |
accessor of CameraInfo. More... | |
void | loadCameraInfo () |
Load camera info from file. More... | |
void | open (int32_t device_id) |
Open capture device with device ID. More... | |
void | open (const std::string &device_path) |
Open capture device with device name. More... | |
void | open () |
Open default camera device. More... | |
void | openFile (const std::string &file_path) |
open video file instead of capture device. More... | |
void | publish () |
Publish the image that is already captured by capture(). More... | |
bool | setHeight (int32_t height) |
try capture image height More... | |
bool | setPropertyFromParam (int property_id, const std::string ¶m_name) |
set CV_PROP_* More... | |
bool | setWidth (int32_t width) |
try capture image width More... | |
Private Member Functions | |
void | rescaleCameraInfo (int width, int height) |
rescale camera calibration to another resolution More... | |
Private Attributes | |
cv_bridge::CvImage | bridge_ |
this stores last captured image. More... | |
int32_t | buffer_size_ |
size of publisher buffer More... | |
cv::VideoCapture | cap_ |
capture device. More... | |
ros::Duration | capture_delay_ |
capture_delay param value More... | |
std::string | frame_id_ |
header.frame_id for publishing images. More... | |
sensor_msgs::CameraInfo | info_ |
this stores last captured image info. More... | |
camera_info_manager::CameraInfoManager | info_manager_ |
camera info manager More... | |
image_transport::ImageTransport | it_ |
ROS image transport utility. More... | |
ros::NodeHandle | node_ |
node handle for advertise. More... | |
image_transport::CameraPublisher | pub_ |
image publisher created by image_transport::ImageTransport. More... | |
bool | rescale_camera_info_ |
rescale_camera_info param value More... | |
std::string | topic_name_ |
name of topic without namespace (usually "image_raw"). More... | |
cv_camera::Capture::Capture | ( | ros::NodeHandle & | node, |
const std::string & | topic_name, | ||
int32_t | buffer_size, | ||
const std::string & | frame_id, | ||
const std::string & | camera_name | ||
) |
costruct with ros node and topic settings
node | ROS node handle for advertise topic. |
topic_name | name of topic to publish (this may be image_raw). |
buffer_size | size of publisher buffer. |
frame_id | frame_id of publishing messages. |
camera_name | camera name for camera_info_manager. |
Definition at line 12 of file capture.cpp.
bool cv_camera::Capture::capture | ( | ) |
capture an image and store.
to publish the captured image, call publish();
Definition at line 131 of file capture.cpp.
|
inline |
|
inline |
|
inline |
void cv_camera::Capture::loadCameraInfo | ( | ) |
Load camera info from file.
This loads the camera info from the file specified in the camera_info_url parameter.
Definition at line 25 of file capture.cpp.
void cv_camera::Capture::open | ( | int32_t | device_id | ) |
Open capture device with device ID.
device_id | id of camera device (number from 0) |
cv_camera::DeviceError | device open failed |
Definition at line 79 of file capture.cpp.
void cv_camera::Capture::open | ( | const std::string & | device_path | ) |
Open capture device with device name.
device_path | path of the camera device |
cv_camera::DeviceError | device open failed |
Definition at line 93 of file capture.cpp.
void cv_camera::Capture::open | ( | ) |
Open default camera device.
This opens with device 0.
cv_camera::DeviceError | device open failed |
Definition at line 105 of file capture.cpp.
void cv_camera::Capture::openFile | ( | const std::string & | file_path | ) |
open video file instead of capture device.
Definition at line 110 of file capture.cpp.
void cv_camera::Capture::publish | ( | ) |
Publish the image that is already captured by capture().
Definition at line 171 of file capture.cpp.
|
private |
rescale camera calibration to another resolution
Definition at line 60 of file capture.cpp.
|
inline |
bool cv_camera::Capture::setPropertyFromParam | ( | int | property_id, |
const std::string & | param_name | ||
) |
|
inline |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
image publisher created by image_transport::ImageTransport.
|
private |
|
private |