$search
00001 #include <cstdlib> 00002 #include <fstream> 00003 #include <sstream> 00004 00005 #include <boost/bind.hpp> 00006 #include <boost/filesystem.hpp> 00007 #include <boost/filesystem/fstream.hpp> 00008 #include <boost/filesystem/path.hpp> 00009 #include <boost/format.hpp> 00010 #include <boost/optional.hpp> 00011 00012 #include <ros/ros.h> 00013 #include <ros/param.h> 00014 #include <image_transport/image_transport.h> 00015 00016 #include <visp/vpDisplayX.h> 00017 00018 #include "conversion.hh" 00019 #include "callbacks.hh" 00020 #include "file.hh" 00021 #include "names.hh" 00022 00023 #include "tracker-viewer.hh" 00024 00025 namespace visp_tracker 00026 { 00027 namespace 00028 { 00029 static void increment(unsigned int* value) 00030 { 00031 ++(*value); 00032 } 00033 } // end of anonymous namespace. 00034 00035 TrackerViewer::TrackerViewer(ros::NodeHandle& nh, 00036 ros::NodeHandle& privateNh, 00037 volatile bool& exiting, 00038 unsigned queueSize) 00039 : exiting_ (exiting), 00040 queueSize_(queueSize), 00041 nodeHandle_(nh), 00042 nodeHandlePrivate_(privateNh), 00043 imageTransport_(nodeHandle_), 00044 rectifiedImageTopic_(), 00045 cameraInfoTopic_(), 00046 checkInputs_(nodeHandle_, ros::this_node::getName()), 00047 tracker_(), 00048 cameraParameters_(), 00049 image_(), 00050 info_(), 00051 cMo_(boost::none), 00052 sites_(), 00053 imageSubscriber_(), 00054 cameraInfoSubscriber_(), 00055 trackingResultSubscriber_(), 00056 movingEdgeSitesSubscriber_(), 00057 synchronizer_(syncPolicy_t(queueSize_)), 00058 timer_(), 00059 countAll_(0u), 00060 countImages_(0u), 00061 countCameraInfo_(0u), 00062 countTrackingResult_(0u), 00063 countMovingEdgeSites_(0u) 00064 { 00065 // Compute topic and services names. 00066 std::string cameraPrefix; 00067 00068 ros::Rate rate (1); 00069 while (cameraPrefix.empty ()) 00070 { 00071 if (!nodeHandle_.getParam ("camera_prefix", cameraPrefix)) 00072 { 00073 ROS_WARN 00074 ("the camera_prefix parameter does not exist.\n" 00075 "This may mean that:\n" 00076 "- the tracker is not launched,\n" 00077 "- the tracker and viewer are not running in the same namespace." 00078 ); 00079 } 00080 else if (cameraPrefix.empty ()) 00081 { 00082 ROS_INFO 00083 ("tracker is not yet initialized, waiting...\n" 00084 "You may want to launch the client to initialize the tracker."); 00085 } 00086 if (this->exiting()) 00087 return; 00088 rate.sleep (); 00089 } 00090 00091 rectifiedImageTopic_ = 00092 ros::names::resolve(cameraPrefix + "/image_rect"); 00093 cameraInfoTopic_ = 00094 ros::names::resolve(cameraPrefix + "/camera_info"); 00095 00096 boost::filesystem::ofstream modelStream; 00097 std::string path; 00098 00099 while (!nodeHandle_.hasParam(visp_tracker::model_description_param)) 00100 { 00101 if (!nodeHandle_.hasParam(visp_tracker::model_description_param)) 00102 { 00103 ROS_WARN 00104 ("the model_description parameter does not exist.\n" 00105 "This may mean that:\n" 00106 "- the tracker is not launched or not initialized,\n" 00107 "- the tracker and viewer are not running in the same namespace." 00108 ); 00109 } 00110 if (this->exiting()) 00111 return; 00112 rate.sleep (); 00113 } 00114 00115 if (!makeModelFile(modelStream, path)) 00116 throw std::runtime_error 00117 ("failed to load the model from the parameter server"); 00118 ROS_INFO_STREAM("Model loaded from the parameter server."); 00119 vrmlPath_ = path; 00120 00121 initializeTracker(); 00122 if (this->exiting()) 00123 return; 00124 00125 checkInputs(); 00126 if (this->exiting()) 00127 return; 00128 00129 // Subscribe to camera and tracker synchronously. 00130 imageSubscriber_.subscribe 00131 (imageTransport_, rectifiedImageTopic_, queueSize_); 00132 cameraInfoSubscriber_.subscribe 00133 (nodeHandle_, cameraInfoTopic_, queueSize_); 00134 trackingResultSubscriber_.subscribe 00135 (nodeHandle_, visp_tracker::object_position_covariance_topic, 00136 queueSize_); 00137 movingEdgeSitesSubscriber_.subscribe 00138 (nodeHandle_, visp_tracker::moving_edge_sites_topic, queueSize_); 00139 00140 synchronizer_.connectInput 00141 (imageSubscriber_, cameraInfoSubscriber_, 00142 trackingResultSubscriber_, movingEdgeSitesSubscriber_); 00143 synchronizer_.registerCallback(boost::bind(&TrackerViewer::callback, 00144 this, _1, _2, _3, _4)); 00145 00146 // Check for synchronization every 30s. 00147 synchronizer_.registerCallback(boost::bind(increment, &countAll_)); 00148 imageSubscriber_.registerCallback(boost::bind(increment, &countImages_)); 00149 cameraInfoSubscriber_.registerCallback 00150 (boost::bind(increment, &countCameraInfo_)); 00151 trackingResultSubscriber_.registerCallback 00152 (boost::bind(increment, &countTrackingResult_)); 00153 movingEdgeSitesSubscriber_.registerCallback 00154 (boost::bind(increment, &countMovingEdgeSites_)); 00155 00156 timer_ = nodeHandle_.createWallTimer 00157 (ros::WallDuration(30.), 00158 boost::bind(&TrackerViewer::timerCallback, this)); 00159 00160 // Wait for image. 00161 waitForImage(); 00162 if (this->exiting()) 00163 return; 00164 if (!image_.getWidth() || !image_.getHeight()) 00165 throw std::runtime_error("failed to retrieve image"); 00166 00167 // Load camera parameters. 00168 initializeVpCameraFromCameraInfo(cameraParameters_, info_); 00169 tracker_.setCameraParameters(cameraParameters_); 00170 tracker_.setDisplayMovingEdges(true); 00171 } 00172 00173 void 00174 TrackerViewer::spin() 00175 { 00176 boost::format fmtWindowTitle ("ViSP MBT tracker viewer - [ns: %s]"); 00177 fmtWindowTitle % ros::this_node::getNamespace (); 00178 00179 vpDisplayX d(image_, 00180 image_.getWidth(), image_.getHeight(), 00181 fmtWindowTitle.str().c_str()); 00182 vpImagePoint point (10, 10); 00183 vpImagePoint pointTime (22, 10); 00184 vpImagePoint pointCameraTopic (34, 10); 00185 ros::Rate loop_rate(80); 00186 00187 boost::format fmt("tracking (x=%f y=%f z=%f)"); 00188 boost::format fmtTime("time = %f"); 00189 00190 boost::format fmtCameraTopic("camera topic = %s"); 00191 fmtCameraTopic % rectifiedImageTopic_; 00192 00193 while (!exiting()) 00194 { 00195 vpDisplay::display(image_); 00196 displayMovingEdgeSites(); 00197 if (cMo_) 00198 { 00199 try 00200 { 00201 tracker_.initFromPose(image_, *cMo_); 00202 tracker_.display(image_, *cMo_, 00203 cameraParameters_, vpColor::red); 00204 } 00205 catch(...) 00206 { 00207 ROS_DEBUG_STREAM_THROTTLE(10, "failed to display cmo"); 00208 } 00209 00210 ROS_DEBUG_STREAM_THROTTLE(10, "cMo:\n" << *cMo_); 00211 00212 fmt % (*cMo_)[0][3] % (*cMo_)[1][3] % (*cMo_)[2][3]; 00213 vpDisplay::displayCharString 00214 (image_, point, fmt.str().c_str(), vpColor::red); 00215 fmtTime % info_->header.stamp.toSec(); 00216 vpDisplay::displayCharString 00217 (image_, pointTime, fmtTime.str().c_str(), vpColor::red); 00218 vpDisplay::displayCharString 00219 (image_, pointCameraTopic, fmtCameraTopic.str().c_str(), 00220 vpColor::red); 00221 } 00222 else 00223 vpDisplay::displayCharString 00224 (image_, point, "tracking failed", vpColor::red); 00225 vpDisplay::flush(image_); 00226 ros::spinOnce(); 00227 loop_rate.sleep(); 00228 } 00229 } 00230 00231 void 00232 TrackerViewer::waitForImage() 00233 { 00234 ros::Rate loop_rate(10); 00235 while (!exiting() 00236 && (!image_.getWidth() || !image_.getHeight())) 00237 { 00238 ROS_INFO_THROTTLE(1, "waiting for a rectified image..."); 00239 ros::spinOnce(); 00240 loop_rate.sleep(); 00241 } 00242 } 00243 00244 void 00245 TrackerViewer::checkInputs() 00246 { 00247 ros::V_string topics; 00248 topics.push_back(rectifiedImageTopic_); 00249 topics.push_back(cameraInfoTopic_); 00250 topics.push_back(visp_tracker::object_position_topic); 00251 topics.push_back(visp_tracker::moving_edge_sites_topic); 00252 checkInputs_.start(topics, 60.0); 00253 } 00254 00255 void 00256 TrackerViewer::initializeTracker() 00257 { 00258 try 00259 { 00260 ROS_DEBUG_STREAM("Trying to load the model " << vrmlPath_); 00261 tracker_.loadModel(vrmlPath_.external_file_string().c_str()); 00262 } 00263 catch(...) 00264 { 00265 boost::format fmt("failed to load the model %1%"); 00266 fmt % vrmlPath_; 00267 throw std::runtime_error(fmt.str()); 00268 } 00269 ROS_INFO("Model has been successfully loaded."); 00270 } 00271 00272 void 00273 TrackerViewer::callback 00274 (const sensor_msgs::ImageConstPtr& image, 00275 const sensor_msgs::CameraInfoConstPtr& info, 00276 const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& trackingResult, 00277 const visp_tracker::MovingEdgeSites::ConstPtr& sites) 00278 { 00279 // Copy image. 00280 try 00281 { 00282 rosImageToVisp(image_, image); 00283 } 00284 catch(std::exception& e) 00285 { 00286 ROS_ERROR_STREAM("dropping frame: " << e.what()); 00287 } 00288 00289 // Copy moving camera infos and edges sites. 00290 info_ = info; 00291 sites_ = sites; 00292 00293 // Copy cMo. 00294 cMo_ = vpHomogeneousMatrix(); 00295 transformToVpHomogeneousMatrix(*cMo_, trackingResult->pose.pose); 00296 } 00297 00298 void 00299 TrackerViewer::displayMovingEdgeSites() 00300 { 00301 if (!sites_) 00302 return; 00303 for (unsigned i = 0; i < sites_->moving_edge_sites.size(); ++i) 00304 { 00305 double x = sites_->moving_edge_sites[i].x; 00306 double y = sites_->moving_edge_sites[i].y; 00307 int suppress = sites_->moving_edge_sites[i].suppress; 00308 vpColor color = vpColor::black; 00309 00310 switch(suppress) 00311 { 00312 case 0: 00313 color = vpColor::green; 00314 break; 00315 case 1: 00316 color = vpColor::blue; 00317 break; 00318 case 2: 00319 color = vpColor::purple; 00320 break; 00321 case 4: 00322 color = vpColor::red; 00323 break; 00324 default: 00325 ROS_ERROR_THROTTLE(10, "bad suppress value"); 00326 } 00327 00328 vpDisplay::displayCross(image_, vpImagePoint(x, y), 3, color, 1); 00329 } 00330 } 00331 00332 void 00333 TrackerViewer::timerCallback() 00334 { 00335 const unsigned threshold = 3 * countAll_; 00336 00337 if (countImages_ < threshold 00338 || countCameraInfo_ < threshold 00339 || countTrackingResult_ < threshold 00340 || countMovingEdgeSites_ < threshold) 00341 { 00342 boost::format fmt 00343 ("[visp_tracker] Low number of synchronized tuples received.\n" 00344 "Images: %d\n" 00345 "Camera info: %d\n" 00346 "Tracking result: %d\n" 00347 "Moving edge sites: %d\n" 00348 "Synchronized tuples: %d\n" 00349 "Possible issues:\n" 00350 "\t* The network is too slow."); 00351 fmt % countImages_ % countCameraInfo_ 00352 % countTrackingResult_ % countMovingEdgeSites_ % countAll_; 00353 ROS_WARN_STREAM_THROTTLE(10, fmt.str()); 00354 } 00355 } 00356 } // end of namespace visp_tracker.