Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_
38 #define JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <sensor_msgs/Image.h>
42 #include <sensor_msgs/CameraInfo.h>
43 #include <std_srvs/Empty.h>
48 #include <boost/circular_buffer.hpp>
49 #include <Eigen/Geometry>
50 #include <geometry_msgs/PolygonStamped.h>
51 #include <jsk_recognition_msgs/PosedCameraInfo.h>
57 class SnapshotInformation
67 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud_;
73 class IntermittentImageAnnotator:
public jsk_topic_tools::DiagnosticNodelet
78 DiagnosticNodelet(
"IntermittentImageAnnotator") {}
89 const sensor_msgs::Image::ConstPtr& image_msg,
90 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
92 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
94 const geometry_msgs::PolygonStamped::ConstPtr& rect);
96 std_srvs::Empty::Request&
req,
97 std_srvs::Empty::Response&
res);
99 std_srvs::Empty::Request&
req,
100 std_srvs::Empty::Response&
res);
102 std_srvs::Empty::Request&
req,
103 std_srvs::Empty::Response&
res);
105 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
106 const cv::Point3d&
A,
const cv::Point3d& B,
107 const cv::Point3d& C,
const cv::Point3d& D,
108 const Eigen::Affine3d& pose);
virtual void publishCroppedPointCloud(pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud, const cv::Point3d &A, const cv::Point3d &B, const cv::Point3d &C, const cv::Point3d &D, const Eigen::Affine3d &pose)
virtual void unsubscribe()
sensor_msgs::Image::ConstPtr latest_image_msg_
std::string fixed_frame_id_
image_transport::CameraSubscriber image_sub_
ros::ServiceServer request_service_
virtual bool requestCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual bool clearCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual void rectCallback(const geometry_msgs::PolygonStamped::ConstPtr &rect)
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::Subscriber cloud_sub_
virtual void cameraCallback(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
ros::Subscriber rect_sub_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_msg_
boost::shared_ptr< IntermittentImageAnnotator > Ptr
ros::Publisher pub_cloud_
virtual void waitForNextImage()
ros::ServiceServer clear_service_
image_transport::Publisher image_pub_
ros::Time last_publish_time_
tf::TransformListener * listener_
ros::ServiceServer shutter_service_
virtual bool shutterCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
boost::circular_buffer< SnapshotInformation::Ptr > snapshot_buffer_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_msg_
boost::mutex mutex
global mutex.
IntermittentImageAnnotator()
ros::Publisher pub_marker_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45