39 #include <dynamic_reconfigure/server.h>
42 #include <opencv2/highgui/highgui.hpp>
43 #include <opencv2/imgproc/imgproc.hpp>
47 #include <boost/filesystem.hpp>
48 #include <boost/assign/list_of.hpp>
49 #include <boost/thread/thread.hpp>
52 #include <video_stream_opencv/VideoStreamConfig.h>
54 namespace fs = boost::filesystem;
91 cam_info_msg.K = boost::assign::list_of(img->width/2.0) (0.0) (img->width/2.0)
92 (0.0) (img->height/2.0) (img->height/2.0)
95 cam_info_msg.R = boost::assign::list_of (1.0) (0.0) (0.0)
99 cam_info_msg.P = boost::assign::list_of (img->width/2.0) (0.0) (img->width/2.0) (0.0)
100 (0.0) (img->height/2.0) (img->height/2.0) (0.0)
101 (0.0) (0.0) (1.0) (0.0);
109 VideoStreamConfig latest_config =
config;
110 ros::Rate camera_fps_rate(latest_config.set_camera_fps);
112 int frame_counter = 0;
117 std::lock_guard<std::mutex> lock(
c_mutex);
120 if (!
cap->isOpened()) {
127 if (latest_config.reopen_on_read_failure) {
137 camera_fps_rate.
sleep();
139 NODELET_DEBUG_STREAM(
"Current frame_counter: " << frame_counter <<
" latest_config.stop_frame - latest_config.start_frame: " << latest_config.stop_frame - latest_config.start_frame);
141 frame_counter >= latest_config.stop_frame - latest_config.start_frame)
143 if (latest_config.loop_videofile)
146 cap->set(cv::CAP_PROP_POS_FRAMES, latest_config.start_frame);
157 std::lock_guard<std::mutex> g(
q_mutex);
159 while (
framesQueue.size() >= latest_config.buffer_queue_size) {
169 bool is_new_image =
false;
170 sensor_msgs::ImagePtr msg;
172 VideoStreamConfig latest_config;
175 std::lock_guard<std::mutex> lock(
p_mutex);
179 header.frame_id = latest_config.frame_id;
181 std::lock_guard<std::mutex> g(
q_mutex);
190 if(!
frame.empty() && is_new_image) {
194 if (latest_config.flip_horizontal && latest_config.flip_vertical)
196 else if (latest_config.flip_horizontal)
198 else if (latest_config.flip_vertical)
201 boost::make_shared<cv_bridge::CvImage>(
header,
"bgr8",
frame);
202 if (latest_config.output_encoding !=
"bgr8")
207 }
catch (std::runtime_error &ex) {
209 <<
": " << ex.what());
212 msg = cv_image->toImageMsg();
215 NODELET_WARN_STREAM(
"No calibration file given, publishing a reasonable default camera info.");
225 VideoStreamConfig& latest_config =
config;
228 *
nh, latest_config.camera_name, latest_config.camera_info_url);
234 cap.reset(
new cv::VideoCapture);
238 cap->open(device_num);
239 }
catch (std::invalid_argument &ex) {
246 if(latest_config.stop_frame == -1)
248 NODELET_WARN_STREAM(
"'stop_frame' set to -1, setting internally (won't be shown in dynamic_reconfigure) to last frame: " <<
cap->get(cv::CAP_PROP_FRAME_COUNT));
249 latest_config.stop_frame =
cap->get(cv::CAP_PROP_FRAME_COUNT);
251 if(latest_config.stop_frame >
cap->get(cv::CAP_PROP_FRAME_COUNT))
253 NODELET_ERROR_STREAM(
"Invalid 'stop_frame' " << latest_config.stop_frame <<
" for video which has " <<
cap->get(cv::CAP_PROP_FRAME_COUNT) <<
" frames. Setting internally (won't be shown in dynamic_reconfigure) 'stop_frame' to " <<
cap->get(cv::CAP_PROP_FRAME_COUNT));
254 latest_config.stop_frame =
cap->get(cv::CAP_PROP_FRAME_COUNT);
257 if(latest_config.start_frame >= latest_config.stop_frame)
259 NODELET_ERROR_STREAM(
"Invalid 'start_frame' " << latest_config.start_frame <<
", which exceeds 'stop_frame' " << latest_config.stop_frame <<
". Setting internally (won't be shown in dynamic_reconfigure) 'start_frame' to 0.");
260 latest_config.start_frame = 0;
263 cap->set(cv::CAP_PROP_POS_FRAMES, latest_config.start_frame);
265 if (!
cap->isOpened()) {
272 double reported_camera_fps;
275 reported_camera_fps =
cap->get(cv::CAP_PROP_FPS);
276 if (reported_camera_fps > 0.0)
281 cap->set(cv::CAP_PROP_FPS, latest_config.set_camera_fps);
282 if(!
cap->isOpened()){
286 if (latest_config.width != 0 && latest_config.height != 0){
287 cap->set(cv::CAP_PROP_FRAME_WIDTH, latest_config.width);
288 cap->set(cv::CAP_PROP_FRAME_HEIGHT, latest_config.height);
291 cap->set(cv::CAP_PROP_BRIGHTNESS, latest_config.brightness);
292 cap->set(cv::CAP_PROP_CONTRAST, latest_config.contrast);
293 cap->set(cv::CAP_PROP_HUE, latest_config.hue);
294 cap->set(cv::CAP_PROP_SATURATION, latest_config.saturation);
296 if (latest_config.auto_exposure) {
297 cap->set(cv::CAP_PROP_AUTO_EXPOSURE, 0.75);
298 latest_config.exposure = 0.5;
300 cap->set(cv::CAP_PROP_AUTO_EXPOSURE, 0.25);
301 cap->set(cv::CAP_PROP_EXPOSURE, latest_config.exposure);
309 }
catch (std::exception& e) {
323 std::lock_guard<std::mutex> lock(
s_mutex);
331 std::lock_guard<std::mutex> lock(
s_mutex);
332 bool always_subscribe =
false;
333 pnh->getParamCached(
"always_subscribe", always_subscribe);
363 if (new_config.fps > new_config.set_camera_fps) {
365 "Asked to publish at 'fps' (" << new_config.fps
366 <<
") which is higher than the 'set_camera_fps' (" << new_config.set_camera_fps <<
367 "), we can't publish faster than the camera provides images.");
368 new_config.fps = new_config.set_camera_fps;
372 std::lock_guard<std::mutex> c_lock(
c_mutex);
373 std::lock_guard<std::mutex> p_lock(
p_mutex);
383 NODELET_INFO_STREAM(
"Setting buffer size for capturing frames to: " << new_config.buffer_queue_size);
384 NODELET_INFO_STREAM(
"Flip horizontal image is: " << ((new_config.flip_horizontal)?
"true":
"false"));
385 NODELET_INFO_STREAM(
"Flip vertical image is: " << ((new_config.flip_vertical)?
"true":
"false"));
389 if (new_config.width != 0 && new_config.height != 0)
398 NODELET_DEBUG(
"New dynamic_reconfigure config received on a parameter with configure level 1, unsubscribing and subscribing");
415 }
catch (std::invalid_argument &ex) {
429 case fs::file_type::character_file:
430 case fs::file_type::block_file:
433 case fs::file_type::regular_file:
443 dyn_srv = boost::make_shared<dynamic_reconfigure::Server<VideoStreamConfig> >(*pnh);
458 connect_cb, disconnect_cb,
459 info_connect_cb, info_disconnect_cb,