intermittent_image_annotator.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_
38 #define JSK_PCL_ROS_INTERMITTENT_IMAGE_ANNOTATOR_H_
39 
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>
45 
48 #include <boost/circular_buffer.hpp>
49 #include <Eigen/Geometry>
50 #include <geometry_msgs/PolygonStamped.h>
51 #include <jsk_recognition_msgs/PosedCameraInfo.h>
52 #include <pcl_ros/transforms.h>
53 
54 
55 namespace jsk_pcl_ros
56 {
57  class SnapshotInformation
58  {
59  public:
62  virtual ~SnapshotInformation() {};
63 
64  Eigen::Affine3d camera_pose_;
65  cv::Mat image_;
67  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_;
68  protected:
69  private:
70 
71  };
72 
73  class IntermittentImageAnnotator: public jsk_topic_tools::DiagnosticNodelet
74  {
75  public:
78  DiagnosticNodelet("IntermittentImageAnnotator") {}
79 
80  protected:
82  // methods
84  virtual void onInit();
85  virtual void subscribe();
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);
101  virtual bool clearCallback(
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);
110  // ROS variables
113  double rate_;
127  sensor_msgs::Image::ConstPtr latest_image_msg_;
128  sensor_msgs::CameraInfo::ConstPtr latest_camera_info_msg_;
129  sensor_msgs::PointCloud2::ConstPtr latest_cloud_msg_;
133  // Parameters
135  int max_image_buffer_;
136  std::string fixed_frame_id_;
137  boost::circular_buffer<SnapshotInformation::Ptr> snapshot_buffer_;
138 
139  private:
140 
141  };
142 }
143 
144 #endif
jsk_pcl_ros::IntermittentImageAnnotator::publishCroppedPointCloud
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)
Definition: intermittent_image_annotator_nodelet.cpp:224
jsk_pcl_ros::IntermittentImageAnnotator::unsubscribe
virtual void unsubscribe()
Definition: intermittent_image_annotator_nodelet.cpp:99
jsk_pcl_ros::SnapshotInformation::camera_
image_geometry::PinholeCameraModel camera_
Definition: intermittent_image_annotator.h:130
jsk_pcl_ros::IntermittentImageAnnotator::latest_image_msg_
sensor_msgs::Image::ConstPtr latest_image_msg_
Definition: intermittent_image_annotator.h:159
ros::Publisher
jsk_pcl_ros::IntermittentImageAnnotator::pub_pose_
ros::Publisher pub_pose_
Definition: intermittent_image_annotator.h:155
boost::shared_ptr
jsk_pcl_ros::IntermittentImageAnnotator::fixed_frame_id_
std::string fixed_frame_id_
Definition: intermittent_image_annotator.h:168
jsk_pcl_ros::IntermittentImageAnnotator::image_sub_
image_transport::CameraSubscriber image_sub_
Definition: intermittent_image_annotator.h:148
pinhole_camera_model.h
jsk_pcl_ros::IntermittentImageAnnotator::request_service_
ros::ServiceServer request_service_
Definition: intermittent_image_annotator.h:154
jsk_pcl_ros::IntermittentImageAnnotator::requestCallback
virtual bool requestCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: intermittent_image_annotator_nodelet.cpp:425
jsk_pcl_ros::SnapshotInformation::Ptr
boost::shared_ptr< SnapshotInformation > Ptr
Definition: intermittent_image_annotator.h:124
jsk_pcl_ros::IntermittentImageAnnotator::clearCallback
virtual bool clearCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: intermittent_image_annotator_nodelet.cpp:416
tf_listener_singleton.h
jsk_pcl_ros::IntermittentImageAnnotator::rectCallback
virtual void rectCallback(const geometry_msgs::PolygonStamped::ConstPtr &rect)
Definition: intermittent_image_annotator_nodelet.cpp:103
jsk_pcl_ros::IntermittentImageAnnotator::keep_organized_
bool keep_organized_
Definition: intermittent_image_annotator.h:163
jsk_pcl_ros::IntermittentImageAnnotator::cloudCallback
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Definition: intermittent_image_annotator_nodelet.cpp:281
transforms.h
jsk_pcl_ros::SnapshotInformation::~SnapshotInformation
virtual ~SnapshotInformation()
Definition: intermittent_image_annotator.h:126
jsk_pcl_ros::IntermittentImageAnnotator::cloud_sub_
ros::Subscriber cloud_sub_
Definition: intermittent_image_annotator.h:151
ros::ServiceServer
jsk_pcl_ros::SnapshotInformation::cloud_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_
Definition: intermittent_image_annotator.h:131
jsk_pcl_ros::IntermittentImageAnnotator::cameraCallback
virtual void cameraCallback(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Definition: intermittent_image_annotator_nodelet.cpp:288
jsk_pcl_ros::IntermittentImageAnnotator::rect_sub_
ros::Subscriber rect_sub_
Definition: intermittent_image_annotator.h:150
jsk_pcl_ros::IntermittentImageAnnotator::latest_camera_info_msg_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_msg_
Definition: intermittent_image_annotator.h:160
jsk_pcl_ros::SnapshotInformation::image_
cv::Mat image_
Definition: intermittent_image_annotator.h:129
jsk_pcl_ros::IntermittentImageAnnotator::mutex_
boost::mutex mutex_
Definition: intermittent_image_annotator.h:149
A
jsk_pcl_ros::IntermittentImageAnnotator::subscribe
virtual void subscribe()
Definition: intermittent_image_annotator_nodelet.cpp:95
jsk_pcl_ros::SnapshotInformation::SnapshotInformation
SnapshotInformation()
Definition: intermittent_image_annotator.h:125
jsk_pcl_ros::IntermittentImageAnnotator::Ptr
boost::shared_ptr< IntermittentImageAnnotator > Ptr
Definition: intermittent_image_annotator.h:108
jsk_pcl_ros
Definition: add_color_from_image.h:51
image_transport::CameraSubscriber
jsk_pcl_ros::IntermittentImageAnnotator::pub_cloud_
ros::Publisher pub_cloud_
Definition: intermittent_image_annotator.h:158
jsk_pcl_ros::IntermittentImageAnnotator::waitForNextImage
virtual void waitForNextImage()
Definition: intermittent_image_annotator_nodelet.cpp:317
jsk_pcl_ros::IntermittentImageAnnotator::clear_service_
ros::ServiceServer clear_service_
Definition: intermittent_image_annotator.h:153
jsk_pcl_ros::IntermittentImageAnnotator::store_pointcloud_
bool store_pointcloud_
Definition: intermittent_image_annotator.h:162
jsk_pcl_ros::IntermittentImageAnnotator::image_pub_
image_transport::Publisher image_pub_
Definition: intermittent_image_annotator.h:147
jsk_pcl_ros::IntermittentImageAnnotator::pub_roi_
ros::Publisher pub_roi_
Definition: intermittent_image_annotator.h:156
jsk_pcl_ros::IntermittentImageAnnotator::last_publish_time_
ros::Time last_publish_time_
Definition: intermittent_image_annotator.h:146
image_transport.h
jsk_pcl_ros::IntermittentImageAnnotator::listener_
tf::TransformListener * listener_
Definition: intermittent_image_annotator.h:144
jsk_pcl_ros::IntermittentImageAnnotator::shutter_service_
ros::ServiceServer shutter_service_
Definition: intermittent_image_annotator.h:152
jsk_pcl_ros::IntermittentImageAnnotator::shutterCallback
virtual bool shutterCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: intermittent_image_annotator_nodelet.cpp:332
jsk_pcl_ros::IntermittentImageAnnotator::snapshot_buffer_
boost::circular_buffer< SnapshotInformation::Ptr > snapshot_buffer_
Definition: intermittent_image_annotator.h:169
ros::Time
image_geometry::PinholeCameraModel
jsk_pcl_ros::IntermittentImageAnnotator::latest_cloud_msg_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_msg_
Definition: intermittent_image_annotator.h:161
image_transport::Publisher
jsk_pcl_ros::IntermittentImageAnnotator::max_image_buffer_
int max_image_buffer_
Definition: intermittent_image_annotator.h:167
tf::TransformListener
jsk_pcl_ros::SnapshotInformation::camera_pose_
Eigen::Affine3d camera_pose_
Definition: intermittent_image_annotator.h:126
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::IntermittentImageAnnotator::IntermittentImageAnnotator
IntermittentImageAnnotator()
Definition: intermittent_image_annotator.h:109
jsk_pcl_ros::IntermittentImageAnnotator::onInit
virtual void onInit()
Definition: intermittent_image_annotator_nodelet.cpp:47
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::IntermittentImageAnnotator::rate_
double rate_
Definition: intermittent_image_annotator.h:145
ros::Subscriber
jsk_pcl_ros::IntermittentImageAnnotator::pub_marker_
ros::Publisher pub_marker_
Definition: intermittent_image_annotator.h:157


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45