depth_calibration.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_PCL_ROS_DEPTH_CALIBRATION_H_
37 #define JSK_PCL_ROS_DEPTH_CALIBRATION_H_
38 
39 #include "pcl_ros/pcl_nodelet.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>
47 
48 namespace jsk_pcl_ros
49 {
50 
51  // calibration:
52  // z' = C_2(u, v) z^2 + C_1(u, v) z + C_0(u, v)
53  // C_i(u, v) = au + bv + c
54  class DepthCalibration: public jsk_topic_tools::DiagnosticNodelet
55  {
56  public:
57  typedef pcl::PointXYZRGB PointT;
59  sensor_msgs::Image,
60  sensor_msgs::CameraInfo> SyncPolicy;
61 
62  DepthCalibration(): DiagnosticNodelet("DepthCalibration") { }
63  virtual ~DepthCalibration();
64  protected:
65  virtual void onInit();
66  virtual void calibrate(
67  const sensor_msgs::Image::ConstPtr& msg,
68  const sensor_msgs::CameraInfo::ConstPtr& camera_info);
69  virtual void subscribe();
70  virtual void unsubscribe();
71  virtual void printModel();
72  virtual inline double applyModel(double z, int u, int v, double cu, double cv) {
73  double z2 = z * z;
74  double uu, vv;
75  if (use_abs_) {
76  uu = uv_scale_ * std::abs(u - cu);
77  vv = uv_scale_ * std::abs(v - cv);
78  }
79  else {
80  uu = uv_scale_ * u;
81  vv = uv_scale_ * v;
82  }
83  double c2 = coefficients2_[0] * uu * uu + coefficients2_[1] * uu +
84  coefficients2_[2] * vv * vv + coefficients2_[3] * vv +
85  coefficients2_[4];
86  double c1 = coefficients1_[0] * uu * uu + coefficients1_[1] * uu +
87  coefficients1_[2] * vv * vv + coefficients1_[3] * vv +
88  coefficients1_[4];
89  double c0 = coefficients0_[0] * uu * uu + coefficients0_[1] * uu +
90  coefficients0_[2] * vv * vv + coefficients0_[3] * vv +
91  coefficients0_[4];
92  return c2 * z2 + c1 * z + c0;
93  }
94 
95  virtual bool setCalibrationParameter(
96  jsk_recognition_msgs::SetDepthCalibrationParameter::Request& req,
97  jsk_recognition_msgs::SetDepthCalibrationParameter::Response& res);
104 
105  // parameters
106  bool use_abs_;
107  double uv_scale_;
108  std::vector<double> coefficients2_;
109  std::vector<double> coefficients1_;
110  std::vector<double> coefficients0_;
111  private:
112  };
113 }
114 
115 #endif
jsk_pcl_ros::DepthCalibration::DepthCalibration
DepthCalibration()
Definition: depth_calibration.h:126
ros::Publisher
jsk_pcl_ros::DepthCalibration::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
Definition: depth_calibration.h:124
boost::shared_ptr
jsk_pcl_ros::DepthCalibration::pub_
ros::Publisher pub_
Definition: depth_calibration.h:165
jsk_pcl_ros::DepthCalibration::PointT
pcl::PointXYZRGB PointT
Definition: depth_calibration.h:121
time_synchronizer.h
jsk_pcl_ros::DepthCalibration::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: depth_calibration.h:164
jsk_pcl_ros::DepthCalibration::coefficients0_
std::vector< double > coefficients0_
Definition: depth_calibration.h:174
jsk_pcl_ros::DepthCalibration::use_abs_
bool use_abs_
Definition: depth_calibration.h:170
message_filters::Subscriber< sensor_msgs::Image >
ros::ServiceServer
pcl_nodelet.h
jsk_pcl_ros::DepthCalibration::subscribe
virtual void subscribe()
Definition: depth_calibration_nodelet.cpp:151
jsk_pcl_ros::DepthCalibration::calibrate
virtual void calibrate(const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
Definition: depth_calibration_nodelet.cpp:166
jsk_pcl_ros::DepthCalibration::setCalibrationParameter
virtual bool setCalibrationParameter(jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res)
Definition: depth_calibration_nodelet.cpp:138
jsk_pcl_ros::DepthCalibration::sub_input_
message_filters::Subscriber< sensor_msgs::Image > sub_input_
Definition: depth_calibration.h:162
jsk_pcl_ros::DepthCalibration::sub_camera_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
Definition: depth_calibration.h:163
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::DepthCalibration::~DepthCalibration
virtual ~DepthCalibration()
Definition: depth_calibration_nodelet.cpp:111
subscriber.h
jsk_pcl_ros::DepthCalibration::coefficients1_
std::vector< double > coefficients1_
Definition: depth_calibration.h:173
jsk_pcl_ros::DepthCalibration::printModel
virtual void printModel()
Definition: depth_calibration_nodelet.cpp:122
jsk_pcl_ros::DepthCalibration::set_calibration_parameter_srv_
ros::ServiceServer set_calibration_parameter_srv_
Definition: depth_calibration.h:166
synchronizer.h
jsk_pcl_ros::DepthCalibration::unsubscribe
virtual void unsubscribe()
Definition: depth_calibration_nodelet.cpp:160
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::DepthCalibration::onInit
virtual void onInit()
Definition: depth_calibration_nodelet.cpp:75
message_filters::sync_policies::ExactTime
jsk_pcl_ros::DepthCalibration::applyModel
virtual double applyModel(double z, int u, int v, double cu, double cv)
Definition: depth_calibration.h:136
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::DepthCalibration::coefficients2_
std::vector< double > coefficients2_
Definition: depth_calibration.h:172
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::DepthCalibration::mutex_
boost::mutex mutex_
Definition: depth_calibration.h:167
v
GLfloat v[8][3]
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::DepthCalibration::uv_scale_
double uv_scale_
Definition: depth_calibration.h:171
attention_pose_set.z
z
Definition: attention_pose_set.py:20


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44