Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::DepthCalibration Class Reference

#include <depth_calibration.h>

Inheritance diagram for jsk_pcl_ros::DepthCalibration:
Inheritance graph
[legend]

List of all members.

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 (SetDepthCalibrationParameter::Request &req, SetDepthCalibrationParameter::Response &res)
virtual void subscribe ()
virtual void unsubscribe ()
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)

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_

Detailed Description

Definition at line 54 of file depth_calibration.h.


Member Typedef Documentation

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.


Constructor & Destructor Documentation

Definition at line 62 of file depth_calibration.h.


Member Function Documentation

virtual double jsk_pcl_ros::DepthCalibration::applyModel ( double  z,
int  u,
int  v,
double  cu,
double  cv 
) [inline, protected, virtual]

Definition at line 73 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 122 of file depth_calibration_nodelet.cpp.

void jsk_pcl_ros::DepthCalibration::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 43 of file depth_calibration_nodelet.cpp.

void jsk_pcl_ros::DepthCalibration::printModel ( ) [protected, virtual]

Definition at line 78 of file depth_calibration_nodelet.cpp.

bool jsk_pcl_ros::DepthCalibration::setCalibrationParameter ( SetDepthCalibrationParameter::Request &  req,
SetDepthCalibrationParameter::Response &  res 
) [protected, virtual]

Definition at line 94 of file depth_calibration_nodelet.cpp.

void jsk_pcl_ros::DepthCalibration::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::DepthCalibration::unsubscribe ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 157 of file depth_calibration_nodelet.cpp.


Member Data Documentation

Definition at line 111 of file depth_calibration.h.

Definition at line 110 of file depth_calibration.h.

Definition at line 109 of file depth_calibration.h.

Definition at line 104 of file depth_calibration.h.

Definition at line 102 of file depth_calibration.h.

Definition at line 103 of file depth_calibration.h.

Definition at line 100 of file depth_calibration.h.

Definition at line 99 of file depth_calibration.h.

Definition at line 101 of file depth_calibration.h.

Definition at line 107 of file depth_calibration.h.

Definition at line 108 of file depth_calibration.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49