Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::DepthCalibration Class Reference

#include <depth_calibration.h>

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

Public Types

typedef pcl::PointXYZRGB PointT
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
 

Public Member Functions

 DepthCalibration ()
 
virtual ~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_
 

Detailed Description

Definition at line 86 of file depth_calibration.h.

Member Typedef Documentation

◆ PointT

typedef pcl::PointXYZRGB jsk_pcl_ros::DepthCalibration::PointT

Definition at line 121 of file depth_calibration.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo> jsk_pcl_ros::DepthCalibration::SyncPolicy

Definition at line 124 of file depth_calibration.h.

Constructor & Destructor Documentation

◆ DepthCalibration()

jsk_pcl_ros::DepthCalibration::DepthCalibration ( )
inline

Definition at line 126 of file depth_calibration.h.

◆ ~DepthCalibration()

jsk_pcl_ros::DepthCalibration::~DepthCalibration ( )
virtual

Definition at line 111 of file depth_calibration_nodelet.cpp.

Member Function Documentation

◆ applyModel()

virtual double jsk_pcl_ros::DepthCalibration::applyModel ( double  z,
int  u,
int  v,
double  cu,
double  cv 
)
inlineprotectedvirtual

Definition at line 136 of file depth_calibration.h.

◆ calibrate()

void jsk_pcl_ros::DepthCalibration::calibrate ( const sensor_msgs::Image::ConstPtr &  msg,
const sensor_msgs::CameraInfo::ConstPtr &  camera_info 
)
protectedvirtual

Definition at line 166 of file depth_calibration_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::DepthCalibration::onInit ( )
protectedvirtual

Definition at line 75 of file depth_calibration_nodelet.cpp.

◆ printModel()

void jsk_pcl_ros::DepthCalibration::printModel ( )
protectedvirtual

Definition at line 122 of file depth_calibration_nodelet.cpp.

◆ setCalibrationParameter()

bool jsk_pcl_ros::DepthCalibration::setCalibrationParameter ( jsk_recognition_msgs::SetDepthCalibrationParameter::Request &  req,
jsk_recognition_msgs::SetDepthCalibrationParameter::Response &  res 
)
protectedvirtual

Definition at line 138 of file depth_calibration_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::DepthCalibration::subscribe ( )
protectedvirtual

Definition at line 151 of file depth_calibration_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::DepthCalibration::unsubscribe ( )
protectedvirtual

Definition at line 160 of file depth_calibration_nodelet.cpp.

Member Data Documentation

◆ coefficients0_

std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients0_
protected

Definition at line 174 of file depth_calibration.h.

◆ coefficients1_

std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients1_
protected

Definition at line 173 of file depth_calibration.h.

◆ coefficients2_

std::vector<double> jsk_pcl_ros::DepthCalibration::coefficients2_
protected

Definition at line 172 of file depth_calibration.h.

◆ mutex_

boost::mutex jsk_pcl_ros::DepthCalibration::mutex_
protected

Definition at line 167 of file depth_calibration.h.

◆ pub_

ros::Publisher jsk_pcl_ros::DepthCalibration::pub_
protected

Definition at line 165 of file depth_calibration.h.

◆ set_calibration_parameter_srv_

ros::ServiceServer jsk_pcl_ros::DepthCalibration::set_calibration_parameter_srv_
protected

Definition at line 166 of file depth_calibration.h.

◆ sub_camera_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::DepthCalibration::sub_camera_info_
protected

Definition at line 163 of file depth_calibration.h.

◆ sub_input_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::DepthCalibration::sub_input_
protected

Definition at line 162 of file depth_calibration.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::DepthCalibration::sync_
protected

Definition at line 164 of file depth_calibration.h.

◆ use_abs_

bool jsk_pcl_ros::DepthCalibration::use_abs_
protected

Definition at line 170 of file depth_calibration.h.

◆ uv_scale_

double jsk_pcl_ros::DepthCalibration::uv_scale_
protected

Definition at line 171 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 Tue Jan 7 2025 04:05:45