$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 gldetector.cpp 00035 * @author Bence Magyar 00036 * @date June 2012 00037 * @version 0.1 00038 * @brief Class of GLDetector which wraps the detector core of BLORT. 00039 */ 00040 00041 #include "gldetector.h" 00042 #include <blort/Tracker/utilities.hpp> 00043 #include <blort/TomGine/tgModelLoader.h> 00044 #include <ros/console.h> 00045 #include <sstream> 00046 #include <iostream> 00047 #include <blort/blort/pal_util.h> 00048 00049 using namespace blort_ros; 00050 00051 GLDetector::GLDetector(const sensor_msgs::CameraInfo& camera_info, const std::string& config_root) 00052 { 00053 //this line should force opengl to run software rendering == no GPU 00054 //putenv("LIBGL_ALWAYS_INDIRECT=1"); 00055 00056 rec3dcounter = 0; 00057 recovery_conf_threshold = 0.05; 00058 00059 //FIXME: make these ROS parameters or eliminate them and use the content as parameters 00060 std::string tracking_ini(pal_blort::addRoot("bin/tracking.ini", config_root)); 00061 std::string ply_model; 00062 GetPlySiftFilenames(tracking_ini.c_str(), ply_model, sift_file, model_name); 00063 recognizer = boost::shared_ptr<blortRecognizer::Recognizer3D>( 00064 new blortRecognizer::Recognizer3D(blortRecognizer::CameraParameter(camera_info), config_root, true)); 00065 recognizer->loadModelFromFile(sift_file); 00066 image_ = cvCreateImage( cvSize(camera_info.width, camera_info.height), 8, 3 ); 00067 } 00068 00069 bool GLDetector::recovery(const cv::Mat& image, 00070 blort_ros::RecoveryCall::Response &resp) 00071 { 00072 last_image = image; 00073 *image_ = last_image; 00074 00075 return recoveryWithLast(resp); 00076 } 00077 00078 bool GLDetector::recoveryWithLast(blort_ros::RecoveryCall::Response &resp) 00079 { 00080 double ticksBefore = cv::getTickCount(); 00081 00082 TomGine::tgPose recPose; 00083 float conf; 00084 recognizer->recognize(image_, recPose, conf); 00085 00086 ROS_INFO("object conf: %f", conf); 00087 ROS_WARN("Tried to recover for the %d. time.", rec3dcounter++); 00088 ROS_INFO("Recovery execution time: %f ms", 00089 1000*(cv::getTickCount() - ticksBefore)/cv::getTickFrequency()); 00090 00091 // if the recovery's confidence is high enough then propose this new pose 00092 if(conf > recovery_conf_threshold) 00093 { 00094 resp.Pose = pal_blort::tgPose2RosPose(recPose); 00095 return true; 00096 } 00097 else // else don't propose 00098 { 00099 return false; 00100 } 00101 } 00102 00103 void GLDetector::reconfigure(blort_ros::DetectorConfig config) 00104 { 00105 recovery_conf_threshold = config.recovery_conf_threshold; 00106 } 00107 00108 cv::Mat GLDetector::getImage() 00109 { 00110 cv::Mat tmp; 00111 tmp = recognizer->getImage(); 00112 return tmp.empty()?last_image:tmp; // do we need a copy? 00113 } 00114 00115 cv::Mat GLDetector::getDebugImage() 00116 { 00117 cv::Mat tmp; 00118 tmp = recognizer->getDebugImage(); 00119 return tmp; 00120 } 00121 00122 GLDetector::~GLDetector() 00123 { 00124 cvReleaseImage(&image_); 00125 }