Public Member Functions | Private Member Functions | Private Attributes | List of all members
cv_camera::Capture Class Reference

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 &param_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...
 

Detailed Description

captures by cv::VideoCapture and publishes to ROS topic.

Definition at line 27 of file capture.h.

Constructor & Destructor Documentation

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

Parameters
nodeROS node handle for advertise topic.
topic_namename of topic to publish (this may be image_raw).
buffer_sizesize of publisher buffer.
frame_idframe_id of publishing messages.
camera_namecamera name for camera_info_manager.

Definition at line 12 of file capture.cpp.

Member Function Documentation

bool cv_camera::Capture::capture ( )

capture an image and store.

to publish the captured image, call publish();

Returns
true if success to capture, false if not captured.

Definition at line 131 of file capture.cpp.

const cv::Mat& cv_camera::Capture::getCvImage ( ) const
inline

accessor of cv::Mat

you have to call capture() before call this.

Returns
captured cv::Mat

Definition at line 116 of file capture.h.

const sensor_msgs::ImagePtr cv_camera::Capture::getImageMsgPtr ( ) const
inline

accessor of ROS Image message.

you have to call capture() before call this.

Returns
message pointer.

Definition at line 128 of file capture.h.

const sensor_msgs::CameraInfo& cv_camera::Capture::getInfo ( ) const
inline

accessor of CameraInfo.

you have to call capture() before call this.

Returns
CameraInfo

Definition at line 104 of file capture.h.

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.

Parameters
device_idid of camera device (number from 0)
Exceptions
cv_camera::DeviceErrordevice 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.

Parameters
device_pathpath of the camera device
Exceptions
cv_camera::DeviceErrordevice open failed

Definition at line 93 of file capture.cpp.

void cv_camera::Capture::open ( )

Open default camera device.

This opens with device 0.

Exceptions
cv_camera::DeviceErrordevice 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.

void cv_camera::Capture::rescaleCameraInfo ( int  width,
int  height 
)
private

rescale camera calibration to another resolution

Definition at line 60 of file capture.cpp.

bool cv_camera::Capture::setHeight ( int32_t  height)
inline

try capture image height

Returns
true if success

Definition at line 146 of file capture.h.

bool cv_camera::Capture::setPropertyFromParam ( int  property_id,
const std::string &  param_name 
)

set CV_PROP_*

Returns
true if success

Definition at line 176 of file capture.cpp.

bool cv_camera::Capture::setWidth ( int32_t  width)
inline

try capture image width

Returns
true if success

Definition at line 137 of file capture.h.

Member Data Documentation

cv_bridge::CvImage cv_camera::Capture::bridge_
private

this stores last captured image.

Definition at line 200 of file capture.h.

int32_t cv_camera::Capture::buffer_size_
private

size of publisher buffer

Definition at line 185 of file capture.h.

cv::VideoCapture cv_camera::Capture::cap_
private

capture device.

Definition at line 195 of file capture.h.

ros::Duration cv_camera::Capture::capture_delay_
private

capture_delay param value

Definition at line 222 of file capture.h.

std::string cv_camera::Capture::frame_id_
private

header.frame_id for publishing images.

Definition at line 181 of file capture.h.

sensor_msgs::CameraInfo cv_camera::Capture::info_
private

this stores last captured image info.

currently this has image size (width/height) only.

Definition at line 207 of file capture.h.

camera_info_manager::CameraInfoManager cv_camera::Capture::info_manager_
private

camera info manager

Definition at line 212 of file capture.h.

image_transport::ImageTransport cv_camera::Capture::it_
private

ROS image transport utility.

Definition at line 171 of file capture.h.

ros::NodeHandle cv_camera::Capture::node_
private

node handle for advertise.

Definition at line 166 of file capture.h.

image_transport::CameraPublisher cv_camera::Capture::pub_
private

image publisher created by image_transport::ImageTransport.

Definition at line 190 of file capture.h.

bool cv_camera::Capture::rescale_camera_info_
private

rescale_camera_info param value

Definition at line 217 of file capture.h.

std::string cv_camera::Capture::topic_name_
private

name of topic without namespace (usually "image_raw").

Definition at line 176 of file capture.h.


The documentation for this class was generated from the following files:


cv_camera
Author(s): Takashi Ogura
autogenerated on Mon Jun 1 2020 03:55:59