2 #include <boost/bind.hpp>
4 #include <sensor_msgs/Image.h>
5 #include <visp3/core/vpImage.h>
7 #include <visp_tracker/Init.h>
13 #include <visp3/mbt/vpMbGenericTracker.h>
16 const sensor_msgs::Image::ConstPtr& msg,
17 const sensor_msgs::CameraInfoConstPtr& info)
23 catch(std::exception& e)
30 std_msgs::Header& header,
31 sensor_msgs::CameraInfoConstPtr& info,
32 const sensor_msgs::Image::ConstPtr& msg,
33 const sensor_msgs::CameraInfoConstPtr& infoConst)
48 std_msgs::Header& header,
49 sensor_msgs::CameraInfoConstPtr& info)
53 boost::ref(image), boost::ref(
header), boost::ref(info), _1, _2);
57 vpImage<unsigned char>& I,
59 vpKltOpencv& kltTracker,
60 boost::recursive_mutex& mutex,
61 visp_tracker::ModelBasedSettingsConfig& config,
67 ROS_INFO(
"Reconfigure Model Based Hybrid Tracker request received.");
69 convertModelBasedSettingsConfigToVpMbTracker<visp_tracker::ModelBasedSettingsConfig>(config, tracker);
71 convertModelBasedSettingsConfigToVpMe<visp_tracker::ModelBasedSettingsConfig>(config, moving_edge, tracker);
74 convertModelBasedSettingsConfigToVpKltOpencv<visp_tracker::ModelBasedSettingsConfig>(config, kltTracker, tracker);
76 vpHomogeneousMatrix cMo;
80 if (I.getHeight() != 0 && I.getWidth() != 0) {
81 tracker.initFromPose(I, cMo);
93 vpImage<unsigned char>& I,
95 boost::recursive_mutex& mutex,
96 visp_tracker::ModelBasedSettingsEdgeConfig& config,
103 ROS_INFO(
"Reconfigure Model Based Edge Tracker request received.");
105 convertModelBasedSettingsConfigToVpMbTracker<visp_tracker::ModelBasedSettingsEdgeConfig>(config, tracker);
106 convertModelBasedSettingsConfigToVpMe<visp_tracker::ModelBasedSettingsEdgeConfig>(config, moving_edge, tracker);
110 if (I.getHeight() != 0 && I.getWidth() != 0) {
111 vpHomogeneousMatrix cMo;
112 tracker.getPose(cMo);
116 tracker.setPose(I, cMo);
128 vpImage<unsigned char>& I,
129 vpKltOpencv& kltTracker,
130 boost::recursive_mutex& mutex,
131 visp_tracker::ModelBasedSettingsKltConfig& config,
137 ROS_INFO(
"Reconfigure Model Based KLT Tracker request received.");
139 convertModelBasedSettingsConfigToVpMbTracker<visp_tracker::ModelBasedSettingsKltConfig>(config, tracker);
140 convertModelBasedSettingsConfigToVpKltOpencv<visp_tracker::ModelBasedSettingsKltConfig>(config, kltTracker, tracker);
143 if (I.getHeight() != 0 && I.getWidth() != 0) {
144 vpHomogeneousMatrix cMo;
145 tracker.getPose(cMo);
146 tracker.initFromPose(I, cMo);
158 vpMbGenericTracker &tracker)
162 visp_tracker::Init srv;
164 if (clientViewer.
call(srv))
166 if (srv.response.initialization_succeed)
167 ROS_INFO(
"Tracker Viewer initialized with success.");
169 throw std::runtime_error(
"failed to initialize tracker viewer.");
174 vpMbGenericTracker &tracker,
175 vpImage<unsigned char>& I,
177 vpKltOpencv& kltTracker,
178 boost::recursive_mutex& mutex,
179 visp_tracker::ModelBasedSettingsConfig& config,
187 vpMbGenericTracker &tracker,
188 vpImage<unsigned char>& I,
190 boost::recursive_mutex& mutex,
191 visp_tracker::ModelBasedSettingsEdgeConfig& config,
199 vpMbGenericTracker &tracker,
200 vpImage<unsigned char>& I,
201 vpKltOpencv& kltTracker,
202 boost::recursive_mutex& mutex,
203 visp_tracker::ModelBasedSettingsKltConfig& config,