#include <depth_calibration.h>
| Public Types | |
| typedef pcl::PointXYZRGB | PointT | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::Image, sensor_msgs::CameraInfo > | SyncPolicy | 
| Public Member Functions | |
| DepthCalibration () | |
| Protected Member Functions | |
| virtual double | applyModel (double z, int u, int v, double cu, double cv) | 
| virtual void | calibrate (const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info) | 
| virtual void | onInit () | 
| virtual void | printModel () | 
| virtual bool | setCalibrationParameter (jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| std::vector< double > | coefficients0_ | 
| std::vector< double > | coefficients1_ | 
| std::vector< double > | coefficients2_ | 
| boost::mutex | mutex_ | 
| ros::Publisher | pub_ | 
| ros::ServiceServer | set_calibration_parameter_srv_ | 
| message_filters::Subscriber < sensor_msgs::CameraInfo > | sub_camera_info_ | 
| message_filters::Subscriber < sensor_msgs::Image > | sub_input_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
| bool | use_abs_ | 
| double | uv_scale_ | 
Definition at line 54 of file depth_calibration.h.
| typedef pcl::PointXYZRGB jsk_pcl_ros::DepthCalibration::PointT | 
Definition at line 57 of file depth_calibration.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo> jsk_pcl_ros::DepthCalibration::SyncPolicy | 
Definition at line 60 of file depth_calibration.h.
| jsk_pcl_ros::DepthCalibration::DepthCalibration | ( | ) |  [inline] | 
Definition at line 62 of file depth_calibration.h.
| virtual double jsk_pcl_ros::DepthCalibration::applyModel | ( | double | z, | 
| int | u, | ||
| int | v, | ||
| double | cu, | ||
| double | cv | ||
| ) |  [inline, protected, virtual] | 
Definition at line 71 of file depth_calibration.h.
| void jsk_pcl_ros::DepthCalibration::calibrate | ( | const sensor_msgs::Image::ConstPtr & | msg, | 
| const sensor_msgs::CameraInfo::ConstPtr & | camera_info | ||
| ) |  [protected, virtual] | 
Definition at line 123 of file depth_calibration_nodelet.cpp.
| void jsk_pcl_ros::DepthCalibration::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 43 of file depth_calibration_nodelet.cpp.
| void jsk_pcl_ros::DepthCalibration::printModel | ( | ) |  [protected, virtual] | 
Definition at line 79 of file depth_calibration_nodelet.cpp.
| bool jsk_pcl_ros::DepthCalibration::setCalibrationParameter | ( | jsk_recognition_msgs::SetDepthCalibrationParameter::Request & | req, | 
| jsk_recognition_msgs::SetDepthCalibrationParameter::Response & | res | ||
| ) |  [protected, virtual] | 
Definition at line 95 of file depth_calibration_nodelet.cpp.
| void jsk_pcl_ros::DepthCalibration::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 108 of file depth_calibration_nodelet.cpp.
| void jsk_pcl_ros::DepthCalibration::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 117 of file depth_calibration_nodelet.cpp.
| std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients0_  [protected] | 
Definition at line 109 of file depth_calibration.h.
| std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients1_  [protected] | 
Definition at line 108 of file depth_calibration.h.
| std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients2_  [protected] | 
Definition at line 107 of file depth_calibration.h.
| boost::mutex jsk_pcl_ros::DepthCalibration::mutex_  [protected] | 
Definition at line 102 of file depth_calibration.h.
| ros::Publisher jsk_pcl_ros::DepthCalibration::pub_  [protected] | 
Definition at line 100 of file depth_calibration.h.
Definition at line 101 of file depth_calibration.h.
| message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::DepthCalibration::sub_camera_info_  [protected] | 
Definition at line 98 of file depth_calibration.h.
| message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::DepthCalibration::sub_input_  [protected] | 
Definition at line 97 of file depth_calibration.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::DepthCalibration::sync_  [protected] | 
Definition at line 99 of file depth_calibration.h.
| bool jsk_pcl_ros::DepthCalibration::use_abs_  [protected] | 
Definition at line 105 of file depth_calibration.h.
| double jsk_pcl_ros::DepthCalibration::uv_scale_  [protected] | 
Definition at line 106 of file depth_calibration.h.