37 #ifndef JSK_PCL_ROS_BOUNDING_BOX_OCCLUSION_REJECTOR_H_ 38 #define JSK_PCL_ROS_BOUNDING_BOX_OCCLUSION_REJECTOR_H_ 41 #include <jsk_recognition_msgs/BoundingBoxArray.h> 42 #include <sensor_msgs/CameraInfo.h> 61 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& candidate_boxes_msg);
63 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
65 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& target_boxes_msg);
66 virtual std::vector<cv::Point2i>
projectVertices(
const std::vector<cv::Point3d>& vertices,
68 virtual std::vector<cv::Point3d>
getVertices(
const jsk_recognition_msgs::BoundingBox&
box);
70 const std::vector<cv::Point2i>& vertices);
ros::Publisher pub_target_image_
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
virtual void unsubscribe()
ros::Subscriber sub_camera_info_
virtual void targetBoxesCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &target_boxes_msg)
ros::Subscriber sub_target_boxes_
tf::TransformListener * tf_listener_
jsk_recognition_msgs::BoundingBoxArray::ConstPtr latest_target_boxes_msg_
virtual std::vector< cv::Point2i > projectVertices(const std::vector< cv::Point3d > &vertices, const image_geometry::PinholeCameraModel &model)
BoundingBoxOcclusionRejector()
boost::shared_ptr< BoundingBoxOcclusionRejector > Ptr
boost::mutex mutex
global mutex.
virtual void reject(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &candidate_boxes_msg)
sensor_msgs::CameraInfo::ConstPtr latest_info_msg_
virtual std::vector< cv::Point3d > getVertices(const jsk_recognition_msgs::BoundingBox &box)
virtual std::vector< std::vector< cv::Point2i > > separateIntoFaces(const std::vector< cv::Point2i > &vertices)
ros::Publisher pub_candidate_image_
ros::Subscriber sub_candidate_boxes_