#include <depth_image_error.h>
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_ |
Definition at line 88 of file depth_image_error.h.
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.
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.
|
virtual |
Definition at line 83 of file depth_image_error_nodelet.cpp.
|
protectedvirtual |
Definition at line 121 of file depth_image_error_nodelet.cpp.
|
protectedvirtual |
Definition at line 75 of file depth_image_error_nodelet.cpp.
|
protectedvirtual |
Definition at line 95 of file depth_image_error_nodelet.cpp.
|
protectedvirtual |
Definition at line 114 of file depth_image_error_nodelet.cpp.
|
protected |
Definition at line 147 of file depth_image_error.h.
|
protected |
Definition at line 145 of file depth_image_error.h.
ros::Publisher jsk_pcl_ros_utils::DepthImageError::depth_error_publisher_ |
Definition at line 133 of file depth_image_error.h.
|
protected |
Definition at line 144 of file depth_image_error.h.
|
protected |
Definition at line 142 of file depth_image_error.h.
|
protected |
Definition at line 143 of file depth_image_error.h.
|
protected |
Definition at line 146 of file depth_image_error.h.