Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_perception::BoundingBoxToRect Class Reference

#include <bounding_box_to_rect.h>

List of all members.

Public Types

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::CameraInfo,
jsk_recognition_msgs::BoundingBoxArray > 
ApproximateSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::CameraInfo,
jsk_recognition_msgs::BoundingBox > 
ApproximateSyncPolicyBox
typedef boost::shared_ptr
< BoundingBoxToRect
Ptr
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::CameraInfo,
jsk_recognition_msgs::BoundingBoxArray > 
SyncPolicy
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::CameraInfo,
jsk_recognition_msgs::BoundingBox > 
SyncPolicyBox

Public Member Functions

 BoundingBoxToRect ()

Protected Member Functions

virtual void inputBoxCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void inputCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &boxes_msg)
virtual void internalCallback (const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr &msg)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

bool approximate_sync_
boost::shared_ptr
< message_filters::Synchronizer
< ApproximateSyncPolicy > > 
async_
boost::shared_ptr
< message_filters::Synchronizer
< ApproximateSyncPolicyBox > > 
async_box_
std::string frame_id_
boost::mutex mutex_
ros::Publisher pub_
ros::Publisher pub_internal_
int queue_size_
message_filters::Subscriber
< jsk_recognition_msgs::BoundingBox > 
sub_box_
message_filters::Subscriber
< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > 
sub_box_with_info_
message_filters::Subscriber
< jsk_recognition_msgs::BoundingBoxArray > 
sub_boxes_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
sub_info_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicyBox > > 
sync_box_
boost::shared_ptr
< tf::MessageFilter
< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > > 
tf_filter_
tf::TransformListenertf_listener_
int tf_queue_size_

Detailed Description

Definition at line 54 of file bounding_box_to_rect.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBoxArray > jsk_perception::BoundingBoxToRect::ApproximateSyncPolicy

Definition at line 63 of file bounding_box_to_rect.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBox > jsk_perception::BoundingBoxToRect::ApproximateSyncPolicyBox

Definition at line 69 of file bounding_box_to_rect.h.

Definition at line 57 of file bounding_box_to_rect.h.

typedef message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBoxArray > jsk_perception::BoundingBoxToRect::SyncPolicy

Definition at line 60 of file bounding_box_to_rect.h.

typedef message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBox > jsk_perception::BoundingBoxToRect::SyncPolicyBox

Definition at line 66 of file bounding_box_to_rect.h.


Constructor & Destructor Documentation

Definition at line 71 of file bounding_box_to_rect.h.


Member Function Documentation

void jsk_perception::BoundingBoxToRect::inputBoxCallback ( const sensor_msgs::CameraInfo::ConstPtr &  info_msg,
const jsk_recognition_msgs::BoundingBox::ConstPtr &  box_msg 
) [protected, virtual]

Definition at line 92 of file bounding_box_to_rect.cpp.

void jsk_perception::BoundingBoxToRect::inputCallback ( const sensor_msgs::CameraInfo::ConstPtr &  info_msg,
const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &  boxes_msg 
) [protected, virtual]

Definition at line 102 of file bounding_box_to_rect.cpp.

void jsk_perception::BoundingBoxToRect::internalCallback ( const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr &  msg) [protected, virtual]

Definition at line 123 of file bounding_box_to_rect.cpp.

void jsk_perception::BoundingBoxToRect::onInit ( ) [protected, virtual]

Definition at line 44 of file bounding_box_to_rect.cpp.

void jsk_perception::BoundingBoxToRect::subscribe ( ) [protected, virtual]

Definition at line 57 of file bounding_box_to_rect.cpp.

void jsk_perception::BoundingBoxToRect::unsubscribe ( ) [protected, virtual]

Definition at line 84 of file bounding_box_to_rect.cpp.


Member Data Documentation

Definition at line 94 of file bounding_box_to_rect.h.

Definition at line 90 of file bounding_box_to_rect.h.

Definition at line 92 of file bounding_box_to_rect.h.

Definition at line 84 of file bounding_box_to_rect.h.

Definition at line 83 of file bounding_box_to_rect.h.

Definition at line 98 of file bounding_box_to_rect.h.

Definition at line 99 of file bounding_box_to_rect.h.

Definition at line 96 of file bounding_box_to_rect.h.

message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> jsk_perception::BoundingBoxToRect::sub_box_ [protected]

Definition at line 86 of file bounding_box_to_rect.h.

message_filters::Subscriber<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo> jsk_perception::BoundingBoxToRect::sub_box_with_info_ [protected]

Definition at line 88 of file bounding_box_to_rect.h.

message_filters::Subscriber<jsk_recognition_msgs::BoundingBoxArray> jsk_perception::BoundingBoxToRect::sub_boxes_ [protected]

Definition at line 87 of file bounding_box_to_rect.h.

Definition at line 85 of file bounding_box_to_rect.h.

Definition at line 89 of file bounding_box_to_rect.h.

Definition at line 91 of file bounding_box_to_rect.h.

boost::shared_ptr<tf::MessageFilter<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo> > jsk_perception::BoundingBoxToRect::tf_filter_ [protected]

Definition at line 97 of file bounding_box_to_rect.h.

Definition at line 93 of file bounding_box_to_rect.h.

Definition at line 95 of file bounding_box_to_rect.h.


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


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:08