Go to the documentation of this file.00001 #include <ros/ros.h>
00002
00003 #include <geometry_msgs/PointStamped.h>
00004 #include <opencv/cv.h>
00005 #include <opencv2/imgproc/imgproc.hpp>
00006 #include <opencv2/highgui/highgui.hpp>
00007 #include <image_transport/image_transport.h>
00008 #include <cv_bridge/cv_bridge.h>
00009 #include <sensor_msgs/image_encodings.h>
00010
00011 namespace hrl_clickable_world {
00012
00013 class ClickableDisplay {
00014 public:
00015 ros::NodeHandle nh, nh_priv;
00016 image_transport::ImageTransport img_trans;
00017 image_transport::Subscriber camera_sub;
00018 ros::Publisher l_click_pub, r_click_pub;
00019 std::string img_frame;
00020 cv_bridge::CvImagePtr img_ptr;
00021 bool have_img;
00022
00023 ClickableDisplay();
00024 ~ClickableDisplay();
00025 void onInit();
00026 void imgCallback(const sensor_msgs::ImageConstPtr& img_msg);
00027 void showImg();
00028 static void mouseClickCallback(int event, int x, int y, int flags, void* data);
00029
00030 };
00031
00032 ClickableDisplay::ClickableDisplay() : nh_priv("~"),
00033 img_trans(nh),
00034 have_img(false) {
00035 }
00036
00037 void ClickableDisplay::onInit() {
00038 cv::namedWindow("Clickable World", 1);
00039 cv::setMouseCallback("Clickable World", &ClickableDisplay::mouseClickCallback, this);
00040
00041 camera_sub = img_trans.subscribe<ClickableDisplay>
00042 ("image", 1,
00043 &ClickableDisplay::imgCallback, this);
00044 l_click_pub = nh_priv.advertise<geometry_msgs::PointStamped>("l_mouse_click", 1);
00045 r_click_pub = nh_priv.advertise<geometry_msgs::PointStamped>("r_mouse_click", 1);
00046
00047 ROS_INFO("[clickable_display] ClickableDisplay loaded.");
00048 ros::Duration(1).sleep();
00049 }
00050
00051 void ClickableDisplay::imgCallback(const sensor_msgs::ImageConstPtr& img_msg) {
00052 img_frame = img_msg->header.frame_id;
00053 try {
00054 img_ptr = cv_bridge::toCvCopy(img_msg, sensor_msgs::image_encodings::BGR8);
00055 have_img = true;
00056 }
00057 catch(cv_bridge::Exception& e) {
00058 ROS_ERROR("[clickable_display] cv_bridge exception: %s", e.what());
00059 return;
00060 }
00061 }
00062
00063 void ClickableDisplay::showImg() {
00064 ros::Rate r(30);
00065 while(ros::ok()) {
00066 ros::spinOnce();
00067 if(have_img) {
00068 cv::imshow("Clickable World", img_ptr->image);
00069 cv::waitKey(3);
00070 }
00071 r.sleep();
00072 }
00073 }
00074
00075 void ClickableDisplay::mouseClickCallback(int event, int x, int y, int flags, void* param) {
00076 ClickableDisplay* this_ = reinterpret_cast<ClickableDisplay*>(param);
00077 if(event == CV_EVENT_LBUTTONDOWN) {
00078 geometry_msgs::PointStamped click_pt;
00079 click_pt.header.frame_id = this_->img_frame;
00080 click_pt.header.stamp = ros::Time::now();
00081 click_pt.point.x = x; click_pt.point.y = y;
00082 this_->l_click_pub.publish(click_pt);
00083 }
00084 if(event == CV_EVENT_RBUTTONDOWN) {
00085 geometry_msgs::PointStamped click_pt;
00086 click_pt.header.frame_id = this_->img_frame;
00087 click_pt.header.stamp = ros::Time::now();
00088 click_pt.point.x = x; click_pt.point.y = y;
00089 this_->r_click_pub.publish(click_pt);
00090 }
00091 }
00092
00093 ClickableDisplay::~ClickableDisplay() {
00094 cv::destroyWindow("Clickable World");
00095 }
00096
00097 };
00098
00099
00100 using namespace hrl_clickable_world;
00101
00102 int main(int argc, char **argv)
00103 {
00104 ros::init(argc, argv, "clickable_display");
00105 ClickableDisplay cd;
00106 cd.onInit();
00107 cd.showImg();
00108 ros::spin();
00109 return 0;
00110 }