#include <opencv_cam_node.h>
Classes | |
| class | CvCaptureInfo |
Public Member Functions | |
| void | capture () |
| double | frequency () |
| void | init () |
| OpenCvCam (ros::NodeHandle &n) | |
| void | publishCamera () |
| void | show () |
| ~OpenCvCam () | |
Private Member Functions | |
| void | readParam () |
Private Attributes | |
| sensor_msgs::Image | cameraImage_ |
| sensor_msgs::CameraInfo | cameraInfo_ |
| image_transport::CameraPublisher | cameraPublisher_ |
| cv::VideoCapture | cap_ |
| CvCaptureInfo | captureInfo_ |
| double | frequency_ |
| image_transport::ImageTransport | imageTransport_ |
| cv::Mat | img_ |
| ros::NodeHandle | n_ |
| ros::NodeHandle | n_param_ |
| bool | show_camera_image_ |
| int | video_device_ |
Definition at line 32 of file opencv_cam_node.h.
Definition at line 102 of file opencv_cam_node.cpp.
Definition at line 225 of file opencv_cam_node.cpp.
| void OpenCvCam::capture | ( | ) |
Definition at line 198 of file opencv_cam_node.cpp.
| double OpenCvCam::frequency | ( | ) | [inline] |
Definition at line 66 of file opencv_cam_node.h.
| void OpenCvCam::init | ( | ) |
Definition at line 174 of file opencv_cam_node.cpp.
| void OpenCvCam::publishCamera | ( | ) |
Definition at line 211 of file opencv_cam_node.cpp.
| void OpenCvCam::readParam | ( | ) | [private] |
Definition at line 111 of file opencv_cam_node.cpp.
| void OpenCvCam::show | ( | ) |
Definition at line 205 of file opencv_cam_node.cpp.
sensor_msgs::Image OpenCvCam::cameraImage_ [private] |
Definition at line 82 of file opencv_cam_node.h.
sensor_msgs::CameraInfo OpenCvCam::cameraInfo_ [private] |
Definition at line 81 of file opencv_cam_node.h.
Definition at line 80 of file opencv_cam_node.h.
cv::VideoCapture OpenCvCam::cap_ [private] |
Definition at line 84 of file opencv_cam_node.h.
CvCaptureInfo OpenCvCam::captureInfo_ [private] |
Definition at line 86 of file opencv_cam_node.h.
double OpenCvCam::frequency_ [private] |
Definition at line 76 of file opencv_cam_node.h.
Definition at line 79 of file opencv_cam_node.h.
cv::Mat OpenCvCam::img_ [private] |
Definition at line 85 of file opencv_cam_node.h.
ros::NodeHandle OpenCvCam::n_ [private] |
Definition at line 74 of file opencv_cam_node.h.
ros::NodeHandle OpenCvCam::n_param_ [private] |
Definition at line 75 of file opencv_cam_node.h.
bool OpenCvCam::show_camera_image_ [private] |
Definition at line 78 of file opencv_cam_node.h.
int OpenCvCam::video_device_ [private] |
Definition at line 77 of file opencv_cam_node.h.