37 #ifndef JSK_PCL_ROS_ATTENTION_CLIPPER_H_ 38 #define JSK_PCL_ROS_ATTENTION_CLIPPER_H_ 41 #include <sensor_msgs/CameraInfo.h> 46 #include <jsk_recognition_msgs/ClusterPointIndices.h> 47 #include <jsk_recognition_msgs/BoundingBoxArray.h> 48 #include <geometry_msgs/PoseArray.h> 49 #include <sensor_msgs/Image.h> 63 virtual void clip(
const sensor_msgs::CameraInfo::ConstPtr&
msg);
64 virtual void clipPointcloud(
const sensor_msgs::PointCloud2::ConstPtr& msg);
66 virtual void boxCallback(
const jsk_recognition_msgs::BoundingBox::ConstPtr&
box);
68 virtual void boxArrayCallback(
const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box);
73 const sensor_msgs::CameraInfo::ConstPtr& msg,
74 std::vector<cv::Point2d>&
points,
virtual void boxArrayCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box)
virtual jsk_recognition_utils::Vertices cubeVertices(Eigen::Vector3f &dimension)
std::vector< Eigen::Affine3f > pose_list_
std::vector< ros::Publisher > multiple_pub_indices_
virtual void poseCallback(const geometry_msgs::PoseStamped::ConstPtr &pose)
bool use_multiple_attention_
ros::Subscriber sub_points_
virtual void clipPointcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
ros::Publisher pub_bounding_box_array_
virtual void publishBoundingBox(const std_msgs::Header &header)
virtual void boxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box)
virtual void computeROI(const sensor_msgs::CameraInfo::ConstPtr &msg, std::vector< cv::Point2d > &points, cv::Mat &mask)
ros::Subscriber sub_pose_
virtual void poseArrayCallback(const geometry_msgs::PoseArray::ConstPtr &pose)
std::vector< std::string > frame_id_list_
ros::Publisher pub_camera_info_
virtual void unsubscribe()
virtual void initializePoseList(size_t num)
tf::TransformListener * tf_listener_
std::vector< Eigen::Affine3f > transformed_pose_list_
jsk_recognition_utils::Vertices dimensions_
virtual void clip(const sensor_msgs::CameraInfo::ConstPtr &msg)
boost::mutex mutex
global mutex.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
ros::Publisher pub_cluster_indices_
std::vector< std::string > prefixes_
jsk_recognition_utils::Vertices vertices_
ros::Publisher pub_indices_