Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_perception::ConsensusTracking Class Reference

#include <consensus_tracking.h>

Inheritance diagram for jsk_perception::ConsensusTracking:
Inheritance graph
[legend]

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_
 

Detailed Description

Definition at line 82 of file consensus_tracking.h.

Member Typedef Documentation

◆ ApproximateSyncPolicy

Definition at line 123 of file consensus_tracking.h.

◆ ExactSyncPolicy

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.

Constructor & Destructor Documentation

◆ ConsensusTracking()

jsk_perception::ConsensusTracking::ConsensusTracking ( )
inline

Definition at line 117 of file consensus_tracking.h.

◆ ~ConsensusTracking()

jsk_perception::ConsensusTracking::~ConsensusTracking ( )
virtual

Definition at line 79 of file consensus_tracking.cpp.

Member Function Documentation

◆ getTrackingResult()

void jsk_perception::ConsensusTracking::getTrackingResult ( const sensor_msgs::Image::ConstPtr &  image_msg)
protectedvirtual

Definition at line 123 of file consensus_tracking.cpp.

◆ onInit()

void jsk_perception::ConsensusTracking::onInit ( )
protectedvirtual

Definition at line 50 of file consensus_tracking.cpp.

◆ setInitialWindow()

void jsk_perception::ConsensusTracking::setInitialWindow ( const sensor_msgs::Image::ConstPtr &  img_msg,
const geometry_msgs::PolygonStamped::ConstPtr &  poly_msg 
)
protected

Definition at line 102 of file consensus_tracking.cpp.

◆ subscribe()

void jsk_perception::ConsensusTracking::subscribe ( )
protectedvirtual

Definition at line 91 of file consensus_tracking.cpp.

◆ unsubscribe()

void jsk_perception::ConsensusTracking::unsubscribe ( )
protectedvirtual

Definition at line 97 of file consensus_tracking.cpp.

Member Data Documentation

◆ approximate_sync_

bool jsk_perception::ConsensusTracking::approximate_sync_
protected

Definition at line 148 of file consensus_tracking.h.

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_perception::ConsensusTracking::async_
protected

Definition at line 140 of file consensus_tracking.h.

◆ cmt

CMT jsk_perception::ConsensusTracking::cmt
protected

Definition at line 144 of file consensus_tracking.h.

◆ mutex_

boost::mutex jsk_perception::ConsensusTracking::mutex_
protected

Definition at line 146 of file consensus_tracking.h.

◆ pub_debug_image_

ros::Publisher jsk_perception::ConsensusTracking::pub_debug_image_
protected

Definition at line 136 of file consensus_tracking.h.

◆ pub_mask_image_

ros::Publisher jsk_perception::ConsensusTracking::pub_mask_image_
protected

Definition at line 135 of file consensus_tracking.h.

◆ queue_size_

int jsk_perception::ConsensusTracking::queue_size_
protected

Definition at line 149 of file consensus_tracking.h.

◆ sub_image_

ros::Subscriber jsk_perception::ConsensusTracking::sub_image_
protected

Definition at line 138 of file consensus_tracking.h.

◆ sub_image_to_init_

message_filters::Subscriber<sensor_msgs::Image> jsk_perception::ConsensusTracking::sub_image_to_init_
protected

Definition at line 141 of file consensus_tracking.h.

◆ sub_polygon_to_init_

message_filters::Subscriber<geometry_msgs::PolygonStamped> jsk_perception::ConsensusTracking::sub_polygon_to_init_
protected

Definition at line 142 of file consensus_tracking.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<ExactSyncPolicy> > jsk_perception::ConsensusTracking::sync_
protected

Definition at line 139 of file consensus_tracking.h.

◆ window_initialized_

bool jsk_perception::ConsensusTracking::window_initialized_
protected

Definition at line 147 of file consensus_tracking.h.


The documentation for this class was generated from the following files:


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