Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_UTILS_DEPTH_IMAGE_ERROR_H_
38 #define JSK_PCL_ROS_UTILS_DEPTH_IMAGE_ERROR_H_
42 #include <sensor_msgs/Image.h>
43 #include <geometry_msgs/PointStamped.h>
44 #include <jsk_recognition_msgs/DepthErrorResult.h>
50 #include <jsk_topic_tools/connection_based_nodelet.h>
51 #include <sensor_msgs/CameraInfo.h>
56 class DepthImageError:
public jsk_topic_tools::ConnectionBasedNodelet
61 geometry_msgs::PointStamped,
62 sensor_msgs::CameraInfo
66 geometry_msgs::PointStamped,
67 sensor_msgs::CameraInfo
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);
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > SyncPolicy
virtual ~DepthImageError()
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_
ros::Publisher depth_error_publisher_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::Image > sub_image_
virtual void calcError(const sensor_msgs::Image::ConstPtr &depth_image, const geometry_msgs::PointStamped::ConstPtr &uv_point, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > ASyncPolicy
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43