6 #include <boost/filesystem.hpp>
7 #include <boost/filesystem/fstream.hpp>
8 #include <boost/format.hpp>
9 #include <boost/optional.hpp>
10 #include <boost/version.hpp>
15 #include <dynamic_reconfigure/server.h>
16 #include <geometry_msgs/PoseWithCovarianceStamped.h>
19 #include <visp_tracker/Init.h>
20 #include <visp_tracker/ModelBasedSettingsConfig.h>
22 #include <visp3/me/vpMe.h>
23 #include <visp3/core/vpPixelMeterConversion.h>
24 #include <visp3/vision/vpPose.h>
26 #include <visp3/mbt/vpMbGenericTracker.h>
28 #include <visp3/gui/vpDisplayX.h>
29 #include <visp3/io/vpImageIo.h>
30 #include <visp3/core/vpIoTools.h>
44 volatile bool& exiting,
47 queueSize_(queueSize),
49 nodeHandlePrivate_(privateNh),
50 imageTransport_(nodeHandle_),
56 rectifiedImageTopic_(),
64 reconfigureSrv_(NULL),
65 reconfigureKltSrv_(NULL),
66 reconfigureEdgeSrv_(NULL),
71 startFromSavedPose_(),
88 tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER);
90 tracker_.setTrackerType(vpMbGenericTracker::KLT_TRACKER);
92 tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER);
97 throw std::runtime_error
99 "Relaunch the client while setting the model_name parameter, i.e.\n"
100 "$ rosrun visp_tracker client _model_name:=my-model"
111 (
"the camera_prefix parameter does not exist.\n"
112 "This may mean that:\n"
113 "- the tracker is not launched,\n"
114 "- the tracker and viewer are not running in the same namespace."
120 (
"tracker is not yet initialized, waiting...\n"
121 "You may want to launch the client to initialize the tracker.");
157 boost::ref(
mutex_), _1, _2);
165 boost::ref(
mutex_), _1, _2);
173 boost::ref(
mutex_), _1, _2);
182 throw std::runtime_error(
"failed to retrieve image");
216 boost::format fmtWindowTitle (
"ViSP MBT tracker initialization - [ns: %s]");
220 fmtWindowTitle.str().c_str());
224 vpHomogeneousMatrix cMo;
225 vpImagePoint point (10, 10);
231 vpDisplay::display(
image_);
243 ROS_INFO_STREAM(
"initial pose [tx,ty,tz,tux,tuy,tuz]:\n" << vpPoseVector(cMo).t());
249 vpMouseButton::vpMouseButtonType button =
250 vpMouseButton::button1;
253 vpDisplay::display(
image_);
261 vpDisplay::displayText
262 (
image_, point,
"tracking, click to initialize tracker",
267 loop_rate_tracking.
sleep();
271 while(!vpDisplay::getClick(
image_, ip, button,
false));
277 catch(
const std::runtime_error& e)
281 << e.what() <<
", retrying...");
283 catch(
const std::string& str)
287 << str <<
", retrying...");
292 ROS_ERROR(
"failed to initialize, retrying...");
301 catch(std::exception& e)
307 ROS_ERROR(
"unknown error happened while sending the cMo, retrying...");
332 visp_tracker::Init srv;
354 (
"Waiting for the initialization service to become available.");
358 if (client.
call(srv))
360 if (srv.response.initialization_succeed)
361 ROS_INFO(
"Tracker initialized with success.");
363 throw std::runtime_error(
"failed to initialize tracker.");
366 throw std::runtime_error(
"failed to call service init");
368 if (clientViewer.call(srv))
370 if (srv.response.initialization_succeed)
371 ROS_INFO(
"Tracker Viewer initialized with success.");
373 throw std::runtime_error(
"failed to initialize tracker viewer.");
376 ROS_INFO(
"No Tracker Viewer node to initialize from service");
387 std::string modelPath;
388 boost::filesystem::ofstream modelStream;
392 throw std::runtime_error (
"failed to retrieve model");
395 ROS_INFO(
"Model has been successfully loaded.");
399 <<
tracker_.getFaces().getPolygon().size());
402 std::list<vpMbtDistanceLine *> linesList;
409 <<
tracker_.getFaces().getPolygon().size());
415 <<
tracker_.getFaces().getPolygon().size());
419 std::list<vpMbtDistanceLine *> linesList;
428 (
"Failed to load the model %1%\n"
429 "Do you use resource_retriever syntax?\n"
430 "I.e. replace /my/model/path by file:///my/model/path");
432 throw std::runtime_error(fmt.str());
439 vpHomogeneousMatrix cMo;
443 std::string resource;
447 std::stringstream file;
453 <<
"using identity as initial pose");
458 for (
unsigned i = 0; i < 6; ++i) {
463 ROS_WARN(
"failed to parse initial pose file");
467 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
478 std::string username;
479 vpIoTools::getUserName(username);
481 std::string filename;
483 filename =
"C:/temp/" + username;
485 filename =
"/tmp/" + username;
489 if (vpIoTools::checkFilename(filename)) {
491 std::ifstream in( filename.c_str() );
494 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
510 boost::filesystem::ofstream file(initialPose);
515 std::string username;
516 vpIoTools::getUserName(username);
519 std::string logdirname;
521 logdirname =
"C:/temp/" + username;
523 logdirname =
"/tmp/" + username;
526 if (vpIoTools::checkDirectory(logdirname) ==
false) {
528 vpIoTools::makeDirectory(logdirname);
531 ROS_WARN_STREAM(
"Unable to create the folder " << logdirname <<
" to save the initial pose");
535 std::string filename = logdirname +
"/" +
modelName_ +
".0.pos";
537 std::fstream finitpos ;
538 finitpos.open(filename.c_str(), std::ios::out) ;
540 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
552 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
569 std::stringstream file;
574 boost::format fmt(
"failed to load initialization points: %1");
576 throw std::runtime_error(fmt.str());
582 while (!file.fail() && (c ==
'#')) {
583 file.ignore(256,
'\n');
588 unsigned int npoints;
590 file.ignore(256,
'\n');
593 if (npoints > 100000) {
594 throw vpException(vpException::badValue,
595 "Exceed the max number of points.");
599 double X = 0., Y = 0., Z = 0.;
600 for (
unsigned int i=0 ; i < npoints ; i++){
603 while (!file.fail() && (c ==
'#')) {
604 file.ignore(256,
'\n');
609 file >> X >> Y >> Z ;
610 file.ignore(256,
'\n');
612 point.setWorldCoordinates(X,Y,Z) ;
613 points.push_back(point);
623 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
624 vpDisplay::display(
image_);
628 vpDisplay::displayText(
image_, 15, 10,
629 "Left click to validate, right click to modify initial pose",
641 while(
ros::ok() && !vpDisplay::getClick(
image_, ip, button,
false));
643 if(button == vpMouseButton::button1)
653 vpHomogeneousMatrix cMo;
654 vpImagePoint point (10, 10);
661 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
667 vpDisplayX *initHelpDisplay = NULL;
669 std::string helpImagePath;
671 if (helpImagePath.empty()){
677 char* tmpname = strdup(
"/tmp/tmpXXXXXX");
678 if (mkdtemp(tmpname) == NULL) {
679 ROS_ERROR_STREAM(
"Failed to create the temporary directory: " << strerror(errno));
682 boost::filesystem::path path(tmpname);
683 path /= (
"help.ppm");
686 helpImagePath = path.native();
688 helpImagePath.c_str());
691 FILE*
f = fopen(helpImagePath.c_str(),
"w");
692 fwrite(resource.
data.get(), resource.
size, 1,
f);
702 if (!helpImagePath.empty()){
705 if (! vpIoTools::checkFilename(helpImagePath)) {
706 ROS_WARN(
"Error tracker initialization help image file \"%s\" doesn't exist", helpImagePath.c_str());
712 #if VISP_VERSION_INT >= VP_VERSION_INT(2,10,0)
713 winx =
image_.display->getWindowXPosition();
714 winy =
image_.display->getWindowYPosition();
716 initHelpDisplay =
new vpDisplayX (winx+
image_.getWidth()+20, winy,
"Init help image");
718 vpImage<vpRGBa> initHelpImage;
719 vpImageIo::read(initHelpImage, helpImagePath);
720 initHelpDisplay->init(initHelpImage);
721 vpDisplay::display(initHelpImage);
722 vpDisplay::flush(initHelpImage);
724 }
catch(vpException &e) {
725 ROS_WARN(
"Error diplaying tracker initialization help image file \"%s\":\n%s", helpImagePath.c_str(), e.what());
734 vpDisplay::display(
image_);
738 for(
unsigned i = 0; i < points.size(); ++i)
747 while(
ros::ok() && !vpDisplay::getClick(
image_, ip, button,
false));
749 imagePoints.push_back(ip);
750 vpDisplay::displayCross(
image_, imagePoints.back(), 5, vpColor::green);
761 if (initHelpDisplay != NULL)
762 delete initHelpDisplay;
773 double x = 0., y = 0.;
774 boost::format fmt(
"click on point %u/%u");
775 fmt % (i + 1) % points.size();
778 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
781 vpDisplay::display(
image_);
782 vpDisplay::displayText
787 for (
unsigned j = 0; j < imagePoints.size(); ++j)
788 vpDisplay::displayCross(
image_, imagePoints[j], 5, vpColor::green);
796 while(!vpDisplay::getClick(
image_, ip, button,
false));
798 imagePoints.push_back(ip);
802 pose.addPoint(points[i]);
824 result.resize(resource.
size);
826 for (; i < resource.
size; ++i)
827 result[i] = resource.
data.get()[i];
833 const std::string& resourcePath,
834 std::string& fullModelPath)
836 std::string modelExt_ =
".cao";
837 bool caoWorked =
true;
864 result.resize(resource.
size);
866 for (; i < resource.
size; ++i)
867 result[i] = resource.
data.get()[i];
868 result[resource.
size];
870 char* tmpname = strdup(
"/tmp/tmpXXXXXX");
871 if (mkdtemp(tmpname) == NULL)
874 (
"Failed to create the temporary directory: " << strerror(errno));
877 boost::filesystem::path path(tmpname);
878 path /= (
"model" + modelExt_);
881 fullModelPath = path.native();
886 modelStream.open(path);
887 if (!modelStream.good())
890 (
"Failed to create the temporary file: " << path);
893 modelStream << result;