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_(),
87 if(trackerType_==
"mbt")
88 tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER);
89 else if(trackerType_==
"klt")
90 tracker_.setTrackerType(vpMbGenericTracker::KLT_TRACKER);
92 tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER);
96 if (modelName_.empty ())
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.");
152 if(trackerType_==
"mbt+klt"){
157 boost::ref(
mutex_), _1, _2);
160 else if(trackerType_==
"mbt"){
165 boost::ref(
mutex_), _1, _2);
173 boost::ref(
mutex_), _1, _2);
182 throw std::runtime_error(
"failed to retrieve image");
192 if(trackerType_!=
"klt"){
196 if(trackerType_!=
"mbt"){
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::displayCharString
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");
474 std::string username;
475 vpIoTools::getUserName(username);
479 filename =
"C:/temp/" + username;
481 filename =
"/tmp/" + username;
485 if (vpIoTools::checkFilename(filename)) {
487 std::ifstream in( filename.c_str() );
502 boost::filesystem::ofstream file(initialPose);
507 std::string username;
508 vpIoTools::getUserName(username);
511 std::string logdirname;
513 logdirname =
"C:/temp/" + username;
515 logdirname =
"/tmp/" + username;
518 if (vpIoTools::checkDirectory(logdirname) ==
false) {
520 vpIoTools::makeDirectory(logdirname);
523 ROS_WARN_STREAM(
"Unable to create the folder " << logdirname <<
" to save the initial pose");
529 std::fstream finitpos ;
530 finitpos.open(filename.c_str(), std::ios::out) ;
553 std::stringstream file;
558 boost::format fmt(
"failed to load initialization points: %1");
560 throw std::runtime_error(fmt.str());
566 while (!file.fail() && (c ==
'#')) {
567 file.ignore(256,
'\n');
572 unsigned int npoints;
574 file.ignore(256,
'\n');
577 if (npoints > 100000) {
578 throw vpException(vpException::badValue,
579 "Exceed the max number of points.");
583 double X = 0., Y = 0., Z = 0.;
584 for (
unsigned int i=0 ; i < npoints ; i++){
587 while (!file.fail() && (c ==
'#')) {
588 file.ignore(256,
'\n');
593 file >> X >> Y >> Z ;
594 file.ignore(256,
'\n');
596 point.setWorldCoordinates(X,Y,Z) ;
597 points.push_back(point);
607 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
608 vpDisplay::display(
image_);
612 vpDisplay::displayCharString(
image_, 15, 10,
613 "Left click to validate, right click to modify initial pose",
625 while(
ros::ok() && !vpDisplay::getClick(
image_, ip, button,
false));
627 if(button == vpMouseButton::button1)
637 vpHomogeneousMatrix cMo;
638 vpImagePoint point (10, 10);
645 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
651 vpDisplayX *initHelpDisplay = NULL;
653 std::string helpImagePath;
655 if (helpImagePath.empty()){
661 char* tmpname = strdup(
"/tmp/tmpXXXXXX");
662 if (mkdtemp(tmpname) == NULL) {
663 ROS_ERROR_STREAM(
"Failed to create the temporary directory: " << strerror(errno));
666 boost::filesystem::path path(tmpname);
667 path /= (
"help.ppm");
670 helpImagePath = path.native();
672 helpImagePath.c_str());
675 FILE*
f = fopen(helpImagePath.c_str(),
"w");
676 fwrite(resource.
data.get(), resource.
size, 1, f);
686 if (!helpImagePath.empty()){
689 if (! vpIoTools::checkFilename(helpImagePath)) {
690 ROS_WARN(
"Error tracker initialization help image file \"%s\" doesn't exist", helpImagePath.c_str());
696 #if VISP_VERSION_INT >= VP_VERSION_INT(2,10,0) 697 winx =
image_.display->getWindowXPosition();
698 winy =
image_.display->getWindowYPosition();
700 initHelpDisplay =
new vpDisplayX (winx+
image_.getWidth()+20, winy,
"Init help image");
702 vpImage<vpRGBa> initHelpImage;
703 vpImageIo::read(initHelpImage, helpImagePath);
704 initHelpDisplay->init(initHelpImage);
705 vpDisplay::display(initHelpImage);
706 vpDisplay::flush(initHelpImage);
708 }
catch(vpException &e) {
709 ROS_WARN(
"Error diplaying tracker initialization help image file \"%s\":\n%s", helpImagePath.c_str(), e.what());
718 vpDisplay::display(
image_);
722 for(
unsigned i = 0; i < points.size(); ++i)
731 while(
ros::ok() && !vpDisplay::getClick(
image_, ip, button,
false));
733 imagePoints.push_back(ip);
734 vpDisplay::displayCross(
image_, imagePoints.back(), 5, vpColor::green);
745 if (initHelpDisplay != NULL)
746 delete initHelpDisplay;
757 double x = 0.,
y = 0.;
758 boost::format fmt(
"click on point %u/%u");
759 fmt % (i + 1) % points.size();
762 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
765 vpDisplay::display(
image_);
766 vpDisplay::displayCharString
771 for (
unsigned j = 0; j < imagePoints.size(); ++j)
772 vpDisplay::displayCross(
image_, imagePoints[j], 5, vpColor::green);
780 while(!vpDisplay::getClick(
image_, ip, button,
false));
782 imagePoints.push_back(ip);
786 pose.addPoint(points[i]);
808 result.resize(resource.
size);
810 for (; i < resource.
size; ++i)
811 result[i] = resource.
data.get()[i];
817 const std::string& resourcePath,
818 std::string& fullModelPath)
820 std::string modelExt_ =
".wrl";
821 bool vrmlWorked =
true;
848 result.resize(resource.
size);
850 for (; i < resource.
size; ++i)
851 result[i] = resource.
data.get()[i];
852 result[resource.
size];
854 char* tmpname = strdup(
"/tmp/tmpXXXXXX");
855 if (mkdtemp(tmpname) == NULL)
858 (
"Failed to create the temporary directory: " << strerror(errno));
861 boost::filesystem::path path(tmpname);
862 path /= (
"model" + modelExt_);
865 fullModelPath = path.native();
870 modelStream.open(path);
871 if (!modelStream.good())
874 (
"Failed to create the temporary file: " << path);
877 modelStream << result;
boost::filesystem::path bInitPath_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
TrackerClient(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
std::string getHelpImageFileFromModelName(const std::string &modelName, const std::string &defaultPath)
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void start(const ros::V_string &topics, double duration)
std::string cameraInfoTopic_
void checkInputs()
Make sure the topics we subscribe already exist.
void saveInitialPose(const vpHomogeneousMatrix &cMo)
ros::NodeHandle & nodeHandle_
void convertVpMeToInitRequest(const vpMe &moving_edge, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
bool call(MReq &req, MRes &res)
image_transport::ImageTransport imageTransport_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ros::NodeHandle & nodeHandlePrivate_
points_t loadInitializationPoints()
void convertVpMbTrackerToInitRequest(const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv &klt)
void convertVpKltOpencvToInitRequest(const vpKltOpencv &klt, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
std::vector< vpPoint > points_t
resource_retriever::Retriever resourceRetriever_
bool validatePose(const vpHomogeneousMatrix &cMo)
vpHomogeneousMatrix loadInitialPose()
std::string getModelFileFromModelName(const std::string &modelName, const std::string &defaultPath)
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe &moving_edge)
std::string getInitFileFromModelName(const std::string &modelName, const std::string &defaultPath)
void initPoint(unsigned &i, points_t &points, imagePoints_t &imagePoints, ros::Rate &rate, vpPose &pose)
std::vector< std::string > V_string
std::string modelPathAndExt_
ROSCPP_DECL const std::string & getNamespace()
boost::shared_array< uint8_t > data
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ROSCPP_DECL bool get(const std::string &key, std::string &s)
std::string getInitialPoseFileFromModelName(const std::string &modelName, const std::string &defaultPath)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string model_description_param
image_transport::CameraSubscriber cameraSubscriber_
void reconfigureEdgeCallback(vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
std::string cameraPrefix_
TFSIMD_FORCE_INLINE const tfScalar & x() const
void sendcMo(const vpHomogeneousMatrix &cMo)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
MemoryResource get(const std::string &url)
vpMbGenericTracker tracker_
sensor_msgs::CameraInfoConstPtr info_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
#define ROS_INFO_STREAM(args)
std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
std::string rectifiedImageTopic_
void reconfigureCallback(vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsConfig &config, uint32_t level)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
bool getParam(const std::string &key, std::string &s) const
boost::filesystem::path bModelPath_
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
std::string default_model_path
#define ROS_INFO_THROTTLE(rate,...)
std::string init_service_viewer
#define ROS_ERROR_STREAM(args)
vpCameraParameters cameraParameters_
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
ROSCPP_DECL void spinOnce()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
std::vector< vpImagePoint > imagePoints_t
void reconfigureKltCallback(vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
bool makeModelFile(boost::filesystem::ofstream &modelStream, const std::string &resourcePath, std::string &fullModelPath)
boost::recursive_mutex mutex_
std::string fetchResource(const std::string &)