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> 59 sensor_msgs::CameraInfo,
62 sensor_msgs::CameraInfo,
65 sensor_msgs::CameraInfo,
68 sensor_msgs::CameraInfo,
77 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& boxes_msg);
78 virtual void inputBoxCallback(
const sensor_msgs::CameraInfo::ConstPtr& info_msg,
79 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
81 virtual void internalCallback(
const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr&
msg);
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)
ros::Publisher pub_internal_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyBox > > sync_box_
message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBox > ApproximateSyncPolicyBox
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBox > SyncPolicyBox
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_boxes_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicyBox > > async_box_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
boost::shared_ptr< BoundingBoxToRect > Ptr
virtual void unsubscribe()
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > sub_box_with_info_
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBoxArray > SyncPolicy
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > > tf_filter_
message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, jsk_recognition_msgs::BoundingBoxArray > ApproximateSyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
tf::TransformListener * tf_listener_
virtual void internalCallback(const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr &msg)