39 #include <opencv2/highgui/highgui.hpp> 42 #include <boost/thread.hpp> 43 #include <boost/format.hpp> 51 static void destroyNode(GtkWidget *widget, gpointer data)
58 static void destroyNodelet(GtkWidget *widget, gpointer data)
84 void imageCb(
const sensor_msgs::ImageConstPtr& msg);
86 static void mouseCb(
int event,
int x,
int y,
int flags,
void* param);
110 const std::vector<std::string>& argv =
getMyArgv();
112 std::string transport;
113 local_nh.
param(
"image_transport", transport, std::string(
"raw"));
114 for (
int i = 0; i < (int)argv.size(); ++i)
116 if (argv[i][0] !=
'-')
124 bool shutdown_on_close = std::find(argv.begin(), argv.end(),
125 "--shutdown-on-close") != argv.end();
133 std::string format_string;
134 local_nh.
param(
"filename_format", format_string, std::string(
"frame%04i.jpg"));
139 GtkWidget *widget = GTK_WIDGET( cvGetWindowHandle(
window_name_.c_str()) );
140 if (shutdown_on_close)
141 g_signal_connect(widget,
"destroy", G_CALLBACK(destroyNode), NULL);
143 g_signal_connect(widget,
"destroy", G_CALLBACK(destroyNodelet), &
sub_);
165 bool do_dynamic_scaling = (msg->encoding.find(
"F") != std::string::npos);
175 msg->encoding.c_str(), e.what());
191 boost::function<const std::string&()>
getName =
194 if (event == cv::EVENT_LBUTTONDOWN)
199 if (event != cv::EVENT_RBUTTONDOWN)
202 boost::lock_guard<boost::mutex> guard(this_->
image_mutex_);
212 if (cv::imwrite(filename, image))
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
#define NODELET_INFO_STREAM(...)
boost::mutex image_mutex_
static void mouseCb(int event, int x, int y, int flags, void *param)
const V_string & getMyArgv() const
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
std::string resolveName(const std::string &name, bool remap=true) const
#define NODELET_ERROR_THROTTLE(rate,...)
const std::string & getName() const
boost::format filename_format_
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::Subscriber sub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::NodeHandle & getNodeHandle() const
#define NODELET_WARN_ONCE(...)
#define NODELET_INFO(...)
CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr &source, const std::string &encoding=std::string(), const CvtColorForDisplayOptions options=CvtColorForDisplayOptions())
ROSCPP_DECL void shutdown()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void imageCb(const sensor_msgs::ImageConstPtr &msg)