8 const double DEFAULT_RATE = 30.0;
9 const int32_t PUBLISHER_BUFFER_SIZE = 1;
16 : private_node_(private_node),
17 camera_node_(camera_node)
23 double hz(DEFAULT_RATE);
25 std::string device_path(
"");
26 std::string frame_id(
"camera");
27 std::string file_path(
"");
28 std::string camera_name(
"");
35 camera_name = frame_id;
38 int32_t image_width(640);
39 int32_t image_height(480);
43 PUBLISHER_BUFFER_SIZE,
61 if (!
camera_->setWidth(image_width))
68 if (!
camera_->setHeight(image_height))
70 ROS_WARN(
"fail to set image_height");
74 camera_->setPropertyFromParam(cv::CAP_PROP_POS_MSEC,
"cv_cap_prop_pos_msec");
75 camera_->setPropertyFromParam(cv::CAP_PROP_POS_AVI_RATIO,
"cv_cap_prop_pos_avi_ratio");
76 camera_->setPropertyFromParam(cv::CAP_PROP_FRAME_WIDTH,
"cv_cap_prop_frame_width");
77 camera_->setPropertyFromParam(cv::CAP_PROP_FRAME_HEIGHT,
"cv_cap_prop_frame_height");
78 camera_->setPropertyFromParam(cv::CAP_PROP_FPS,
"cv_cap_prop_fps");
79 camera_->setPropertyFromParam(cv::CAP_PROP_FOURCC,
"cv_cap_prop_fourcc");
80 camera_->setPropertyFromParam(cv::CAP_PROP_FRAME_COUNT,
"cv_cap_prop_frame_count");
81 camera_->setPropertyFromParam(cv::CAP_PROP_FORMAT,
"cv_cap_prop_format");
82 camera_->setPropertyFromParam(cv::CAP_PROP_MODE,
"cv_cap_prop_mode");
83 camera_->setPropertyFromParam(cv::CAP_PROP_BRIGHTNESS,
"cv_cap_prop_brightness");
84 camera_->setPropertyFromParam(cv::CAP_PROP_CONTRAST,
"cv_cap_prop_contrast");
85 camera_->setPropertyFromParam(cv::CAP_PROP_SATURATION,
"cv_cap_prop_saturation");
86 camera_->setPropertyFromParam(cv::CAP_PROP_HUE,
"cv_cap_prop_hue");
87 camera_->setPropertyFromParam(cv::CAP_PROP_GAIN,
"cv_cap_prop_gain");
88 camera_->setPropertyFromParam(cv::CAP_PROP_EXPOSURE,
"cv_cap_prop_exposure");
89 camera_->setPropertyFromParam(cv::CAP_PROP_CONVERT_RGB,
"cv_cap_prop_convert_rgb");
91 camera_->setPropertyFromParam(cv::CAP_PROP_RECTIFICATION,
"cv_cap_prop_rectification");
92 camera_->setPropertyFromParam(cv::CAP_PROP_ISO_SPEED,
"cv_cap_prop_iso_speed");
93 camera_->setPropertyFromParam(cv::CAP_PROP_WHITE_BALANCE_BLUE_U,
"cv_cap_prop_white_balance_u");
94 camera_->setPropertyFromParam(cv::CAP_PROP_WHITE_BALANCE_RED_V,
"cv_cap_prop_white_balance_v");
95 camera_->setPropertyFromParam(cv::CAP_PROP_BUFFERSIZE,
"cv_cap_prop_buffersize");
boost::shared_ptr< ros::Rate > rate_
publishing rate.
ros::NodeHandle camera_node_
ROS private node for publishing images.
ros::NodeHandle private_node_
ROS private node for getting ROS parameters.
captures by cv::VideoCapture and publishes to ROS topic.
Driver(ros::NodeHandle &private_node, ros::NodeHandle &camera_node)
construct with ROS node handles.
namespace of this package
void proceed()
Capture, publish and sleep.
boost::shared_ptr< Capture > camera_
wrapper of cv::VideoCapture.
bool getParam(const std::string &key, std::string &s) const
void setup()
Setup camera device and ROS parameters.