Go to the documentation of this file.
   37 #ifndef JSK_PERCEPTION_BOUNDING_BOX_TO_RECT_H_ 
   38 #define JSK_PERCEPTION_BOUNDING_BOX_TO_RECT_H_ 
   40 #include <jsk_recognition_msgs/BoundingBoxArray.h> 
   41 #include <jsk_recognition_msgs/RectArray.h> 
   42 #include <jsk_recognition_msgs/BoundingBoxArrayWithCameraInfo.h> 
   43 #include <sensor_msgs/CameraInfo.h> 
   44 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   54   class BoundingBoxToRect: 
public jsk_topic_tools::DiagnosticNodelet
 
   59       sensor_msgs::CameraInfo,
 
   60       jsk_recognition_msgs::BoundingBoxArray > 
SyncPolicy;
 
   62       sensor_msgs::CameraInfo,
 
   65       sensor_msgs::CameraInfo,
 
   68       sensor_msgs::CameraInfo,
 
   77     virtual void inputCallback(
const sensor_msgs::CameraInfo::ConstPtr& info_msg,
 
   78                                const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& boxes_msg);
 
   79     virtual void inputBoxCallback(
const sensor_msgs::CameraInfo::ConstPtr& info_msg,
 
   80                                   const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
 
   82     virtual void internalCallback(
const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr& msg);
 
  
virtual ~BoundingBoxToRect()
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_boxes_
ros::Publisher pub_internal_
boost::shared_ptr< BoundingBoxToRect > Ptr
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
virtual void inputBoxCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
tf::TransformListener * tf_listener_
message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBox > ApproximateSyncPolicyBox
virtual void internalCallback(const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr &msg)
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > > tf_filter_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyBox > > sync_box_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > sub_box_with_info_
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBox > SyncPolicyBox
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
virtual void inputCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &boxes_msg)
message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBoxArray > ApproximateSyncPolicy
virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicyBox > > async_box_
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBoxArray > SyncPolicy
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda 
autogenerated on Fri May 16 2025 03:11:16