$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00036 00037 #include <ros/ros.h> 00038 #include <boost/thread/mutex.hpp> 00039 00040 #include <calibration_msgs/CalibrationPattern.h> 00041 #include <sensor_msgs/Image.h> 00042 #include <cv_bridge/CvBridge.h> 00043 #include <opencv/cv.h> 00044 #include <message_filters/time_synchronizer.h> 00045 #include <message_filters/subscriber.h> 00046 00047 namespace laser_cb_detector 00048 { 00049 00050 class ImageAnnotator 00051 { 00052 public: 00053 ImageAnnotator(); 00054 00055 void processPair(const sensor_msgs::ImageConstPtr& image, const calibration_msgs::CalibrationPatternConstPtr& features); 00056 private: 00057 ros::Publisher image_pub_; 00058 ros::NodeHandle n_; 00059 00060 sensor_msgs::CvBridge bridge_; 00061 00062 // Params 00063 int marker_size_; 00064 double scaling_; 00065 }; 00066 00067 } 00068 00069 using namespace laser_cb_detector; 00070 00071 ImageAnnotator::ImageAnnotator() 00072 { 00073 image_pub_ = n_.advertise<sensor_msgs::Image>("annotated", 1); 00074 00075 ros::NodeHandle local_ns_("~"); 00076 00077 local_ns_.param("marker_size", marker_size_, 1); 00078 local_ns_.param("scaling", scaling_, 1.0); 00079 ROS_INFO("[marker_size]: %i", marker_size_); 00080 ROS_INFO("[scaling]: %.3f", scaling_); 00081 } 00082 00083 void ImageAnnotator::processPair(const sensor_msgs::ImageConstPtr& image, const calibration_msgs::CalibrationPatternConstPtr& features) 00084 { 00085 if (bridge_.fromImage(*image, "rgb8")) 00086 { 00087 IplImage* cv_image = bridge_.toIpl(); 00088 00089 // ***** Resize the image based on scaling parameters in config ***** 00090 const int scaled_width = (int) (.5 + image->width * scaling_); 00091 const int scaled_height = (int) (.5 + image->height * scaling_); 00092 IplImage* cv_image_scaled = cvCreateImage(cvSize( scaled_width, scaled_height), 00093 cv_image->depth, 00094 cv_image->nChannels); 00095 cvResize(cv_image, cv_image_scaled, CV_INTER_LINEAR); 00096 00097 if (features->success) 00098 { 00099 CvPoint pt0 = cvPoint(features->image_points[0].x*scaling_, 00100 features->image_points[0].y*scaling_); 00101 cvCircle(cv_image_scaled, pt0, marker_size_*2, cvScalar(0,0,255), 1) ; 00102 for (unsigned int i=0; i<features->image_points.size(); i++) 00103 { 00104 CvPoint pt = cvPoint(features->image_points[i].x*scaling_, 00105 features->image_points[i].y*scaling_); 00106 cvCircle(cv_image_scaled, pt, marker_size_, cvScalar(0,255,0), 1) ; 00107 } 00108 } 00109 else 00110 { 00111 for (unsigned int i=0; i<features->image_points.size(); i++) 00112 { 00113 CvPoint pt = cvPoint(features->image_points[i].x*scaling_, 00114 features->image_points[i].y*scaling_); 00115 cvCircle(cv_image_scaled, pt, marker_size_, cvScalar(0,0,255), 1) ; 00116 } 00117 } 00118 00119 // Send the annotated image over ROS 00120 sensor_msgs::Image result_image; 00121 bridge_.fromIpltoRosImage(cv_image_scaled, result_image); 00122 result_image.header.frame_id = image->header.frame_id; 00123 result_image.header.stamp = image->header.stamp; 00124 image_pub_.publish(result_image); 00125 cvReleaseImage(&cv_image_scaled); 00126 } 00127 else 00128 ROS_WARN("Error converting image with CvBridge"); 00129 00130 } 00131 00132 int main(int argc, char** argv) 00133 { 00134 ros::init(argc, argv, "image_annotator"); 00135 00136 ros::NodeHandle nh; 00137 00138 ImageAnnotator annotator; 00139 00140 message_filters::Subscriber<sensor_msgs::Image> image_sub(nh, "image", 1); 00141 message_filters::Subscriber<calibration_msgs::CalibrationPattern> features_sub(nh, "features", 1); 00142 message_filters::TimeSynchronizer<sensor_msgs::Image, 00143 calibration_msgs::CalibrationPattern> sync(image_sub, features_sub, 5); 00144 00145 sync.registerCallback(boost::bind(&ImageAnnotator::processPair, &annotator, _1, _2)); 00146 00147 ros::spin(); 00148 return 0; 00149 }