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