Go to the documentation of this file.
   36 #ifndef JSK_PCL_ROS_DEPTH_CALIBRATION_H_ 
   37 #define JSK_PCL_ROS_DEPTH_CALIBRATION_H_ 
   40 #include "jsk_topic_tools/diagnostic_nodelet.h" 
   41 #include "jsk_recognition_msgs/SetDepthCalibrationParameter.h" 
   45 #include <sensor_msgs/CameraInfo.h> 
   46 #include <sensor_msgs/Image.h> 
   54   class DepthCalibration: 
public jsk_topic_tools::DiagnosticNodelet
 
   57     typedef pcl::PointXYZRGB 
PointT;
 
   67       const sensor_msgs::Image::ConstPtr& 
msg,
 
   68       const sensor_msgs::CameraInfo::ConstPtr& camera_info);
 
   72     virtual inline double applyModel(
double z, 
int u, 
int v, 
double cu, 
double cv) {
 
   92       return c2 * z2 + c1 * 
z + c0;
 
   96       jsk_recognition_msgs::SetDepthCalibrationParameter::Request& 
req,
 
   97       jsk_recognition_msgs::SetDepthCalibrationParameter::Response& 
res);
 
  
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
std::vector< double > coefficients0_
virtual void calibrate(const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
virtual bool setCalibrationParameter(jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res)
message_filters::Subscriber< sensor_msgs::Image > sub_input_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
virtual ~DepthCalibration()
std::vector< double > coefficients1_
virtual void printModel()
ros::ServiceServer set_calibration_parameter_srv_
virtual void unsubscribe()
boost::mutex mutex
global mutex.
virtual double applyModel(double z, int u, int v, double cu, double cv)
std::vector< double > coefficients2_
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11