1 #ifndef VISP_TRACKER_CALLBACKS_HH 2 # define VISP_TRACKER_CALLBACKS_HH 3 # include <boost/thread/recursive_mutex.hpp> 5 # include <sensor_msgs/Image.h> 6 # include <std_msgs/Header.h> 10 # include <visp/vpImage.h> 11 # include <visp/vpMbTracker.h> 12 # include <visp/vpMe.h> 13 # include <visp/vpKltOpencv.h> 15 # include <visp_tracker/ModelBasedSettingsConfig.h> 16 # include <visp_tracker/ModelBasedSettingsKltConfig.h> 17 # include <visp_tracker/ModelBasedSettingsEdgeConfig.h> 21 const sensor_msgs::Image::ConstPtr& msg,
22 const sensor_msgs::CameraInfoConstPtr& info);
26 std_msgs::Header& header,
27 sensor_msgs::CameraInfoConstPtr& info,
28 const sensor_msgs::Image::ConstPtr& msg,
29 const sensor_msgs::CameraInfoConstPtr& infoConst);
36 std_msgs::Header& header,
37 sensor_msgs::CameraInfoConstPtr& info);
41 vpImage<unsigned char>& I,
43 vpKltOpencv& kltTracker,
44 boost::recursive_mutex& mutex,
45 visp_tracker::ModelBasedSettingsConfig& config,
49 vpImage<unsigned char>& I,
51 boost::recursive_mutex& mutex,
52 visp_tracker::ModelBasedSettingsEdgeConfig& config,
56 vpImage<unsigned char>& I,
57 vpKltOpencv& kltTracker,
58 boost::recursive_mutex& mutex,
59 visp_tracker::ModelBasedSettingsKltConfig& config,
63 vpMbTracker* tracker);
67 vpImage<unsigned char>& I,
69 vpKltOpencv& kltTracker,
70 boost::recursive_mutex& mutex,
71 visp_tracker::ModelBasedSettingsConfig& config,
76 vpImage<unsigned char>& I,
78 boost::recursive_mutex& mutex,
79 visp_tracker::ModelBasedSettingsEdgeConfig& config,
84 vpImage<unsigned char>& I,
85 vpKltOpencv& kltTracker,
86 boost::recursive_mutex& mutex,
87 visp_tracker::ModelBasedSettingsKltConfig& config,
void reconfigureEdgeCallback(vpMbTracker *tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
void reconfigureKltCallbackAndInitViewer(ros::NodeHandle &nh, vpMbTracker *tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
void reconfigureKltCallback(vpMbTracker *tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
void imageCallback(vpImage< unsigned char > &image, const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info)
void reconfigureEdgeCallbackAndInitViewer(ros::NodeHandle &nh, vpMbTracker *tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
void reconfigureCallbackAndInitViewer(ros::NodeHandle &nh, vpMbTracker *tracker, vpImage< unsigned char > &I, vpMe &moving_edge, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsConfig &config, uint32_t level)
void reInitViewerCommonParameters(ros::NodeHandle &nh, vpMbTracker *tracker)
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
void reconfigureCallback(vpMbTracker *tracker, vpImage< unsigned char > &I, vpMe &moving_edge, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsConfig &config, uint32_t level)