Public Types | Public Attributes | Protected Member Functions | Protected Attributes
jsk_pcl_ros_utils::DepthImageError Class Reference

#include <depth_image_error.h>

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

List of all members.

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 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 56 of file depth_image_error.h.


Member Typedef Documentation

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

Definition at line 63 of file depth_image_error.h.

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

Definition at line 68 of file depth_image_error.h.


Member Function Documentation

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 
) [protected, virtual]

Definition at line 76 of file depth_image_error_nodelet.cpp.

void jsk_pcl_ros_utils::DepthImageError::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 43 of file depth_image_error_nodelet.cpp.

void jsk_pcl_ros_utils::DepthImageError::subscribe ( ) [protected, virtual]
void jsk_pcl_ros_utils::DepthImageError::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 82 of file depth_image_error.h.

Definition at line 80 of file depth_image_error.h.

Definition at line 69 of file depth_image_error.h.

Definition at line 79 of file depth_image_error.h.

Definition at line 77 of file depth_image_error.h.

Definition at line 78 of file depth_image_error.h.

Definition at line 81 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 Sun Oct 8 2017 02:43:05