00001 // -*- mode: c++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2014, JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 00037 #ifndef JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_ 00038 #define JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_ 00039 00040 #include <jsk_topic_tools/diagnostic_nodelet.h> 00041 #include <sensor_msgs/Image.h> 00042 #include <sensor_msgs/CameraInfo.h> 00043 #include <std_srvs/Empty.h> 00044 #include <image_geometry/pinhole_camera_model.h> 00045 00046 #include <image_transport/image_transport.h> 00047 #include "jsk_pcl_ros/tf_listener_singleton.h" 00048 #include <boost/circular_buffer.hpp> 00049 #include <Eigen/Geometry> 00050 #include <geometry_msgs/PolygonStamped.h> 00051 #include <jsk_recognition_msgs/PosedCameraInfo.h> 00052 #include <pcl_ros/transforms.h> 00053 00054 00055 namespace jsk_pcl_ros 00056 { 00057 class SnapshotInformation 00058 { 00059 public: 00060 typedef boost::shared_ptr<SnapshotInformation> Ptr; 00061 SnapshotInformation() {}; 00062 virtual ~SnapshotInformation() {}; 00063 00064 Eigen::Affine3d camera_pose_; 00065 cv::Mat image_; 00066 image_geometry::PinholeCameraModel camera_; 00067 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_; 00068 protected: 00069 private: 00070 00071 }; 00072 00073 class IntermittentImageAnnotator: public jsk_topic_tools::DiagnosticNodelet 00074 { 00075 public: 00076 typedef boost::shared_ptr<IntermittentImageAnnotator> Ptr; 00077 IntermittentImageAnnotator(): 00078 DiagnosticNodelet("IntermittentImageAnnotator") {} 00079 00080 protected: 00082 // methods 00084 virtual void onInit(); 00085 virtual void subscribe(); 00086 virtual void unsubscribe(); 00087 virtual void updateDiagnostic( 00088 diagnostic_updater::DiagnosticStatusWrapper &stat); 00089 virtual void waitForNextImage(); 00090 virtual void cameraCallback( 00091 const sensor_msgs::Image::ConstPtr& image_msg, 00092 const sensor_msgs::CameraInfo::ConstPtr& info_msg); 00093 virtual void cloudCallback( 00094 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg); 00095 virtual void rectCallback( 00096 const geometry_msgs::PolygonStamped::ConstPtr& rect); 00097 virtual bool shutterCallback( 00098 std_srvs::Empty::Request& req, 00099 std_srvs::Empty::Response& res); 00100 virtual bool requestCallback( 00101 std_srvs::Empty::Request& req, 00102 std_srvs::Empty::Response& res); 00103 virtual bool clearCallback( 00104 std_srvs::Empty::Request& req, 00105 std_srvs::Empty::Response& res); 00106 virtual void publishCroppedPointCloud( 00107 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, 00108 const cv::Point3d& A, const cv::Point3d& B, 00109 const cv::Point3d& C, const cv::Point3d& D, 00110 const Eigen::Affine3d& pose); 00112 // ROS variables 00114 tf::TransformListener* listener_; 00115 double rate_; 00116 ros::Time last_publish_time_; 00117 image_transport::Publisher image_pub_; 00118 image_transport::CameraSubscriber image_sub_; 00119 boost::mutex mutex_; 00120 ros::Subscriber rect_sub_; 00121 ros::Subscriber cloud_sub_; 00122 ros::ServiceServer shutter_service_; 00123 ros::ServiceServer clear_service_; 00124 ros::ServiceServer request_service_; 00125 ros::Publisher pub_pose_; 00126 ros::Publisher pub_roi_; 00127 ros::Publisher pub_marker_; 00128 ros::Publisher pub_cloud_; 00129 sensor_msgs::Image::ConstPtr latest_image_msg_; 00130 sensor_msgs::CameraInfo::ConstPtr latest_camera_info_msg_; 00131 sensor_msgs::PointCloud2::ConstPtr latest_cloud_msg_; 00132 bool store_pointcloud_; 00133 bool keep_organized_; 00135 // Parameters 00137 int max_image_buffer_; 00138 std::string fixed_frame_id_; 00139 boost::circular_buffer<SnapshotInformation::Ptr> snapshot_buffer_; 00140 00141 private: 00142 00143 }; 00144 } 00145 00146 #endif