Go to the documentation of this file.
   37 #ifndef JSK_PCL_ROS_ATTENTION_CLIPPER_H_ 
   38 #define JSK_PCL_ROS_ATTENTION_CLIPPER_H_ 
   40 #include <jsk_topic_tools/diagnostic_nodelet.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> 
   53   class AttentionClipper: 
public jsk_topic_tools::DiagnosticNodelet
 
   63     virtual void clip(
const sensor_msgs::CameraInfo::ConstPtr& 
msg);
 
   65     virtual void poseCallback(
const geometry_msgs::PoseStamped::ConstPtr& pose);
 
   66     virtual void boxCallback(
const jsk_recognition_msgs::BoundingBox::ConstPtr& 
box);
 
   73       const sensor_msgs::CameraInfo::ConstPtr& 
msg,
 
   74       std::vector<cv::Point2d>& 
points,
 
  
virtual void poseCallback(const geometry_msgs::PoseStamped::ConstPtr &pose)
virtual void clipPointcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void unsubscribe()
ros::Publisher pub_bounding_box_array_
ros::Subscriber sub_points_
virtual void poseArrayCallback(const geometry_msgs::PoseArray::ConstPtr &pose)
jsk_recognition_utils::Vertices dimensions_
tf::TransformListener * tf_listener_
jsk_recognition_utils::Vertices vertices_
std::vector< ros::Publisher > multiple_pub_indices_
virtual void boxArrayCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box)
ros::Publisher pub_cluster_indices_
virtual void clip(const sensor_msgs::CameraInfo::ConstPtr &msg)
std::vector< Eigen::Affine3f > transformed_pose_list_
ros::Subscriber sub_pose_
ros::Publisher pub_indices_
virtual void publishBoundingBox(const std_msgs::Header &header)
virtual void boxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box)
virtual void initializePoseList(size_t num)
virtual jsk_recognition_utils::Vertices cubeVertices(Eigen::Vector3f &dimension)
std::vector< std::string > prefixes_
boost::mutex mutex
global mutex.
std::vector< Eigen::Affine3f > pose_list_
std::vector< std::string > frame_id_list_
virtual void computeROI(const sensor_msgs::CameraInfo::ConstPtr &msg, std::vector< cv::Point2d > &points, cv::Mat &mask)
ros::Publisher pub_camera_info_
bool use_multiple_attention_
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:10