Go to the documentation of this file.00001 #ifndef VISP_TRACKER_CALLBACKS_HH
00002 # define VISP_TRACKER_CALLBACKS_HH
00003 # include <boost/thread/recursive_mutex.hpp>
00004 # include <image_transport/image_transport.h>
00005 # include <sensor_msgs/Image.h>
00006 # include <std_msgs/Header.h>
00007
00008 # include <string>
00009
00010 # include <visp/vpImage.h>
00011 # include <visp/vpMbTracker.h>
00012 # include <visp/vpMe.h>
00013 # include <visp/vpKltOpencv.h>
00014
00015 # include <visp_tracker/ModelBasedSettingsConfig.h>
00016
00017
00018 void
00019 imageCallback(vpImage<unsigned char>& image,
00020 const sensor_msgs::Image::ConstPtr& msg,
00021 const sensor_msgs::CameraInfoConstPtr& info);
00022
00023 void
00024 imageCallback(vpImage<unsigned char>& image,
00025 std_msgs::Header& header,
00026 sensor_msgs::CameraInfoConstPtr& info,
00027 const sensor_msgs::Image::ConstPtr& msg,
00028 const sensor_msgs::CameraInfoConstPtr& infoConst);
00029
00030 image_transport::CameraSubscriber::Callback
00031 bindImageCallback(vpImage<unsigned char>& image);
00032
00033 image_transport::CameraSubscriber::Callback
00034 bindImageCallback(vpImage<unsigned char>& image,
00035 std_msgs::Header& header,
00036 sensor_msgs::CameraInfoConstPtr& info);
00037
00038
00039 void reconfigureCallback(vpMbTracker* tracker,
00040 vpImage<unsigned char>& I,
00041 vpMe& moving_edge,
00042 vpKltOpencv& kltTracker,
00043 const std::string &trackerType,
00044 boost::recursive_mutex& mutex,
00045 visp_tracker::ModelBasedSettingsConfig& config,
00046 uint32_t level);
00047
00048 #endif //! VISP_TRACKER_CALLBACKS_HH