$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 gltracker.cpp 00035 * @author Bence Magyar 00036 * @date June 2012 00037 * @version 0.1 00038 * @brief Class of GLTracker which wraps the tracker core of BLORT. 00039 */ 00040 00041 #include "gltracker.h" 00042 #include <blort/Tracker/utilities.hpp> 00043 #include <blort/TomGine/tgModelLoader.h> 00044 #include <sstream> 00045 #include <iostream> 00046 #include <blort/blort/pal_util.h> 00047 #include <ros/console.h> 00048 00049 using namespace blort_ros; 00050 00051 GLTracker::GLTracker(const sensor_msgs::CameraInfo camera_info, 00052 const std::string& config_root, 00053 bool visualize_obj_pose) 00054 { 00055 //this line should force opengl to run software rendering == no GPU 00056 //putenv("LIBGL_ALWAYS_INDIRECT=1"); 00057 00058 conf_threshold = 0.4; 00059 recovery_conf_threshold = 0.05; 00060 publish_mode = 1; 00061 this->visualize_obj_pose = visualize_obj_pose; 00062 00063 printf("\n Blort detection node\n\n"); 00064 printf(" There is a dynamic_reconfigure interface for your convenience. \n"); 00065 printf(" Control commands received via ROS service: tracker_control. \n"); 00066 printf(" --------------------------\n"); 00067 printf(" [0] Lock/Unlock tracking\n"); 00068 printf(" [1] Reset tracker to initial pose\n"); 00069 printf(" [2] Switch display mode of model\n"); 00070 printf(" [3] Show particles\n"); 00071 printf(" [4] Texture edge tracking\n"); 00072 printf(" [5] Texture color tracking\n"); 00073 printf(" [6] Show edges of image\n"); 00074 printf(" [7] Print tracking information to console\n"); 00075 printf(" \n\n "); 00076 00077 // File names 00078 pose_cal = pal_blort::addRoot("bin/pose.cal", config_root); 00079 //FIXME: make these ROS parameters or eliminate them and use the content as parameters 00080 std::string tracking_ini(pal_blort::addRoot("bin/tracking.ini", config_root)); 00081 std::string ply_model; 00082 00083 GetPlySiftFilenames(tracking_ini.c_str(), ply_model, sift_file, model_name); 00084 GetTrackingParameter(track_params, tracking_ini.c_str(), config_root); 00085 00086 tgcam_params = TomGine::tgCamera::Parameter(camera_info); 00087 getCamPose(pose_cal.c_str(), cam_pose); // should get this from a TF call 00088 setCameraPose(tgcam_params, pose_cal.c_str()); // camPose and tgCamParams share a lot of stuff 00089 track_params.camPar = tgcam_params; 00090 00091 tracker.init(track_params); 00092 trPose.t = vec3(0.0, 0.1, 0.0); 00093 trPose.Rotate(0.0f, 0.0f, 0.5f); 00094 00095 model_id = tracker.addModelFromFile(pal_blort::addRoot(ply_model, config_root).c_str(), trPose, model_name.c_str(), true); 00096 tracker.setLockFlag(true); 00097 00098 image = cvCreateImage( cvSize(tgcam_params.width, tgcam_params.height), 8, 3 ); 00099 00100 movement = Tracking::ST_SLOW; 00101 quality = Tracking::ST_LOST; 00102 tracker_confidence = Tracking::ST_BAD; 00103 00104 // define the constant cam_pose to be published 00105 fixed_cam_pose = pal_blort::tgPose2RosPose(cam_pose); 00106 } 00107 00108 void GLTracker::track() 00109 { 00110 *image = last_image; 00111 00112 // Track object 00113 tracker.image_processing((unsigned char*)image->imageData); 00114 tracker.track(); 00115 00116 tracker.drawImage(0); 00117 tracker.drawCoordinates(); 00118 tracker.getModelPose(model_id, trPose); 00119 tracker.drawResult(2.0f); 00120 00121 // visualize current object pose if needed. moving this piece of code is troublesome, 00122 // has to stay right after drawImage(), because of OpenGL 00123 if(visualize_obj_pose) 00124 { 00125 trPose.Activate(); 00126 glBegin(GL_LINES); 00127 glColor3f(1.0f, 0.0f, 0.0f); 00128 glVertex3f(0.0f, 0.0f, 0.0f); 00129 glVertex3f(1.0f, 0.0f, 0.0f); 00130 00131 glColor3f(0.0f, 1.0f, 0.0f); 00132 glVertex3f(0.0f, 0.0f, 0.0f); 00133 glVertex3f(0.0f, 1.0f, 0.0f); 00134 00135 glColor3f(0.0f, 0.0f, 1.0f); 00136 glVertex3f(0.0f, 0.0f, 0.0f); 00137 glVertex3f(0.0f, 0.0f, 1.0f); 00138 glEnd(); 00139 trPose.Deactivate(); 00140 } 00141 00142 update(); 00143 00144 if(quality == Tracking::ST_LOCKED) 00145 { 00146 this->current_mode = blort_ros::TRACKER_LOCKED_MODE; 00147 } 00148 else if(quality == Tracking::ST_LOST) 00149 { 00150 switchToRecovery(); 00151 } 00152 00153 if(tracker_confidence == Tracking::ST_GOOD && movement == Tracking::ST_STILL && quality != Tracking::ST_LOCKED) 00154 { 00155 ROS_DEBUG_STREAM("Tracker is really confident (edge conf: " << tracker_confidences.edgeConf << 00156 " lost conf: " << tracker_confidences.lostConf << ". Sorry, no learning with this node."); 00157 } 00158 } 00159 00160 void GLTracker::resetWithPose(const geometry_msgs::Pose& new_pose) 00161 { 00162 ConvertCam2World(pal_blort::rosPose2TgPose(new_pose), cam_pose, trPose); 00163 tracker.setModelInitialPose(model_id, trPose); 00164 tracker.resetUnlockLock(); // this does one run of the tracker to update the probabilities 00165 switchToTracking(); 00166 update(); 00167 // make sure that the tracker will start tracking after a recovery, 00168 // not standing still in locked mode 00169 tracker.setLockFlag(false); 00170 } 00171 00172 void GLTracker::reconfigure(blort_ros::TrackerConfig config) 00173 { 00174 tracker.setLockFlag(config.lock); 00175 tracker.setModelModeFlag(config.render_mode); 00176 tracker.setEdgesImageFlag(config.edge); 00177 visualize_obj_pose = config.visualize_obj_pose; 00178 publish_mode = config.publish_mode; 00179 00180 //only reset the tracker when the checkbox was clicked, not depending on the act value 00181 if(last_reset != config.reset) 00182 { 00183 last_reset = config.reset; 00184 switchToRecovery(); 00185 } 00186 } 00187 00188 void GLTracker::trackerControl(int code, int param) 00189 { 00190 switch(code) 00191 { 00192 case 0: //l 00193 tracker.setLockFlag( !tracker.getLockFlag() ); 00194 break; 00195 case 1: //r 00196 //tracker.reset(); 00197 this->reset(); 00198 break; 00199 case 2: //m 00200 if ( param != -1 ) 00201 tracker.setModelModeFlag( param ); 00202 else 00203 tracker.setModelModeFlag( tracker.getModelModeFlag()+1 ); 00204 break; 00205 case 3: //p 00206 tracker.setDrawParticlesFlag( !tracker.getDrawParticlesFlag() ); 00207 break; 00208 case 4: //4 00209 tracker.setEdgeShader(); 00210 break; 00211 case 5: //5 00212 tracker.setColorShader(); 00213 break; 00214 case 6: //e 00215 tracker.setEdgesImageFlag( !tracker.getEdgesImageFlag() ); 00216 break; 00217 case 7: //i 00218 tracker.printStatistics(); 00219 break; 00220 } 00221 } 00222 00223 std::string GLTracker::getStatusString() 00224 { 00225 std::stringstream ss; 00226 ss << "GLTracker, mode: "; 00227 if(current_mode == blort_ros::TRACKER_TRACKING_MODE) 00228 ss << "tracking"; 00229 else 00230 ss << "recovery"; 00231 00232 ss << " with target named: " << model_name << std::endl; 00233 return ss.str(); 00234 } 00235 00236 cv::Mat GLTracker::getImage() 00237 { 00238 cv::Mat tmp; 00239 switch(current_mode) 00240 { 00241 case TRACKER_RECOVERY_MODE: 00242 return tmp.empty()?last_image.clone():tmp; // do we need a copy? 00243 break; 00244 case TRACKER_TRACKING_MODE: 00245 return tracker.getImage().clone(); 00246 break; 00247 case TRACKER_LOCKED_MODE: 00248 return tracker.getImage().clone(); 00249 break; 00250 } 00251 return tmp; 00252 } 00253 00254 void GLTracker::updatePoseResult() 00255 { 00256 result.clear(); 00257 TomGine::tgPose pose; 00258 tracker.getModelPose(model_id, pose); 00259 00260 geometry_msgs::Pose detection; 00261 detection.position.x = pose.t.x; 00262 detection.position.y = pose.t.y; 00263 detection.position.z = pose.t.z; 00264 //ALERT!!! inverse needed on the rotation quaternion because the blort orientation 00265 //output is computed differently than what rviz expects. they compute the inverse orientation 00266 detection.orientation.x = -pose.q.x; 00267 detection.orientation.y = -pose.q.y; 00268 detection.orientation.z = -pose.q.z; 00269 detection.orientation.w = pose.q.w; 00270 00271 result.push_back(detection); 00272 } 00273 00274 void GLTracker::update() 00275 { 00276 //update confidences for output 00277 Tracking::ModelEntry* myModelEntry = tracker.getModelEntry(model_id); 00278 tracker_confidences.edgeConf = myModelEntry->c_edge; 00279 tracker_confidences.confThreshold = myModelEntry->c_th; 00280 tracker_confidences.lostConf = myModelEntry->c_lost; 00281 tracker_confidences.distance = myModelEntry->t; 00282 00283 //update confidences based on the currently tracked model 00284 // !!! the tracker state is now defined by the ONLY object tracked. 00285 // although the implementation would allow it, at several places, lacks this at several other. 00286 tracker.getModelMovementState(model_id, movement); 00287 tracker.getModelQualityState(model_id, quality); 00288 tracker.getModelConfidenceState(model_id, tracker_confidence); 00289 00290 switch(tracker_confidence) 00291 { 00292 case Tracking::ST_GOOD: 00293 this->current_conf = blort_ros::TRACKER_CONF_GOOD; 00294 updatePoseResult(); 00295 break; 00296 case Tracking::ST_FAIR: 00297 this->current_conf = blort_ros::TRACKER_CONF_FAIR; 00298 if(publish_mode == TRACKER_PUBLISH_GOOD_AND_FAIR || 00299 publish_mode == TRACKER_PUBLISH_ALL) 00300 { 00301 updatePoseResult(); 00302 this->current_conf = blort_ros::TRACKER_CONF_GOOD; 00303 } 00304 break; 00305 case Tracking::ST_BAD: 00306 this->current_conf = blort_ros::TRACKER_CONF_FAIR; 00307 if(publish_mode == TRACKER_PUBLISH_ALL) 00308 updatePoseResult(); 00309 break; 00310 default: 00311 ROS_ERROR("Unknown confidence value: %d", tracker_confidence); 00312 break; 00313 } 00314 } 00315 00316 void GLTracker::reset() 00317 { 00318 switchToRecovery(); 00319 } 00320 00321 GLTracker::~GLTracker() 00322 { 00323 }