34 #include <image_view/ImageViewConfig.h>
39 #include <dynamic_reconfigure/server.h>
42 #include <opencv2/highgui/highgui.hpp>
45 #include <boost/bind/bind.hpp>
46 #include <boost/thread.hpp>
47 #include <boost/format.hpp>
59 void set(
const cv::Mat& image);
68 boost::unique_lock<boost::mutex> lock(
mutex_);
75 boost::unique_lock<boost::mutex> lock(
mutex_);
83 boost::unique_lock<boost::mutex> lock(
mutex_);
109 dynamic_reconfigure::Server<image_view::ImageViewConfig>
srv_;
117 void reconfigureCb(image_view::ImageViewConfig &config, uint32_t level);
119 void imageCb(
const sensor_msgs::ImageConstPtr& msg);
121 static void mouseCb(
int event,
int x,
int y,
int flags,
void* param);
132 : filename_format_(
""), count_(0)
151 const std::vector<std::string>& argv =
getMyArgv();
153 std::string transport;
154 local_nh.
param(
"image_transport", transport, std::string(
"raw"));
155 for (
int i = 0; i < (int)argv.size(); ++i)
157 if (argv[i][0] !=
'-')
165 bool shutdown_on_close = std::find(argv.begin(), argv.end(),
166 "--shutdown-on-close") != argv.end();
174 std::string format_string;
175 local_nh.
param(
"filename_format", format_string, std::string(
"frame%04i.jpg"));
185 dynamic_reconfigure::Server<image_view::ImageViewConfig>::CallbackType
f =
201 bool do_dynamic_scaling;
202 if (msg->encoding.find(
"F") != std::string::npos) {
203 do_dynamic_scaling =
true;
220 if (msg->encoding ==
"32FC1") {
222 }
else if (msg->encoding ==
"16UC1") {
234 msg->encoding.c_str(), e.what());
245 boost::function<
const std::string&()>
getName =
248 if (event == cv::EVENT_LBUTTONDOWN)
253 if (event != cv::EVENT_RBUTTONDOWN)
256 cv::Mat image(this_->shown_image_.get());
266 filename = (this_->filename_format_ % this_->count_).str();
268 catch (
const boost::io::too_many_args&)
305 catch (
const boost::thread_interrupted&)
309 cv::destroyAllWindows();