#include <flow_velocity_thresholding.h>
|
| 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 () |
| |
◆ ApproximateSyncPolicy
◆ Config
◆ SyncPolicy
◆ FlowVelocityThresholding()
| jsk_perception::FlowVelocityThresholding::FlowVelocityThresholding |
( |
| ) |
|
|
inline |
◆ ~FlowVelocityThresholding()
| jsk_perception::FlowVelocityThresholding::~FlowVelocityThresholding |
( |
| ) |
|
|
virtual |
◆ callback() [1/2]
| void jsk_perception::FlowVelocityThresholding::callback |
( |
const opencv_apps::FlowArrayStamped::ConstPtr & |
flows_msg | ) |
|
|
protectedvirtual |
◆ callback() [2/2]
| void jsk_perception::FlowVelocityThresholding::callback |
( |
const opencv_apps::FlowArrayStamped::ConstPtr & |
flows_msg, |
|
|
const sensor_msgs::CameraInfo::ConstPtr & |
info_msg |
|
) |
| |
|
protectedvirtual |
◆ configCallback()
| void jsk_perception::FlowVelocityThresholding::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ onInit()
| void jsk_perception::FlowVelocityThresholding::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ process()
| void jsk_perception::FlowVelocityThresholding::process |
( |
const opencv_apps::FlowArrayStamped::ConstPtr & |
flows_msg, |
|
|
const int |
image_height, |
|
|
const int |
image_width |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
| void jsk_perception::FlowVelocityThresholding::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
| void jsk_perception::FlowVelocityThresholding::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ approximate_sync_
| bool jsk_perception::FlowVelocityThresholding::approximate_sync_ |
|
protected |
◆ async_
◆ image_height_
| int jsk_perception::FlowVelocityThresholding::image_height_ |
|
protected |
◆ image_width_
| int jsk_perception::FlowVelocityThresholding::image_width_ |
|
protected |
◆ mutex_
| boost::mutex jsk_perception::FlowVelocityThresholding::mutex_ |
|
protected |
◆ pub_
◆ queue_size_
| int jsk_perception::FlowVelocityThresholding::queue_size_ |
|
protected |
◆ srv_
◆ sub_flow_
◆ sub_info_
◆ sync_
◆ threshold_
| double jsk_perception::FlowVelocityThresholding::threshold_ |
|
protected |
◆ use_camera_info_
| bool jsk_perception::FlowVelocityThresholding::use_camera_info_ |
|
protected |
◆ window_size_
| int jsk_perception::FlowVelocityThresholding::window_size_ |
|
protected |
The documentation for this class was generated from the following files: