Public Member Functions | Private Attributes
cv_camera::Capture Class Reference

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

#include <capture.h>

List of all members.

Public Member Functions

 Capture (ros::NodeHandle &node, const std::string &topic_name, int32_t buffer_size, const std::string &frame_id)
 costruct with ros node and topic settings
bool capture ()
 capture an image and store.
const cv::Mat & getCvImage () const
 accessor of cv::Mat
const sensor_msgs::ImagePtr getImageMsgPtr () const
 accessor of ROS Image message.
const sensor_msgs::CameraInfo & getInfo () const
 accessor of CameraInfo.
void open (int32_t device_id)
 Open capture device with device ID.
void open ()
 Open default camera device.
void openFile (const std::string &file_path)
 open video file instead of capture device.
void publish ()
 Publish the image that is already captured by capture().
bool setHeight (int32_t height)
 try capture image height
bool setWidth (int32_t width)
 try capture image width

Private Attributes

cv_bridge::CvImage bridge_
 this stores last captured image.
int32_t buffer_size_
 size of publisher buffer
cv::VideoCapture cap_
 capture device.
std::string frame_id_
 header.frame_id for publishing images.
sensor_msgs::CameraInfo info_
 this stores last captured image info.
camera_info_manager::CameraInfoManager info_manager_
 camera info manager
image_transport::ImageTransport it_
 ROS image transport utility.
ros::NodeHandle node_
 node handle for advertise.
image_transport::CameraPublisher pub_
 image publisher created by image_transport::ImageTransport.
std::string topic_name_
 name of topic without namespace (usually "image_raw").

Detailed Description

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

Definition at line 23 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 
)

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.

Definition at line 9 of file capture.cpp.


Member Function Documentation

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 67 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 94 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 106 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 82 of file capture.h.

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 22 of file capture.cpp.

Open default camera device.

This opens with device 0.

Exceptions:
cv_camera::DeviceErrordevice open failed

Definition at line 42 of file capture.cpp.

void cv_camera::Capture::openFile ( const std::string &  file_path)

open video file instead of capture device.

Definition at line 47 of file capture.cpp.

Publish the image that is already captured by capture().

Definition at line 90 of file capture.cpp.

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

try capture image height

Returns:
true if success

Definition at line 123 of file capture.h.

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

try capture image width

Returns:
true if success

Definition at line 115 of file capture.h.


Member Data Documentation

this stores last captured image.

Definition at line 166 of file capture.h.

size of publisher buffer

Definition at line 151 of file capture.h.

cv::VideoCapture cv_camera::Capture::cap_ [private]

capture device.

Definition at line 161 of file capture.h.

std::string cv_camera::Capture::frame_id_ [private]

header.frame_id for publishing images.

Definition at line 147 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 173 of file capture.h.

camera info manager

Definition at line 178 of file capture.h.

ROS image transport utility.

Definition at line 137 of file capture.h.

node handle for advertise.

Definition at line 132 of file capture.h.

image publisher created by image_transport::ImageTransport.

Definition at line 156 of file capture.h.

std::string cv_camera::Capture::topic_name_ [private]

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

Definition at line 142 of file capture.h.


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


cv_camera
Author(s): Takashi Ogura
autogenerated on Wed Aug 26 2015 11:13:42