#include <consensus_tracking.h>
Public Types | |
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PolygonStamped > | ApproximateSyncPolicy |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PolygonStamped > | ExactSyncPolicy |
Public Member Functions | |
| ConsensusTracking () | |
| virtual | ~ConsensusTracking () |
Protected Member Functions | |
| virtual void | getTrackingResult (const sensor_msgs::Image::ConstPtr &image_msg) |
| virtual void | onInit () |
| void | setInitialWindow (const sensor_msgs::Image::ConstPtr &img_msg, const geometry_msgs::PolygonStamped::ConstPtr &poly_msg) |
| virtual void | subscribe () |
| virtual void | unsubscribe () |
Protected Attributes | |
| bool | approximate_sync_ |
| boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > | async_ |
| CMT | cmt |
| boost::mutex | mutex_ |
| ros::Publisher | pub_debug_image_ |
| ros::Publisher | pub_mask_image_ |
| int | queue_size_ |
| ros::Subscriber | sub_image_ |
| message_filters::Subscriber< sensor_msgs::Image > | sub_image_to_init_ |
| message_filters::Subscriber< geometry_msgs::PolygonStamped > | sub_polygon_to_init_ |
| boost::shared_ptr< message_filters::Synchronizer< ExactSyncPolicy > > | sync_ |
| bool | window_initialized_ |
Definition at line 82 of file consensus_tracking.h.
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PolygonStamped> jsk_perception::ConsensusTracking::ApproximateSyncPolicy |
Definition at line 123 of file consensus_tracking.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PolygonStamped> jsk_perception::ConsensusTracking::ExactSyncPolicy |
Definition at line 126 of file consensus_tracking.h.
|
inline |
Definition at line 117 of file consensus_tracking.h.
|
virtual |
Definition at line 79 of file consensus_tracking.cpp.
|
protectedvirtual |
Definition at line 123 of file consensus_tracking.cpp.
|
protectedvirtual |
Definition at line 50 of file consensus_tracking.cpp.
|
protected |
Definition at line 102 of file consensus_tracking.cpp.
|
protectedvirtual |
Definition at line 91 of file consensus_tracking.cpp.
|
protectedvirtual |
Definition at line 97 of file consensus_tracking.cpp.
|
protected |
Definition at line 148 of file consensus_tracking.h.
|
protected |
Definition at line 140 of file consensus_tracking.h.
|
protected |
Definition at line 144 of file consensus_tracking.h.
|
protected |
Definition at line 146 of file consensus_tracking.h.
|
protected |
Definition at line 136 of file consensus_tracking.h.
|
protected |
Definition at line 135 of file consensus_tracking.h.
|
protected |
Definition at line 149 of file consensus_tracking.h.
|
protected |
Definition at line 138 of file consensus_tracking.h.
|
protected |
Definition at line 141 of file consensus_tracking.h.
|
protected |
Definition at line 142 of file consensus_tracking.h.
|
protected |
Definition at line 139 of file consensus_tracking.h.
|
protected |
Definition at line 147 of file consensus_tracking.h.