#include <depth_calibration.h>
|
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 () |
|
Definition at line 86 of file depth_calibration.h.
◆ PointT
◆ SyncPolicy
◆ DepthCalibration()
jsk_pcl_ros::DepthCalibration::DepthCalibration |
( |
| ) |
|
|
inline |
◆ ~DepthCalibration()
jsk_pcl_ros::DepthCalibration::~DepthCalibration |
( |
| ) |
|
|
virtual |
◆ applyModel()
virtual double jsk_pcl_ros::DepthCalibration::applyModel |
( |
double |
z, |
|
|
int |
u, |
|
|
int |
v, |
|
|
double |
cu, |
|
|
double |
cv |
|
) |
| |
|
inlineprotectedvirtual |
◆ calibrate()
void jsk_pcl_ros::DepthCalibration::calibrate |
( |
const sensor_msgs::Image::ConstPtr & |
msg, |
|
|
const sensor_msgs::CameraInfo::ConstPtr & |
camera_info |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::DepthCalibration::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ printModel()
void jsk_pcl_ros::DepthCalibration::printModel |
( |
| ) |
|
|
protectedvirtual |
◆ setCalibrationParameter()
bool jsk_pcl_ros::DepthCalibration::setCalibrationParameter |
( |
jsk_recognition_msgs::SetDepthCalibrationParameter::Request & |
req, |
|
|
jsk_recognition_msgs::SetDepthCalibrationParameter::Response & |
res |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::DepthCalibration::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::DepthCalibration::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ coefficients0_
std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients0_ |
|
protected |
◆ coefficients1_
std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients1_ |
|
protected |
◆ coefficients2_
std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients2_ |
|
protected |
◆ mutex_
◆ pub_
◆ set_calibration_parameter_srv_
◆ sub_camera_info_
◆ sub_input_
◆ sync_
◆ use_abs_
bool jsk_pcl_ros::DepthCalibration::use_abs_ |
|
protected |
◆ uv_scale_
double jsk_pcl_ros::DepthCalibration::uv_scale_ |
|
protected |
The documentation for this class was generated from the following files: