37 #ifndef JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_ 38 #define JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_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> 67 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud_;
78 DiagnosticNodelet(
"IntermittentImageAnnotator") {}
84 virtual void onInit();
86 virtual void unsubscribe();
87 virtual void waitForNextImage();
88 virtual void cameraCallback(
89 const sensor_msgs::Image::ConstPtr& image_msg,
90 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
91 virtual void cloudCallback(
92 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
93 virtual void rectCallback(
94 const geometry_msgs::PolygonStamped::ConstPtr& rect);
95 virtual bool shutterCallback(
96 std_srvs::Empty::Request&
req,
97 std_srvs::Empty::Response&
res);
98 virtual bool requestCallback(
99 std_srvs::Empty::Request& req,
100 std_srvs::Empty::Response& res);
102 std_srvs::Empty::Request& req,
103 std_srvs::Empty::Response& res);
104 virtual void publishCroppedPointCloud(
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);
ros::Publisher pub_marker_
ros::Subscriber rect_sub_
IntermittentImageAnnotator()
boost::circular_buffer< SnapshotInformation::Ptr > snapshot_buffer_
ros::ServiceServer clear_service_
ros::ServiceServer shutter_service_
ros::Subscriber cloud_sub_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_msg_
ros::Time last_publish_time_
bool clearCallback(ClearClassifier::Request &req, ClearClassifier::Response &res)
std::string fixed_frame_id_
image_transport::CameraSubscriber image_sub_
tf::TransformListener * listener_
boost::shared_ptr< IntermittentImageAnnotator > Ptr
boost::mutex mutex
global mutex.
ros::Publisher pub_cloud_
ros::ServiceServer request_service_
sensor_msgs::Image::ConstPtr latest_image_msg_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_msg_
image_transport::Publisher image_pub_