$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 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 PAL Robotics, S.L. 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 * @file detector_node.cpp 00035 * @author Bence Magyar 00036 * @date June 2012 00037 * @version 0.2 00038 * @brief Main file of BLORT detector node for ROS. 00039 */ 00040 00041 #include <ros/ros.h> 00042 #include <opencv2/core/core.hpp> 00043 #include <image_transport/image_transport.h> 00044 #include <cv_bridge/cv_bridge.h> 00045 #include <sensor_msgs/image_encodings.h> 00046 #include <dynamic_reconfigure/server.h> 00047 #include <blort_ros/DetectorConfig.h> 00048 #include <blort_ros/SetCameraInfo.h> 00049 #include "../gldetector.h" 00050 00051 class DetectorNode 00052 { 00053 private: 00054 ros::NodeHandle nh_; 00055 image_transport::ImageTransport it_; 00056 image_transport::Publisher image_pub; 00057 ros::Subscriber cam_info_sub; 00058 const std::string root_; 00059 ros::ServiceServer pose_service; 00060 ros::ServiceServer cam_info_service; 00061 std::auto_ptr<dynamic_reconfigure::Server<blort_ros::DetectorConfig> > server_; 00062 dynamic_reconfigure::Server<blort_ros::DetectorConfig>::CallbackType f_; 00063 blort_ros::GLDetector* detector; 00064 unsigned int counter; 00065 00066 double nn_match_threshold; 00067 int ransac_n_points_to_match; 00068 00069 //uncomment corresponding lines if need debug stuff 00070 //image_transport::Publisher debug_pub; 00071 00072 public: 00073 DetectorNode(std::string root = ".") 00074 : nh_("blort_detector"), it_(nh_), root_(root), detector(0) 00075 { 00076 cam_info_sub = nh_.subscribe("/blort_camera_info", 1, &DetectorNode::cam_info_callback, this); 00077 image_pub = it_.advertise("image_result", 1); 00078 //debug_pub = it_.advertise("image_debug", 1); 00079 cam_info_service = nh_.advertiseService("set_camera_info", &DetectorNode::setCameraInfoCb, this); 00080 counter = 0; 00081 00082 nh_.param<double>("nn_match_threshold", nn_match_threshold, 0.55); 00083 nh_.param<int>("ransac_n_points_to_match", ransac_n_points_to_match, 4); 00084 00085 } 00086 00087 ~DetectorNode() 00088 { 00089 if(detector != 0) 00090 delete(detector); 00091 } 00092 00093 bool recovery(blort_ros::RecoveryCall::Request &req, 00094 blort_ros::RecoveryCall::Response &resp) 00095 { 00096 if(detector != 0) 00097 { 00098 ROS_INFO("Detector called the %u-th time.", ++counter); 00099 bool result; 00100 if(!req.Image.data.empty()) 00101 { 00102 cv_bridge::CvImagePtr cv_ptr; 00103 try 00104 { 00105 cv_ptr = cv_bridge::toCvCopy(req.Image, sensor_msgs::image_encodings::BGR8); 00106 } 00107 catch (cv_bridge::Exception& e) 00108 { 00109 ROS_ERROR("cv_bridge exception: %s", e.what()); 00110 return false; 00111 } 00112 result = detector->recovery(cv_ptr->image, resp); 00113 } else { 00114 ROS_INFO("Running detector on latest image."); 00115 result = detector->recoveryWithLast(resp); 00116 } 00117 cv_bridge::CvImage out_msg; 00118 out_msg.header = req.Image.header; 00119 out_msg.header.stamp = ros::Time::now(); 00120 out_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC3; 00121 out_msg.image = detector->getImage(); 00122 image_pub.publish(out_msg.toImageMsg()); 00123 00124 // cv_bridge::CvImage debug_msg; 00125 // debug_msg.header = req.Image.header; 00126 // debug_msg.header.stamp = ros::Time::now(); 00127 // debug_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC3; 00128 // debug_msg.image = detector->getDebugImage(); 00129 // debug_pub.publish(debug_msg.toImageMsg()); 00130 00131 return result; 00132 } else { 00133 ROS_ERROR("blort_detector service called while the core is uninitialized."); 00134 return false; 00135 } 00136 } 00137 00138 bool setCameraInfoCb(blort_ros::SetCameraInfo::Request &req, 00139 blort_ros::SetCameraInfo::Response &resp) 00140 { 00141 if(detector == 0) 00142 cam_info_callback(req.CameraInfo); 00143 return true; 00144 } 00145 00146 void reconf_callback(blort_ros::DetectorConfig &config, uint32_t level) 00147 { 00148 if(detector != 0) 00149 { 00150 detector->reconfigure(config); 00151 ROS_INFO("Detector confidence threshold set to %f", config.recovery_conf_threshold); 00152 } else { 00153 ROS_WARN("Please publish camera_info for the tracker initialization."); 00154 } 00155 } 00156 00157 void cam_info_callback(const sensor_msgs::CameraInfo &msg) 00158 { 00159 if(detector == 0) 00160 { 00161 ROS_INFO("Camera parameters received, ready to run."); 00162 cam_info_sub.shutdown(); 00163 detector = new blort_ros::GLDetector(msg, root_); 00164 if(nn_match_threshold != 0.0) 00165 detector->setNNThreshold(nn_match_threshold); 00166 if(ransac_n_points_to_match != 0) 00167 detector->setRansacNPointsToMatch(ransac_n_points_to_match); 00168 pose_service = nh_.advertiseService("pose_service", &DetectorNode::recovery, this); 00169 // lines for dynamic_reconfigure 00170 server_ = std::auto_ptr<dynamic_reconfigure::Server<blort_ros::DetectorConfig> > 00171 (new dynamic_reconfigure::Server<blort_ros::DetectorConfig>()); 00172 f_ = boost::bind(&DetectorNode::reconf_callback, this, _1, _2); 00173 server_->setCallback(f_); 00174 } 00175 } 00176 }; 00177 00178 int main(int argc, char *argv[] ) 00179 { 00180 if(argc < 2) 00181 { 00182 ROS_ERROR("The first command line argument should be the package root!"); 00183 return -1; 00184 } 00185 ros::init(argc, argv, "blort_detector"); 00186 DetectorNode node(argv[1]); 00187 ros::spin(); 00188 return 0; 00189 } 00190