Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros_utils::DepthImageError Class Reference

#include <depth_image_error.h>

Inheritance diagram for jsk_pcl_ros_utils::DepthImageError:
Inheritance graph
[legend]

Public Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > ASyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > SyncPolicy
 

Public Member Functions

virtual ~DepthImageError ()
 

Public Attributes

ros::Publisher depth_error_publisher_
 

Protected Member Functions

virtual void calcError (const sensor_msgs::Image::ConstPtr &depth_image, const geometry_msgs::PointStamped::ConstPtr &uv_point, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
 
virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

bool approximate_sync_
 
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
 
message_filters::Subscriber< sensor_msgs::Image > sub_image_
 
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 

Detailed Description

Definition at line 88 of file depth_image_error.h.

Member Typedef Documentation

◆ ASyncPolicy

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > jsk_pcl_ros_utils::DepthImageError::ASyncPolicy

Definition at line 127 of file depth_image_error.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > jsk_pcl_ros_utils::DepthImageError::SyncPolicy

Definition at line 132 of file depth_image_error.h.

Constructor & Destructor Documentation

◆ ~DepthImageError()

jsk_pcl_ros_utils::DepthImageError::~DepthImageError ( )
virtual

Definition at line 83 of file depth_image_error_nodelet.cpp.

Member Function Documentation

◆ calcError()

void jsk_pcl_ros_utils::DepthImageError::calcError ( const sensor_msgs::Image::ConstPtr &  depth_image,
const geometry_msgs::PointStamped::ConstPtr &  uv_point,
const sensor_msgs::CameraInfo::ConstPtr &  camera_info 
)
protectedvirtual

Definition at line 121 of file depth_image_error_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros_utils::DepthImageError::onInit ( )
protectedvirtual

Definition at line 75 of file depth_image_error_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros_utils::DepthImageError::subscribe ( )
protectedvirtual

Definition at line 95 of file depth_image_error_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros_utils::DepthImageError::unsubscribe ( )
protectedvirtual

Definition at line 114 of file depth_image_error_nodelet.cpp.

Member Data Documentation

◆ approximate_sync_

bool jsk_pcl_ros_utils::DepthImageError::approximate_sync_
protected

Definition at line 147 of file depth_image_error.h.

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy> > jsk_pcl_ros_utils::DepthImageError::async_
protected

Definition at line 145 of file depth_image_error.h.

◆ depth_error_publisher_

ros::Publisher jsk_pcl_ros_utils::DepthImageError::depth_error_publisher_

Definition at line 133 of file depth_image_error.h.

◆ sub_camera_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros_utils::DepthImageError::sub_camera_info_
protected

Definition at line 144 of file depth_image_error.h.

◆ sub_image_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros_utils::DepthImageError::sub_image_
protected

Definition at line 142 of file depth_image_error.h.

◆ sub_point_

message_filters::Subscriber<geometry_msgs::PointStamped> jsk_pcl_ros_utils::DepthImageError::sub_point_
protected

Definition at line 143 of file depth_image_error.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros_utils::DepthImageError::sync_
protected

Definition at line 146 of file depth_image_error.h.


The documentation for this class was generated from the following files:


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