00001 #include <stdexcept>
00002 #include <boost/bind.hpp>
00003 #include <image_transport/image_transport.h>
00004 #include <sensor_msgs/Image.h>
00005 #include <visp/vpImage.h>
00006
00007 #include <visp_tracker/Init.h>
00008
00009 #include "names.hh"
00010 #include "conversion.hh"
00011 #include "callbacks.hh"
00012
00013 # include <visp/vpMbEdgeTracker.h>
00014 # include <visp/vpMbKltTracker.h>
00015
00016 void imageCallback(vpImage<unsigned char>& image,
00017 const sensor_msgs::Image::ConstPtr& msg,
00018 const sensor_msgs::CameraInfoConstPtr& info)
00019 {
00020 try
00021 {
00022 rosImageToVisp(image, msg);
00023 }
00024 catch(std::exception& e)
00025 {
00026 ROS_ERROR_STREAM("dropping frame: " << e.what());
00027 }
00028 }
00029
00030 void imageCallback(vpImage<unsigned char>& image,
00031 std_msgs::Header& header,
00032 sensor_msgs::CameraInfoConstPtr& info,
00033 const sensor_msgs::Image::ConstPtr& msg,
00034 const sensor_msgs::CameraInfoConstPtr& infoConst)
00035 {
00036 imageCallback(image, msg, info);
00037 header = msg->header;
00038 info = infoConst;
00039 }
00040
00041 image_transport::CameraSubscriber::Callback
00042 bindImageCallback(vpImage<unsigned char>& image)
00043 {
00044 return boost::bind(imageCallback, boost::ref(image), _1, _2);
00045 }
00046
00047 image_transport::CameraSubscriber::Callback
00048 bindImageCallback(vpImage<unsigned char>& image,
00049 std_msgs::Header& header,
00050 sensor_msgs::CameraInfoConstPtr& info)
00051 {
00052 return boost::bind
00053 (imageCallback,
00054 boost::ref(image), boost::ref(header), boost::ref(info), _1, _2);
00055 }
00056
00057 void reconfigureCallback(vpMbTracker* tracker,
00058 vpImage<unsigned char>& I,
00059 vpMe& moving_edge,
00060 vpKltOpencv& kltTracker,
00061 boost::recursive_mutex& mutex,
00062 visp_tracker::ModelBasedSettingsConfig& config,
00063 uint32_t level)
00064 {
00065 mutex.lock ();
00066 try
00067 {
00068 ROS_INFO("Reconfigure Model Based Hybrid Tracker request received.");
00069
00070 convertModelBasedSettingsConfigToVpMbTracker<visp_tracker::ModelBasedSettingsConfig>(config, tracker);
00071
00072 convertModelBasedSettingsConfigToVpMe<visp_tracker::ModelBasedSettingsConfig>(config, moving_edge, tracker);
00073
00074
00075 convertModelBasedSettingsConfigToVpKltOpencv<visp_tracker::ModelBasedSettingsConfig>(config, kltTracker, tracker);
00076
00077 vpHomogeneousMatrix cMo;
00078 tracker->getPose(cMo);
00079
00080 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)
00081
00082
00083 vpMbKltTracker* tracker_klt = dynamic_cast<vpMbKltTracker*>(tracker);
00084 if (tracker_klt != NULL)
00085 tracker_klt->firstTrack = true;
00086 #endif
00087
00088
00089 if (I.getHeight() != 0 && I.getWidth() != 0) {
00090
00091
00092
00093 tracker->setPose(I, cMo);
00094 tracker->initFromPose(I, cMo);
00095 }
00096 }
00097 catch (...)
00098 {
00099 mutex.unlock ();
00100 throw;
00101 }
00102 mutex.unlock ();
00103 }
00104
00105 void reconfigureEdgeCallback(vpMbTracker* tracker,
00106 vpImage<unsigned char>& I,
00107 vpMe& moving_edge,
00108 boost::recursive_mutex& mutex,
00109 visp_tracker::ModelBasedSettingsEdgeConfig& config,
00110 uint32_t level)
00111 {
00112
00113 mutex.lock ();
00114 try
00115 {
00116 ROS_INFO("Reconfigure Model Based Edge Tracker request received.");
00117
00118 convertModelBasedSettingsConfigToVpMbTracker<visp_tracker::ModelBasedSettingsEdgeConfig>(config, tracker);
00119 convertModelBasedSettingsConfigToVpMe<visp_tracker::ModelBasedSettingsEdgeConfig>(config, moving_edge, tracker);
00120
00121
00122
00123 if (I.getHeight() != 0 && I.getWidth() != 0) {
00124 vpHomogeneousMatrix cMo;
00125 tracker->getPose(cMo);
00126
00127
00128
00129 tracker->setPose(I, cMo);
00130 }
00131 }
00132 catch (...)
00133 {
00134 mutex.unlock ();
00135 throw;
00136 }
00137 mutex.unlock ();
00138 }
00139
00140 void reconfigureKltCallback(vpMbTracker* tracker,
00141 vpImage<unsigned char>& I,
00142 vpKltOpencv& kltTracker,
00143 boost::recursive_mutex& mutex,
00144 visp_tracker::ModelBasedSettingsKltConfig& config,
00145 uint32_t level)
00146 {
00147 mutex.lock ();
00148 try
00149 {
00150 ROS_INFO("Reconfigure Model Based KLT Tracker request received.");
00151
00152 convertModelBasedSettingsConfigToVpMbTracker<visp_tracker::ModelBasedSettingsKltConfig>(config, tracker);
00153 convertModelBasedSettingsConfigToVpKltOpencv<visp_tracker::ModelBasedSettingsKltConfig>(config, kltTracker, tracker);
00154
00155
00156 if (I.getHeight() != 0 && I.getWidth() != 0) {
00157 vpHomogeneousMatrix cMo;
00158 tracker->getPose(cMo);
00159 tracker->initFromPose(I, cMo);
00160 }
00161 }
00162 catch (...)
00163 {
00164 mutex.unlock ();
00165 throw;
00166 }
00167 mutex.unlock ();
00168 }
00169
00170 void reInitViewerCommonParameters(ros::NodeHandle& nh,
00171 vpMbTracker* tracker)
00172 {
00173 ros::ServiceClient clientViewer =
00174 nh.serviceClient<visp_tracker::Init>(visp_tracker::reconfigure_service_viewer);
00175 visp_tracker::Init srv;
00176 convertVpMbTrackerToInitRequest(tracker, srv);
00177 if (clientViewer.call(srv))
00178 {
00179 if (srv.response.initialization_succeed)
00180 ROS_INFO("Tracker Viewer initialized with success.");
00181 else
00182 throw std::runtime_error("failed to initialize tracker viewer.");
00183 }
00184 }
00185
00186 void reconfigureCallbackAndInitViewer(ros::NodeHandle& nh,
00187 vpMbTracker* tracker,
00188 vpImage<unsigned char>& I,
00189 vpMe& moving_edge,
00190 vpKltOpencv& kltTracker,
00191 boost::recursive_mutex& mutex,
00192 visp_tracker::ModelBasedSettingsConfig& config,
00193 uint32_t level)
00194 {
00195 reconfigureCallback(tracker,I,moving_edge,kltTracker,mutex,config,level);
00196 reInitViewerCommonParameters(nh,tracker);
00197 }
00198
00199 void reconfigureEdgeCallbackAndInitViewer(ros::NodeHandle& nh,
00200 vpMbTracker* tracker,
00201 vpImage<unsigned char>& I,
00202 vpMe& moving_edge,
00203 boost::recursive_mutex& mutex,
00204 visp_tracker::ModelBasedSettingsEdgeConfig& config,
00205 uint32_t level)
00206 {
00207 reconfigureEdgeCallback(tracker,I,moving_edge,mutex,config,level);
00208 reInitViewerCommonParameters(nh,tracker);
00209 }
00210
00211 void reconfigureKltCallbackAndInitViewer(ros::NodeHandle& nh,
00212 vpMbTracker* tracker,
00213 vpImage<unsigned char>& I,
00214 vpKltOpencv& kltTracker,
00215 boost::recursive_mutex& mutex,
00216 visp_tracker::ModelBasedSettingsKltConfig& config,
00217 uint32_t level)
00218 {
00219 reconfigureKltCallback(tracker,I,kltTracker,mutex,config,level);
00220 reInitViewerCommonParameters(nh,tracker);
00221 }