flow_velocity_thresholding.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 
00036 #ifndef JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
00037 #define JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
00038 
00039 #include <jsk_topic_tools/diagnostic_nodelet.h>
00040 #include <message_filters/subscriber.h>
00041 #include <message_filters/synchronizer.h>
00042 #include <message_filters/sync_policies/exact_time.h>
00043 #include <message_filters/sync_policies/approximate_time.h>
00044 #include <sensor_msgs/CameraInfo.h>
00045 #include <opencv_apps/FlowArrayStamped.h>
00046 #include <dynamic_reconfigure/server.h>
00047 #include "jsk_perception/FlowVelocityThresholdingConfig.h"
00048 
00049 namespace jsk_perception
00050 {
00051   class FlowVelocityThresholding: public jsk_topic_tools::DiagnosticNodelet
00052   {
00053   public:
00054     FlowVelocityThresholding(): DiagnosticNodelet("FlowVelocityThresholding") {}
00055     typedef jsk_perception::FlowVelocityThresholdingConfig Config;
00056     typedef message_filters::sync_policies::ApproximateTime<
00057       opencv_apps::FlowArrayStamped,
00058       sensor_msgs::CameraInfo > ApproximateSyncPolicy;
00059     typedef message_filters::sync_policies::ExactTime<
00060       opencv_apps::FlowArrayStamped,
00061       sensor_msgs::CameraInfo > SyncPolicy;
00062   protected:
00063     virtual void onInit();
00064     virtual void configCallback(Config &config, uint32_t level);
00065     virtual void subscribe();
00066     virtual void unsubscribe();
00067     virtual void callback(
00068       const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg);
00069     virtual void callback(
00070       const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
00071       const sensor_msgs::CameraInfo::ConstPtr& info_msg);
00072     virtual void process(
00073       const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
00074       const int image_height,
00075       const int image_width);
00076 
00077     bool use_camera_info_;
00078     bool approximate_sync_;
00079     int queue_size_;
00080     int image_height_;
00081     int image_width_;
00082     int window_size_;
00083     double threshold_;
00084 
00085     boost::mutex mutex_;
00086     ros::Publisher pub_;
00087     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00088     boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > async_;
00089     message_filters::Subscriber<opencv_apps::FlowArrayStamped> sub_flow_;
00090     message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
00091     boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00092   private:
00093   };
00094 }  // namespace jsk_perception
00095 
00096 #endif  // JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07