#include <depth_image_error.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime < 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 | |
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_ |
Definition at line 56 of file depth_image_error.h.
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PointStamped, sensor_msgs::CameraInfo > jsk_pcl_ros::DepthImageError::SyncPolicy |
Definition at line 63 of file depth_image_error.h.
void jsk_pcl_ros::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 68 of file depth_image_error_nodelet.cpp.
void jsk_pcl_ros::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::DepthImageError::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 49 of file depth_image_error_nodelet.cpp.
void jsk_pcl_ros::DepthImageError::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 60 of file depth_image_error_nodelet.cpp.
Definition at line 64 of file depth_image_error.h.
message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::DepthImageError::sub_camera_info_ [protected] |
Definition at line 74 of file depth_image_error.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::DepthImageError::sub_image_ [protected] |
Definition at line 72 of file depth_image_error.h.
message_filters::Subscriber<geometry_msgs::PointStamped> jsk_pcl_ros::DepthImageError::sub_point_ [protected] |
Definition at line 73 of file depth_image_error.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::DepthImageError::sync_ [protected] |
Definition at line 75 of file depth_image_error.h.