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) | |
| 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"). | |
| 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
| 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. |
Definition at line 9 of file capture.cpp.
| bool cv_camera::Capture::capture | ( | ) |
capture an image and store.
to publish the captured image, call publish();
Definition at line 67 of file capture.cpp.
| const cv::Mat& cv_camera::Capture::getCvImage | ( | ) | const [inline] |
| const sensor_msgs::ImagePtr cv_camera::Capture::getImageMsgPtr | ( | ) | const [inline] |
| const sensor_msgs::CameraInfo& cv_camera::Capture::getInfo | ( | ) | const [inline] |
| 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 22 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 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.
| void cv_camera::Capture::publish | ( | ) |
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] |
| bool cv_camera::Capture::setWidth | ( | int32_t | width | ) | [inline] |
int32_t cv_camera::Capture::buffer_size_ [private] |
cv::VideoCapture cv_camera::Capture::cap_ [private] |
std::string cv_camera::Capture::frame_id_ [private] |
sensor_msgs::CameraInfo cv_camera::Capture::info_ [private] |
ros::NodeHandle cv_camera::Capture::node_ [private] |
image publisher created by image_transport::ImageTransport.
std::string cv_camera::Capture::topic_name_ [private] |