Go to the documentation of this file.
5 #include <boost/bind.hpp>
6 #include <boost/filesystem.hpp>
7 #include <boost/filesystem/fstream.hpp>
8 #include <boost/filesystem/path.hpp>
9 #include <boost/format.hpp>
10 #include <boost/optional.hpp>
16 #include <visp3/gui/vpDisplayX.h>
29 static void increment(
unsigned int* value)
39 visp_tracker::Init::Response& res)
41 boost::filesystem::ofstream modelStream;
45 throw std::runtime_error(
"failed to load the model from the callback");
55 res.initialization_succeed =
true;
61 visp_tracker::Init::Response& res)
67 res.initialization_succeed =
true;
73 volatile bool& exiting,
76 queueSize_(queueSize),
78 nodeHandlePrivate_(privateNh),
79 imageTransport_(nodeHandle_),
81 rectifiedImageTopic_(),
83 checkInputs_(nodeHandle_,
ros::this_node::
getName()),
89 reconfigureService_(),
94 cameraInfoSubscriber_(),
95 trackingResultSubscriber_(),
96 movingEdgeSitesSubscriber_(),
97 kltPointsSubscriber_(),
102 countCameraInfo_(0u),
103 countTrackingResult_(0u),
104 countMovingEdgeSites_(0u),
108 std::string cameraPrefix;
111 while (cameraPrefix.empty ())
117 (
"the camera_prefix parameter does not exist.\n"
118 "This may mean that:\n"
119 "- the tracker is not launched,\n"
120 "- the tracker and viewer are not running in the same namespace."
123 else if (cameraPrefix.empty ())
126 (
"tracker is not yet initialized, waiting...\n"
127 "You may want to launch the client to initialize the tracker.");
153 boost::filesystem::ofstream modelStream;
156 unsigned int cpt = 0;
164 "The model_description parameter does not exist.\n"
165 "This may mean that:\n"
166 "- the tracker is not launched or not initialized,\n"
167 "- the tracker and viewer are not running in the same namespace."
179 throw std::runtime_error
180 (
"failed to load the model from the parameter server");
212 this, _1, _2, _3, _4, _5));
235 throw std::runtime_error(
"failed to retrieve image");
248 boost::format fmtWindowTitle (
"ViSP MBT tracker viewer - [ns: %s]");
253 fmtWindowTitle.str().c_str());
254 vpImagePoint point (10, 10);
255 vpImagePoint pointTime (22, 10);
256 vpImagePoint pointCameraTopic (34, 10);
259 boost::format fmt(
"tracking (x=%f y=%f z=%f)");
260 boost::format fmtTime(
"time = %f");
262 boost::format fmtCameraTopic(
"camera topic = %s");
266 vpDisplay::display(
image_);
284 fmt % (*cMo_)[0][3] % (*cMo_)[1][3] % (*cMo_)[2][3];
285 vpDisplay::displayText
286 (
image_, point, fmt.str().c_str(), vpColor::red);
287 fmtTime %
info_->header.stamp.toSec();
288 vpDisplay::displayText
289 (
image_, pointTime, fmtTime.str().c_str(), vpColor::red);
290 vpDisplay::displayText
291 (
image_, pointCameraTopic, fmtCameraTopic.str().c_str(),
295 vpDisplay::displayText
296 (
image_, point,
"tracking failed", vpColor::red);
336 bool loadParam =
false;
344 ROS_WARN_STREAM(
"No tracker has been found with the default name value \""
346 <<
"Tracker name parameter (tracker_name) should be provided for this node (tracker_viewer).\n"
347 <<
"Polygon visibility might not work well in the viewer window.");
349 else loadParam =
true;
351 else loadParam =
true;
353 else loadParam =
true;
363 tracker_.setAngleAppear(vpMath::rad(value));
368 ROS_WARN_STREAM(
"No tracker has been found with the provided parameter "
370 <<
"Polygon visibility might not work well in the viewer window");
378 tracker_.setAngleDisappear(vpMath::rad(value));
394 boost::format fmt(
"failed to load the model %1%");
396 throw std::runtime_error(fmt.str());
403 (
const sensor_msgs::ImageConstPtr& image,
404 const sensor_msgs::CameraInfoConstPtr& info,
405 const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& trackingResult,
406 const visp_tracker::MovingEdgeSites::ConstPtr& sites,
407 const visp_tracker::KltPoints::ConstPtr& klt)
414 catch(std::exception& e)
425 cMo_ = vpHomogeneousMatrix();
434 for (
unsigned i = 0; i <
sites_->moving_edge_sites.size(); ++i)
436 double x =
sites_->moving_edge_sites[i].x;
437 double y =
sites_->moving_edge_sites[i].y;
438 int suppress =
sites_->moving_edge_sites[i].suppress;
439 vpColor color = vpColor::black;
443 case vpMeSite::NO_SUPPRESSION:
444 color = vpColor::green;
446 case vpMeSite::CONSTRAST:
447 color = vpColor::blue;
449 case vpMeSite::THRESHOLD:
450 color = vpColor::purple;
452 case vpMeSite::M_ESTIMATOR:
453 color = vpColor::red;
456 color = vpColor::yellow;
459 vpDisplay::displayCross(
image_, vpImagePoint(x, y), 3, color, 1);
471 for (
unsigned i = 0; i <
klt_->klt_points_positions.size(); ++i)
473 double ii =
klt_->klt_points_positions[i].i;
474 double jj =
klt_->klt_points_positions[i].j;
475 int id =
klt_->klt_points_positions[i].id;
476 vpColor color = vpColor::red;
478 vpDisplay::displayCross(
image_, vpImagePoint(ii, jj), 15, color, 1);
480 pos.set_i( vpMath::round( ii + 7 ) );
481 pos.set_j( vpMath::round( jj + 7 ) );
483 sprintf(ide,
"%d",
id);
484 vpDisplay::displayText(
image_, pos, ide, vpColor::red);
495 (
"[visp_tracker] Low number of synchronized tuples received.\n"
498 "Tracking result: %d\n"
499 "Moving edge sites: %d\n"
501 "Synchronized tuples: %d\n"
503 "\t* The network is too slow.");
void increment(int *value)
const ROSCPP_DECL std::string & getNamespace()
unsigned countTrackingResult_
image_transport::SubscriberFilter imageSubscriber_
std::string klt_points_topic
void displayMovingEdgeSites()
Display moving edge sites.
void checkInputs()
Make sure the topics we subscribe already exist.
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL bool get(const std::string &key, bool &b)
unsigned countMovingEdgeSites_
bool getParam(const std::string &key, bool &b) const
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
ROSCPP_DECL void spinOnce()
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
std::string moving_edge_sites_topic
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ros::ServiceServer reconfigureService_
Service called when user is reconfiguring tracker node.
ros::ServiceServer initService_
Service called when user ends tracker_client node.
void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker)
message_filters::Synchronizer< syncPolicy_t > synchronizer_
Synchronizer with approximate time policy.
message_filters::Subscriber< visp_tracker::MovingEdgeSites > movingEdgeSitesSubscriber_
Subscriber to moving edge sites topics.
void start(const ros::V_string &topics, double duration)
unsigned countCameraInfo_
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
vpMbGenericTracker tracker_
ViSP edge tracker.
visp_tracker::KltPoints::ConstPtr klt_
Shared pointer to latest received KLT point positions.
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string trackerName_
Name of the tracker used in this viewer node.
TrackerViewer(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
Constructor.
#define ROS_WARN_STREAM(args)
ros::NodeHandle & nodeHandlePrivate_
#define ROS_WARN_STREAM_THROTTLE(period, args)
std::string model_description_param
image_t image_
ViSP image.
boost::filesystem::path modelPath_
Model path.
void transformToVpHomogeneousMatrix(vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src)
void waitForImage()
Hang until the first image is received.
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > trackingResultSubscriber_
Subscriber to tracking result topic.
bool reconfigureCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
bool hasParam(const std::string &key) const
ROSCPP_DECL bool search(const std::string &key, std::string &result)
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
std::string rectifiedImageTopic_
Full topic name for rectified image.
Connection registerCallback(const boost::function< void(P)> &callback)
sensor_msgs::CameraInfoConstPtr info_
Shared pointer to latest received camera information.
#define ROS_INFO_STREAM(args)
bool makeModelFile(boost::filesystem::ofstream &modelStream, std::string &fullModelPath)
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> reconfigureCallback_t
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
void rosImageToVisp(vpImage< unsigned char > &dst, const sensor_msgs::Image::ConstPtr &src)
Convert a ROS image into a ViSP one.
std::string init_service_viewer
ros::NodeHandle & nodeHandle_
const ROSCPP_DECL std::string & getName()
boost::optional< vpHomogeneousMatrix > cMo_
Last tracked object position, set to none if tracking failed.
vpCameraParameters cameraParameters_
ViSP camera parameters.
unsigned queueSize_
Queue size for all subscribers.
void initializeTracker()
Initialize the tracker.
std::string object_position_covariance_topic
message_filters::Subscriber< visp_tracker::KltPoints > kltPointsSubscriber_
Subscriber to KLT point topics.
std::string reconfigure_service_viewer
std::string cameraInfoTopic_
Full topic name for camera information.
T param(const std::string ¶m_name, const T &default_val) const
void spin()
Display camera image, tracked object position and moving edge sites.
void displayKltPoints()
Display KLT points that are tracked.
std::vector< std::string > V_string
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSubscriber_
Subscriber to camera information topic.
std::string object_position_topic
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
void loadCommonParameters()
Initialize the common parameters (visibility angles, etc)
void callback(const sensor_msgs::ImageConstPtr &imageConst, const sensor_msgs::CameraInfoConstPtr &infoConst, const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &trackingResult, const visp_tracker::MovingEdgeSites::ConstPtr &sitesConst, const visp_tracker::KltPoints::ConstPtr &kltConst)
Callback used to received synchronized data.
image_transport::ImageTransport imageTransport_
Image transport used to receive images.
visp_tracker::MovingEdgeSites::ConstPtr sites_
Shared pointer to latest received moving edge sites.
#define ROS_INFO_THROTTLE(period,...)
visp_tracker
Author(s): Thomas Moulard
autogenerated on Sat Aug 24 2024 02:54:56