$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 tracker_node.cpp 00035 * @author Bence Magyar 00036 * @date May 2012 00037 * @version 0.2 00038 * @brief Main file of BLORT tracker node for ROS. 00039 */ 00040 00041 #include <ros/ros.h> 00042 #include <opencv2/core/core.hpp> 00043 #include <ros/duration.h> 00044 #include <ros/time.h> 00045 00046 #include <image_transport/image_transport.h> 00047 #include <image_transport/subscriber_filter.h> 00048 #include <message_filters/time_synchronizer.h> 00049 #include <cv_bridge/cv_bridge.h> 00050 #include <sensor_msgs/image_encodings.h> 00051 #include <geometry_msgs/Pose.h> 00052 #include <dynamic_reconfigure/server.h> 00053 00054 #include <blort_ros/TrackerConfig.h> 00055 #include <blort_ros/TrackerCommand.h> 00056 #include <blort_ros/RecoveryCall.h> 00057 #include <blort_ros/EstimatePose.h> 00058 #include <blort_ros/SetCameraInfo.h> 00059 #include <blort/GLWindow/glxhidingwindow.h> 00060 #include <blort/blort/pal_util.h> 00061 #include "../gltracker.h" 00062 #include <boost/noncopyable.hpp> 00063 00064 class TrackerNode : boost::noncopyable 00065 { 00066 private: 00067 class Mode; 00068 class TrackingMode; 00069 class SingleShotMode; 00070 00071 private: 00072 ros::NodeHandle nh_; 00073 image_transport::ImageTransport it_; 00074 image_transport::Publisher image_pub; 00075 image_transport::Publisher image_debug_pub; 00076 ros::Publisher detection_result; 00077 ros::Publisher confidences_pub; 00078 00079 const std::string root_; 00080 ros::ServiceServer control_service; 00081 std::auto_ptr<dynamic_reconfigure::Server<blort_ros::TrackerConfig> > server_; 00082 dynamic_reconfigure::Server<blort_ros::TrackerConfig>::CallbackType f_; 00083 ros::ServiceClient recovery_client; 00084 blort_ros::GLTracker* tracker; 00085 std::string launch_mode; 00086 00087 Mode* mode; 00088 public: 00089 00090 TrackerNode(std::string root = ".") 00091 : nh_("blort_tracker"), it_(nh_), root_(root), tracker(0) 00092 { 00093 nh_.param<std::string>("launch_mode", launch_mode, "tracking"); 00094 detection_result = nh_.advertise<geometry_msgs::Pose>("detection_result", 100); 00095 confidences_pub = nh_.advertise<blort_ros::TrackerConfidences>("confidences", 100); 00096 image_pub = it_.advertise("image_result", 1); 00097 00098 if(launch_mode == "tracking") 00099 { 00100 mode = new TrackingMode(this); 00101 }else if(launch_mode == "singleshot") 00102 { 00103 mode = new SingleShotMode(this); 00104 } else { 00105 ROS_FATAL("Invalid launch_mode parameter passed to blort_tracker."); 00106 } 00107 } 00108 00109 ~TrackerNode() 00110 { 00111 if(tracker != 0) 00112 delete(tracker); 00113 delete mode; 00114 } 00115 00116 void imageCb(const sensor_msgs::ImageConstPtr& detectorImgMsg, const sensor_msgs::ImageConstPtr& trackerImgMsg ) 00117 { 00118 if(tracker != 0) 00119 { 00120 cv_bridge::CvImagePtr cv_detector_ptr, cv_tracker_ptr; 00121 try 00122 { 00123 cv_detector_ptr = cv_bridge::toCvCopy(detectorImgMsg, sensor_msgs::image_encodings::BGR8); 00124 cv_tracker_ptr = cv_bridge::toCvCopy(trackerImgMsg, sensor_msgs::image_encodings::BGR8); 00125 } 00126 catch (cv_bridge::Exception& e) 00127 { 00128 ROS_ERROR("cv_bridge exception: %s", e.what()); 00129 return; 00130 } 00131 00132 if(tracker->getMode() == blort_ros::TRACKER_RECOVERY_MODE) 00133 { 00134 blort_ros::RecoveryCall srv = mode->recovery(detectorImgMsg); 00135 00136 if(recovery_client.call(srv)) 00137 { 00138 tracker->resetWithPose(srv.response.Pose); 00139 } 00140 else 00141 { 00142 ROS_WARN("Detector not confident enough."); 00143 } 00144 } 00145 else 00146 { 00147 tracker->process(cv_tracker_ptr->image); 00148 00149 confidences_pub.publish(tracker->getConfidences()); 00150 if(tracker->getConfidence() == blort_ros::TRACKER_CONF_GOOD) 00151 { 00152 geometry_msgs::Pose target_pose = pal_blort::blortPosesToRosPose(tracker->getCameraReferencePose(), 00153 tracker->getDetections()[0]); 00154 00155 detection_result.publish(target_pose); 00156 } 00157 00158 cv_bridge::CvImage out_msg; 00159 out_msg.header = trackerImgMsg->header; 00160 out_msg.header.stamp = ros::Time::now(); 00161 out_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC3; 00162 out_msg.image = tracker->getImage(); 00163 image_pub.publish(out_msg.toImageMsg()); 00164 } 00165 } 00166 } 00167 00168 bool trackerControlServiceCb(blort_ros::TrackerCommand::Request &req, 00169 blort_ros::TrackerCommand::Response &) 00170 { 00171 if(tracker != 0) 00172 { 00173 tracker->trackerControl(req.code, req.param); 00174 return true; 00175 } else { 00176 ROS_WARN("Please publish camera_info for the tracker initialization."); 00177 return false; 00178 } 00179 } 00180 00181 // STATE DESIGN PATTERN 00182 // to implement the different tracker modes 00183 private: 00184 class Mode 00185 { 00186 public: 00187 virtual void reconf_callback(blort_ros::TrackerConfig &config, uint32_t level) = 0; 00188 virtual blort_ros::RecoveryCall recovery(const sensor_msgs::ImageConstPtr& msg) = 0; 00189 }; 00190 00191 class TrackingMode : public Mode 00192 { 00193 private: 00194 ros::Subscriber cam_info_sub; 00195 boost::shared_ptr<image_transport::SubscriberFilter> detector_image_sub, tracker_image_sub; 00196 boost::shared_ptr< message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image > > imageSynchronizer; 00197 TrackerNode* parent_; 00198 public: 00199 TrackingMode(TrackerNode* parent) : parent_(parent) 00200 { 00201 ROS_INFO("Blort tracker launched in tracking mode."); 00202 cam_info_sub = parent_->nh_.subscribe("/detector_camera_info", 10, &TrackerNode::TrackingMode::cam_info_callback, this); 00203 } 00204 00205 virtual void reconf_callback(blort_ros::TrackerConfig &config, uint32_t level) 00206 { 00207 if(parent_->tracker != 0) 00208 { 00209 parent_->tracker->reconfigure(config); 00210 } else { 00211 ROS_WARN("Please publish camera_info for the tracker initialization."); 00212 } 00213 } 00214 00215 virtual blort_ros::RecoveryCall recovery(const sensor_msgs::ImageConstPtr& msg) 00216 { 00217 blort_ros::RecoveryCall srv; 00218 srv.request.Image = *msg; 00219 return srv; 00220 } 00221 00222 // The real initialization is being done after receiving the camerainfo. 00223 void cam_info_callback(const sensor_msgs::CameraInfo &msg) 00224 { 00225 if(parent_->tracker == 0) 00226 { 00227 ROS_INFO("Camera parameters received, ready to run."); 00228 cam_info_sub.shutdown(); 00229 parent_->tracker = new blort_ros::GLTracker(msg, parent_->root_, true); 00230 00231 image_transport::TransportHints transportHint("raw"); 00232 00233 detector_image_sub.reset( new image_transport::SubscriberFilter(parent_->it_, "/detector_image", 1, transportHint) ); 00234 tracker_image_sub.reset( new image_transport::SubscriberFilter(parent_->it_, "/tracker_image", 1, transportHint) ); 00235 00236 imageSynchronizer.reset( new message_filters::TimeSynchronizer<sensor_msgs::Image, 00237 sensor_msgs::Image>(*detector_image_sub, *tracker_image_sub, 1) ); 00238 00239 imageSynchronizer->registerCallback(boost::bind(&TrackerNode::imageCb, parent_, _1, _2)); 00240 00241 parent_->control_service = parent_->nh_.advertiseService("tracker_control", &TrackerNode::trackerControlServiceCb, parent_); 00242 parent_->server_ = std::auto_ptr<dynamic_reconfigure::Server<blort_ros::TrackerConfig> > 00243 (new dynamic_reconfigure::Server<blort_ros::TrackerConfig>()); 00244 parent_->f_ = boost::bind(&TrackerNode::TrackingMode::reconf_callback, this, _1, _2); 00245 parent_->server_->setCallback(parent_->f_); 00246 parent_->recovery_client = parent_->nh_.serviceClient<blort_ros::RecoveryCall>("/blort_detector/pose_service"); 00247 } 00248 } 00249 }; 00250 00251 class SingleShotMode : public Mode 00252 { 00253 private: 00254 ros::ServiceServer singleshot_service; 00255 double time_to_run_singleshot; 00256 ros::ServiceClient detector_set_caminfo_service; 00257 bool inServiceCall; 00258 TrackerNode* parent_; 00259 std::list<geometry_msgs::Pose> results; 00260 00261 ros::Subscriber cam_info_sub; 00262 image_transport::Subscriber image_sub; 00263 sensor_msgs::ImageConstPtr lastImage; 00264 sensor_msgs::CameraInfoConstPtr lastCameraInfo; 00265 public: 00266 SingleShotMode(TrackerNode* parent) : parent_(parent) 00267 { 00268 ROS_INFO("Blort tracker launched in singleshot mode."); 00269 detector_set_caminfo_service = parent_->nh_.serviceClient<blort_ros::SetCameraInfo>("/blort_detector/set_camera_info"); 00270 singleshot_service = parent_->nh_.advertiseService("singleshot_service", &TrackerNode::SingleShotMode::singleShotService, this); 00271 image_sub = parent_->it_.subscribe("/blort_image_rect_masked", 10, &TrackerNode::SingleShotMode::imageCallback, this); 00272 cam_info_sub = parent_->nh_.subscribe("/detector_camera_info", 10, &TrackerNode::SingleShotMode::cameraCallback, this); 00273 00274 parent_->control_service = parent_->nh_.advertiseService("tracker_control", &TrackerNode::trackerControlServiceCb, parent_); 00275 parent_->server_ = std::auto_ptr<dynamic_reconfigure::Server<blort_ros::TrackerConfig> > 00276 (new dynamic_reconfigure::Server<blort_ros::TrackerConfig>()); 00277 parent_->f_ = boost::bind(&SingleShotMode::reconf_callback, this, _1, _2); 00278 parent_->server_->setCallback(parent_->f_); 00279 00280 time_to_run_singleshot = 10.; 00281 inServiceCall = false; 00282 } 00283 00284 void imageCallback(const sensor_msgs::ImageConstPtr &image) 00285 { 00286 if(!inServiceCall) 00287 { 00288 // if there is no ongoing servicecall, we can receive the new infos 00289 // if we are in an ongoing servicecall, these fields should be constant 00290 lastImage = image; 00291 } 00292 } 00293 00294 void cameraCallback(const sensor_msgs::CameraInfoConstPtr &camera_info) 00295 { 00296 if(!inServiceCall) 00297 { 00298 // if there is no ongoing servicecall, we can receive the new infos 00299 // if we are in an ongoing servicecall, these fields should be constant 00300 lastCameraInfo = camera_info; 00301 } 00302 } 00303 00304 virtual void reconf_callback(blort_ros::TrackerConfig &config, uint32_t level) 00305 { 00306 time_to_run_singleshot = config.time_to_run_singleshot; 00307 } 00308 00309 virtual blort_ros::RecoveryCall recovery(const sensor_msgs::ImageConstPtr& msg) 00310 { 00311 blort_ros::RecoveryCall srv; 00312 if(!inServiceCall) 00313 { 00314 srv.request.Image = *msg; 00315 // we step into the service call "state" with the first recoverycall made 00316 // no new images are accepted until the end of the singleShotServiceCall 00317 inServiceCall = true; 00318 } 00319 return srv; 00320 } 00321 00322 bool singleShotService(blort_ros::EstimatePose::Request &req, 00323 blort_ros::EstimatePose::Response &resp) 00324 { 00325 if(lastImage.use_count() < 1 && lastCameraInfo.use_count() < 1) 00326 { 00327 ROS_ERROR("Service called but there was no data on the input topics!"); 00328 return false; 00329 } else { 00330 00331 ROS_INFO("Singleshot service has been called with a timeout of %f seconds.", time_to_run_singleshot); 00332 results.clear(); 00333 00334 if(parent_->tracker == 0) 00335 { 00336 parent_->tracker = new blort_ros::GLTracker(*lastCameraInfo, parent_->root_, true); 00337 parent_->recovery_client = parent_->nh_.serviceClient<blort_ros::RecoveryCall>("/blort_detector/poseService"); 00338 } else { 00339 parent_->tracker->reset(); 00340 } 00341 parent_->tracker->setPublisMode(blort_ros::TRACKER_PUBLISH_GOOD); 00342 parent_->tracker->setVisualizeObjPose(true); 00343 blort_ros::SetCameraInfo camera_info; 00344 camera_info.request.CameraInfo = *lastCameraInfo; 00345 if(!detector_set_caminfo_service.call(camera_info)) 00346 ROS_ERROR("blort_tracker failed to call blort_detector/set_camera_info service"); 00347 00348 double start_secs = ros::Time::now().toSec(); 00349 while(ros::Time::now().toSec()-start_secs < time_to_run_singleshot) 00350 { 00351 ROS_INFO("Remaining time %f", time_to_run_singleshot+start_secs-ros::Time::now().toSec()); 00352 parent_->imageCb(lastImage, lastImage); 00353 if(parent_->tracker->getConfidence() == blort_ros::TRACKER_CONF_GOOD) 00354 { 00355 // instead of returning right away let's store the result 00356 // to see if the tracker can get better 00357 results.push_back(parent_->tracker->getDetections()[0]); 00358 } else if(parent_->tracker->getConfidence() == blort_ros::TRACKER_CONF_LOST) 00359 { 00360 results.clear(); 00361 } 00362 } 00363 // we are out of the service call now, the results will be published 00364 inServiceCall = false; 00365 if(!results.empty()) 00366 { 00367 //convert results to a tf style transform and multiply them 00368 //to get the camera-to-target transformation 00369 resp.Pose = pal_blort::blortPosesToRosPose(parent_->tracker->getCameraReferencePose(), 00370 results.back()); 00371 //NOTE: check the pose in vec3 location + mat3x3 rotation could be added here 00372 // if we have any previous knowledge of the given scene 00373 ROS_INFO_STREAM("PUBLISHED POSE: \n" << resp.Pose.position << "\n" << 00374 pal_blort::quaternionTo3x3cvMat(resp.Pose.orientation) << "\n"); 00375 return true; 00376 } else { 00377 //if the time was not enough to get a good detection, make the whole thing fail 00378 return false; 00379 } 00380 } 00381 } 00382 }; 00383 }; 00384 00385 int main(int argc, char *argv[] ) 00386 { 00387 if(argc < 2) 00388 { 00389 ROS_ERROR("The first command line argument should be the package root!"); 00390 return -1; 00391 } 00392 ros::init(argc, argv, "blort_tracker"); 00393 //FIXME: hardcoded size, 1x1 is not good, renders the tracker unfunctional in runtime 00394 // size should be not smaller the image size, too big size is also wrong 00395 pal_blort::GLXHidingWindow window(656, 492, "Tracker"); // a window which should hide itself after start 00396 //blortGLWindow::GLWindow window(640 , 480, "Window"); // a normal opengl window 00397 TrackerNode node(argv[1]); 00398 ros::spin(); 00399 return 0; 00400 } 00401