35 #include <boost/assign.hpp> 
   36 #include <boost/tuple/tuple.hpp> 
   37 #include <jsk_topic_tools/log_utils.h> 
   39 #include <opencv2/opencv.hpp> 
   42 #include <Eigen/Dense> 
   49     DiagnosticNodelet::onInit();
 
   50     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   51     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   53     srv_->setCallback (f);
 
   57     pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"output", 1);
 
   74     Config &config, uint32_t level)
 
   89         async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
 
   94         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
 
   98       names.push_back(
"~input/camera_info");
 
  102       if (pnh_->hasParam(
"image_height") && pnh_->hasParam(
"image_width"))
 
  110         ROS_FATAL(
"Rosparam ~image_height and ~image_width must be set if ~use_camera_info=false");
 
  113     jsk_topic_tools::warnNoRemap(names);
 
  123     const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg)
 
  129     const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
 
  130     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
 
  136     const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
 
  137     const int image_height,
 
  138     const int image_width)
 
  140     vital_checker_->poke();
 
  142     cv::Mat mask = cv::Mat::zeros(image_height, image_width, CV_8UC1);
 
  144     for (
size_t i=0; 
i<flow_msg->flow.size(); 
i++)
 
  147       vel(0) = flow_msg->flow[
i].velocity.x;
 
  148       vel(1) = flow_msg->flow[
i].velocity.y;
 
  150         cv::Point center = cv::Point(flow_msg->flow[
i].point.x, flow_msg->flow[
i].point.y);