driver.h
Go to the documentation of this file.
1 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
2 
3 #ifndef CV_CAMERA_DRIVER_H
4 #define CV_CAMERA_DRIVER_H
5 
6 #include "cv_camera/capture.h"
7 
8 namespace cv_camera
9 {
10 
16 class Driver
17 {
18  public:
28  Driver(ros::NodeHandle& private_node,
29  ros::NodeHandle& camera_node);
30  ~Driver();
31 
37  void setup();
41  void proceed();
42  private:
55 
60 };
61 
62 } // namespace cv_camera
63 
64 #endif // CV_CAMERA_DRIVER_H
cv_camera::Driver::camera_node_
ros::NodeHandle camera_node_
ROS private node for publishing images.
Definition: driver.h:50
capture.h
cv_camera::Driver
ROS cv camera driver.
Definition: driver.h:16
boost::shared_ptr
cv_camera::Driver::rate_
boost::shared_ptr< ros::Rate > rate_
publishing rate.
Definition: driver.h:59
cv_camera::Driver::proceed
void proceed()
Capture, publish and sleep.
Definition: driver.cpp:100
cv_camera
namespace of this package
Definition: capture.h:20
cv_camera::Driver::camera_
boost::shared_ptr< Capture > camera_
wrapper of cv::VideoCapture.
Definition: driver.h:54
cv_camera::Driver::~Driver
~Driver()
Definition: driver.cpp:109
cv_camera::Driver::private_node_
ros::NodeHandle private_node_
ROS private node for getting ROS parameters.
Definition: driver.h:46
cv_camera::Driver::Driver
Driver(ros::NodeHandle &private_node, ros::NodeHandle &camera_node)
construct with ROS node handles.
Definition: driver.cpp:15
cv_camera::Driver::setup
void setup()
Setup camera device and ROS parameters.
Definition: driver.cpp:21
ros::NodeHandle


cv_camera
Author(s): Takashi Ogura
autogenerated on Wed Mar 2 2022 00:09:55