flow_velocity_thresholding.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 
36 #ifndef JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
37 #define JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
38 
39 #include <jsk_topic_tools/diagnostic_nodelet.h>
44 #include <sensor_msgs/CameraInfo.h>
45 #include <opencv_apps/FlowArrayStamped.h>
46 #include <dynamic_reconfigure/server.h>
47 #include "jsk_perception/FlowVelocityThresholdingConfig.h"
48 
49 namespace jsk_perception
50 {
51  class FlowVelocityThresholding: public jsk_topic_tools::DiagnosticNodelet
52  {
53  public:
54  FlowVelocityThresholding(): DiagnosticNodelet("FlowVelocityThresholding") {}
55  virtual ~FlowVelocityThresholding();
56  typedef jsk_perception::FlowVelocityThresholdingConfig Config;
58  opencv_apps::FlowArrayStamped,
59  sensor_msgs::CameraInfo > ApproximateSyncPolicy;
61  opencv_apps::FlowArrayStamped,
62  sensor_msgs::CameraInfo > SyncPolicy;
63  protected:
64  virtual void onInit();
65  virtual void configCallback(Config &config, uint32_t level);
66  virtual void subscribe();
67  virtual void unsubscribe();
68  virtual void callback(
69  const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg);
70  virtual void callback(
71  const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
72  const sensor_msgs::CameraInfo::ConstPtr& info_msg);
73  virtual void process(
74  const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
75  const int image_height,
76  const int image_width);
77 
78  bool use_camera_info_;
79  bool approximate_sync_;
80  int queue_size_;
81  int image_height_;
82  int image_width_;
84  double threshold_;
85 
86  boost::mutex mutex_;
93  private:
94  };
95 } // namespace jsk_perception
96 
97 #endif // JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
jsk_perception::FlowVelocityThresholding::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > ApproximateSyncPolicy
Definition: flow_velocity_thresholding.h:123
jsk_perception::FlowVelocityThresholding::window_size_
int window_size_
Definition: flow_velocity_thresholding.h:147
jsk_perception::FlowVelocityThresholding::~FlowVelocityThresholding
virtual ~FlowVelocityThresholding()
Definition: flow_velocity_thresholding.cpp:93
jsk_perception::FlowVelocityThresholding::use_camera_info_
bool use_camera_info_
Definition: flow_velocity_thresholding.h:142
ros::Publisher
boost::shared_ptr
jsk_perception::FlowVelocityThresholding::unsubscribe
virtual void unsubscribe()
Definition: flow_velocity_thresholding.cpp:148
jsk_perception::FlowVelocityThresholding::SyncPolicy
message_filters::sync_policies::ExactTime< opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > SyncPolicy
Definition: flow_velocity_thresholding.h:126
jsk_perception::FlowVelocityThresholding::image_height_
int image_height_
Definition: flow_velocity_thresholding.h:145
jsk_perception::FlowVelocityThresholding::Config
jsk_perception::FlowVelocityThresholdingConfig Config
Definition: flow_velocity_thresholding.h:120
jsk_perception::FlowVelocityThresholding::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: flow_velocity_thresholding.h:156
message_filters::Subscriber< opencv_apps::FlowArrayStamped >
jsk_perception::FlowVelocityThresholding::process
virtual void process(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg, const int image_height, const int image_width)
Definition: flow_velocity_thresholding.cpp:167
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::FlowVelocityThresholding::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: flow_velocity_thresholding.h:155
message_filters::sync_policies::ApproximateTime
jsk_perception::FlowVelocityThresholding::FlowVelocityThresholding
FlowVelocityThresholding()
Definition: flow_velocity_thresholding.h:118
jsk_perception::FlowVelocityThresholding::queue_size_
int queue_size_
Definition: flow_velocity_thresholding.h:144
subscriber.h
jsk_perception::FlowVelocityThresholding::subscribe
virtual void subscribe()
Definition: flow_velocity_thresholding.cpp:113
jsk_perception::FlowVelocityThresholding::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: flow_velocity_thresholding.h:153
jsk_perception::FlowVelocityThresholding::pub_
ros::Publisher pub_
Definition: flow_velocity_thresholding.h:151
jsk_perception::FlowVelocityThresholding::image_width_
int image_width_
Definition: flow_velocity_thresholding.h:146
jsk_perception::FlowVelocityThresholding::sub_flow_
message_filters::Subscriber< opencv_apps::FlowArrayStamped > sub_flow_
Definition: flow_velocity_thresholding.h:154
exact_time.h
jsk_perception::FlowVelocityThresholding::onInit
virtual void onInit()
Definition: flow_velocity_thresholding.cpp:79
synchronizer.h
approximate_time.h
jsk_perception::FlowVelocityThresholding::mutex_
boost::mutex mutex_
Definition: flow_velocity_thresholding.h:150
jsk_perception::FlowVelocityThresholding::approximate_sync_
bool approximate_sync_
Definition: flow_velocity_thresholding.h:143
message_filters::sync_policies::ExactTime
jsk_perception::FlowVelocityThresholding::callback
virtual void callback(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg)
Definition: flow_velocity_thresholding.cpp:154
jsk_perception::FlowVelocityThresholding::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: flow_velocity_thresholding.cpp:105
jsk_perception::FlowVelocityThresholding::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: flow_velocity_thresholding.h:152
jsk_perception::FlowVelocityThresholding::threshold_
double threshold_
Definition: flow_velocity_thresholding.h:148


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17