39 #include <image_publisher/ImagePublisherConfig.h>
41 #include <sensor_msgs/CameraInfo.h>
43 #include <opencv2/highgui/highgui.hpp>
44 #include <dynamic_reconfigure/server.h>
45 #include <boost/assign.hpp>
46 using namespace boost::assign;
51 typedef dynamic_reconfigure::Server<image_publisher::ImagePublisherConfig>
ReconfigureServer;
73 frame_id_ = new_config.frame_id;
78 if ( !new_config.camera_info_url.empty() ) {
83 }
catch(cv::Exception &e) {
84 NODELET_ERROR(
"camera calibration failed to load: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
96 if ( cap_.isOpened() ) {
97 if ( ! cap_.read(image_) ) {
98 cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
102 cv::flip(image_, image_, flip_value_);
105 out_img->header.frame_id = frame_id_;
107 camera_info_.header.frame_id = out_img->header.frame_id;
108 camera_info_.header.stamp = out_img->header.stamp;
110 pub_.
publish(*out_img, camera_info_);
112 catch (cv::Exception &e)
114 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
131 subscriber_count_ = 0;
132 nh_ = getPrivateNodeHandle();
136 nh_.
param(
"filename", filename_, std::string(
""));
137 NODELET_INFO(
"File name for publishing image is : %s", filename_.c_str());
139 image_ = cv::imread(filename_, cv::IMREAD_COLOR);
140 if ( image_.empty() ) {
142 int num = boost::lexical_cast<int>(filename_);
144 }
catch(boost::bad_lexical_cast &) {
145 cap_.open(filename_);
147 CV_Assert(cap_.isOpened());
149 cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
151 CV_Assert(!image_.empty());
153 catch (cv::Exception &e)
155 NODELET_ERROR(
"Failed to load image (%s): %s %s %s %i", filename_.c_str(), e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
158 bool flip_horizontal;
159 nh_.
param(
"flip_horizontal", flip_horizontal,
false);
160 NODELET_INFO(
"Flip horizontal image is : %s", ((flip_horizontal)?
"true":
"false"));
163 nh_.
param(
"flip_vertical", flip_vertical,
false);
164 NODELET_INFO(
"Flip flip_vertical image is : %s", ((flip_vertical)?
"true":
"false"));
169 if (flip_horizontal && flip_vertical)
171 else if (flip_horizontal)
173 else if (flip_vertical)
178 camera_info_.width = image_.cols;
179 camera_info_.height = image_.rows;
180 camera_info_.distortion_model =
"plumb_bob";
181 camera_info_.D = list_of(0)(0)(0)(0)(0).convert_to_container<std::vector<double> >();
182 camera_info_.K = list_of(1)(0)(camera_info_.width/2)(0)(1)(camera_info_.height/2)(0)(0)(1);
183 camera_info_.R = list_of(1)(0)(0)(0)(1)(0)(0)(0)(1);
184 camera_info_.P = list_of(1)(0)(camera_info_.width/2)(0)(0)(1)(camera_info_.height/2)(0)(0)(0)(1)(0);
189 ReconfigureServer::CallbackType
f =
190 boost::bind(&ImagePublisherNodelet::reconfigureCallback,
this, boost::placeholders::_1, boost::placeholders::_2);