depth_image_error.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_UTILS_DEPTH_IMAGE_ERROR_H_
38 #define JSK_PCL_ROS_UTILS_DEPTH_IMAGE_ERROR_H_
39 
40 #include <ros/ros.h>
41 #include <pcl_ros/pcl_nodelet.h>
42 #include <sensor_msgs/Image.h>
43 #include <geometry_msgs/PointStamped.h>
44 #include <jsk_recognition_msgs/DepthErrorResult.h>
45 
50 #include <jsk_topic_tools/connection_based_nodelet.h>
51 #include <sensor_msgs/CameraInfo.h>
52 #include <string>
53 
54 namespace jsk_pcl_ros_utils
55 {
56  class DepthImageError: public jsk_topic_tools::ConnectionBasedNodelet
57  {
58  public:
60  sensor_msgs::Image,
61  geometry_msgs::PointStamped,
62  sensor_msgs::CameraInfo
63  > ASyncPolicy;
65  sensor_msgs::Image,
66  geometry_msgs::PointStamped,
67  sensor_msgs::CameraInfo
68  > SyncPolicy;
70  virtual ~DepthImageError();
71  protected:
72  virtual void onInit();
73  virtual void calcError(const sensor_msgs::Image::ConstPtr& depth_image,
74  const geometry_msgs::PointStamped::ConstPtr& uv_point,
75  const sensor_msgs::CameraInfo::ConstPtr& camera_info);
76  virtual void subscribe();
77  virtual void unsubscribe();
83  bool approximate_sync_;
84  private:
85  };
86 }
87 
88 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::DepthImageError::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: depth_image_error.h:145
jsk_pcl_ros_utils::DepthImageError::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > SyncPolicy
Definition: depth_image_error.h:132
ros::Publisher
boost::shared_ptr
jsk_pcl_ros_utils::DepthImageError::approximate_sync_
bool approximate_sync_
Definition: depth_image_error.h:147
ros.h
jsk_pcl_ros_utils::DepthImageError::~DepthImageError
virtual ~DepthImageError()
Definition: depth_image_error_nodelet.cpp:83
jsk_pcl_ros_utils::DepthImageError::sub_point_
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_
Definition: depth_image_error.h:143
time_synchronizer.h
jsk_pcl_ros_utils::DepthImageError::subscribe
virtual void subscribe()
Definition: depth_image_error_nodelet.cpp:95
jsk_pcl_ros_utils::DepthImageError::depth_error_publisher_
ros::Publisher depth_error_publisher_
Definition: depth_image_error.h:133
message_filters::Subscriber< sensor_msgs::Image >
jsk_pcl_ros_utils::DepthImageError::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: depth_image_error.h:146
pcl_nodelet.h
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros_utils::DepthImageError::onInit
virtual void onInit()
Definition: depth_image_error_nodelet.cpp:75
jsk_pcl_ros_utils::DepthImageError::unsubscribe
virtual void unsubscribe()
Definition: depth_image_error_nodelet.cpp:114
subscriber.h
jsk_pcl_ros_utils::DepthImageError::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: depth_image_error.h:142
jsk_pcl_ros_utils::DepthImageError::calcError
virtual void calcError(const sensor_msgs::Image::ConstPtr &depth_image, const geometry_msgs::PointStamped::ConstPtr &uv_point, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
Definition: depth_image_error_nodelet.cpp:121
synchronizer.h
jsk_pcl_ros_utils::DepthImageError::sub_camera_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
Definition: depth_image_error.h:144
approximate_time.h
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::DepthImageError::ASyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > ASyncPolicy
Definition: depth_image_error.h:127


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43