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 "conversion.hh"
00008
00009 #include "callbacks.hh"
00010
00011 void imageCallback(vpImage<unsigned char>& image,
00012 const sensor_msgs::Image::ConstPtr& msg,
00013 const sensor_msgs::CameraInfoConstPtr& info)
00014 {
00015 try
00016 {
00017 rosImageToVisp(image, msg);
00018 }
00019 catch(std::exception& e)
00020 {
00021 ROS_ERROR_STREAM("dropping frame: " << e.what());
00022 }
00023 }
00024
00025 void imageCallback(vpImage<unsigned char>& image,
00026 std_msgs::Header& header,
00027 sensor_msgs::CameraInfoConstPtr& info,
00028 const sensor_msgs::Image::ConstPtr& msg,
00029 const sensor_msgs::CameraInfoConstPtr& infoConst)
00030 {
00031 imageCallback(image, msg, info);
00032 header = msg->header;
00033 info = infoConst;
00034 }
00035
00036 image_transport::CameraSubscriber::Callback
00037 bindImageCallback(vpImage<unsigned char>& image)
00038 {
00039 return boost::bind(imageCallback, boost::ref(image), _1, _2);
00040 }
00041
00042 image_transport::CameraSubscriber::Callback
00043 bindImageCallback(vpImage<unsigned char>& image,
00044 std_msgs::Header& header,
00045 sensor_msgs::CameraInfoConstPtr& info)
00046 {
00047 return boost::bind
00048 (imageCallback,
00049 boost::ref(image), boost::ref(header), boost::ref(info), _1, _2);
00050 }
00051
00052 void reconfigureCallback(vpMbEdgeTracker& tracker,
00053 vpImage<unsigned char>& I,
00054 vpMe& moving_edge,
00055 visp_tracker::MovingEdgeConfig& config,
00056 uint32_t level)
00057 {
00058 ROS_INFO("Reconfigure request received.");
00059 convertMovingEdgeConfigToVpMe(config, moving_edge, tracker);
00060
00061
00062 moving_edge.initMask();
00063
00064 vpHomogeneousMatrix cMo;
00065 tracker.getPose(cMo);
00066
00067 tracker.setMovingEdge(moving_edge);
00068 tracker.init(I, cMo);
00069
00070 moving_edge.print();
00071 }