$search
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 # include <visp/vpImage.h> 00008 # include <visp/vpMbEdgeTracker.h> 00009 # include <visp/vpMe.h> 00010 00011 # include <visp_tracker/MovingEdgeConfig.h> 00012 00013 00014 void 00015 imageCallback(vpImage<unsigned char>& image, 00016 const sensor_msgs::Image::ConstPtr& msg, 00017 const sensor_msgs::CameraInfoConstPtr& info); 00018 00019 void 00020 imageCallback(vpImage<unsigned char>& image, 00021 std_msgs::Header& header, 00022 sensor_msgs::CameraInfoConstPtr& info, 00023 const sensor_msgs::Image::ConstPtr& msg, 00024 const sensor_msgs::CameraInfoConstPtr& infoConst); 00025 00026 image_transport::CameraSubscriber::Callback 00027 bindImageCallback(vpImage<unsigned char>& image); 00028 00029 image_transport::CameraSubscriber::Callback 00030 bindImageCallback(vpImage<unsigned char>& image, 00031 std_msgs::Header& header, 00032 sensor_msgs::CameraInfoConstPtr& info); 00033 00034 00035 void reconfigureCallback(vpMbEdgeTracker& tracker, 00036 vpImage<unsigned char>& I, 00037 vpMe& moving_edge, 00038 boost::recursive_mutex& mutex, 00039 visp_tracker::MovingEdgeConfig& config, 00040 uint32_t level); 00041 00042 #endif //! VISP_TRACKER_CALLBACKS_HH