#include <flow_velocity_thresholding.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime < opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > | ApproximateSyncPolicy |
typedef jsk_perception::FlowVelocityThresholdingConfig | Config |
typedef message_filters::sync_policies::ExactTime < opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > | SyncPolicy |
Public Member Functions | |
FlowVelocityThresholding () | |
Protected Member Functions | |
virtual void | callback (const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg) |
virtual void | callback (const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg) |
virtual void | configCallback (Config &config, uint32_t level) |
virtual void | onInit () |
virtual void | process (const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg, const int image_height, const int image_width) |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
bool | approximate_sync_ |
boost::shared_ptr < message_filters::Synchronizer < ApproximateSyncPolicy > > | async_ |
int | image_height_ |
int | image_width_ |
boost::mutex | mutex_ |
ros::Publisher | pub_ |
int | queue_size_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
message_filters::Subscriber < opencv_apps::FlowArrayStamped > | sub_flow_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | sub_info_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
double | threshold_ |
bool | use_camera_info_ |
int | window_size_ |
Definition at line 51 of file flow_velocity_thresholding.h.
typedef message_filters::sync_policies::ApproximateTime< opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > jsk_perception::FlowVelocityThresholding::ApproximateSyncPolicy |
Definition at line 58 of file flow_velocity_thresholding.h.
typedef jsk_perception::FlowVelocityThresholdingConfig jsk_perception::FlowVelocityThresholding::Config |
Definition at line 55 of file flow_velocity_thresholding.h.
typedef message_filters::sync_policies::ExactTime< opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > jsk_perception::FlowVelocityThresholding::SyncPolicy |
Definition at line 61 of file flow_velocity_thresholding.h.
Definition at line 54 of file flow_velocity_thresholding.h.
void jsk_perception::FlowVelocityThresholding::callback | ( | const opencv_apps::FlowArrayStamped::ConstPtr & | flows_msg | ) | [protected, virtual] |
Definition at line 110 of file flow_velocity_thresholding.cpp.
void jsk_perception::FlowVelocityThresholding::callback | ( | const opencv_apps::FlowArrayStamped::ConstPtr & | flows_msg, |
const sensor_msgs::CameraInfo::ConstPtr & | info_msg | ||
) | [protected, virtual] |
Definition at line 116 of file flow_velocity_thresholding.cpp.
void jsk_perception::FlowVelocityThresholding::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 61 of file flow_velocity_thresholding.cpp.
void jsk_perception::FlowVelocityThresholding::onInit | ( | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 47 of file flow_velocity_thresholding.cpp.
void jsk_perception::FlowVelocityThresholding::process | ( | const opencv_apps::FlowArrayStamped::ConstPtr & | flows_msg, |
const int | image_height, | ||
const int | image_width | ||
) | [protected, virtual] |
Definition at line 123 of file flow_velocity_thresholding.cpp.
void jsk_perception::FlowVelocityThresholding::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 69 of file flow_velocity_thresholding.cpp.
void jsk_perception::FlowVelocityThresholding::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 104 of file flow_velocity_thresholding.cpp.
bool jsk_perception::FlowVelocityThresholding::approximate_sync_ [protected] |
Definition at line 78 of file flow_velocity_thresholding.h.
boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_perception::FlowVelocityThresholding::async_ [protected] |
Definition at line 88 of file flow_velocity_thresholding.h.
int jsk_perception::FlowVelocityThresholding::image_height_ [protected] |
Definition at line 80 of file flow_velocity_thresholding.h.
int jsk_perception::FlowVelocityThresholding::image_width_ [protected] |
Definition at line 81 of file flow_velocity_thresholding.h.
boost::mutex jsk_perception::FlowVelocityThresholding::mutex_ [protected] |
Definition at line 85 of file flow_velocity_thresholding.h.
Definition at line 86 of file flow_velocity_thresholding.h.
int jsk_perception::FlowVelocityThresholding::queue_size_ [protected] |
Definition at line 79 of file flow_velocity_thresholding.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::FlowVelocityThresholding::srv_ [protected] |
Definition at line 91 of file flow_velocity_thresholding.h.
message_filters::Subscriber<opencv_apps::FlowArrayStamped> jsk_perception::FlowVelocityThresholding::sub_flow_ [protected] |
Definition at line 89 of file flow_velocity_thresholding.h.
message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_perception::FlowVelocityThresholding::sub_info_ [protected] |
Definition at line 90 of file flow_velocity_thresholding.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::FlowVelocityThresholding::sync_ [protected] |
Definition at line 87 of file flow_velocity_thresholding.h.
double jsk_perception::FlowVelocityThresholding::threshold_ [protected] |
Definition at line 83 of file flow_velocity_thresholding.h.
bool jsk_perception::FlowVelocityThresholding::use_camera_info_ [protected] |
Definition at line 77 of file flow_velocity_thresholding.h.
int jsk_perception::FlowVelocityThresholding::window_size_ [protected] |
Definition at line 82 of file flow_velocity_thresholding.h.