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/o2r 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"
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
55  {
56  public:
57  typedef pcl::PointXYZRGB PointT;
59  sensor_msgs::Image,
60  sensor_msgs::CameraInfo> SyncPolicy;
61 
62  DepthCalibration(): DiagnosticNodelet("DepthCalibration") { }
63  protected:
64  virtual void onInit();
65  virtual void calibrate(
66  const sensor_msgs::Image::ConstPtr& msg,
67  const sensor_msgs::CameraInfo::ConstPtr& camera_info);
68  virtual void subscribe();
69  virtual void unsubscribe();
70  virtual void printModel();
71  virtual inline double applyModel(double z, int u, int v, double cu, double cv) {
72  double z2 = z * z;
73  double uu, vv;
74  if (use_abs_) {
75  uu = uv_scale_ * std::abs(u - cu);
76  vv = uv_scale_ * std::abs(v - cv);
77  }
78  else {
79  uu = uv_scale_ * u;
80  vv = uv_scale_ * v;
81  }
82  double c2 = coefficients2_[0] * uu * uu + coefficients2_[1] * uu +
83  coefficients2_[2] * vv * vv + coefficients2_[3] * vv +
84  coefficients2_[4];
85  double c1 = coefficients1_[0] * uu * uu + coefficients1_[1] * uu +
86  coefficients1_[2] * vv * vv + coefficients1_[3] * vv +
87  coefficients1_[4];
88  double c0 = coefficients0_[0] * uu * uu + coefficients0_[1] * uu +
89  coefficients0_[2] * vv * vv + coefficients0_[3] * vv +
90  coefficients0_[4];
91  return c2 * z2 + c1 * z + c0;
92  }
93 
94  virtual bool setCalibrationParameter(
95  jsk_recognition_msgs::SetDepthCalibrationParameter::Request& req,
96  jsk_recognition_msgs::SetDepthCalibrationParameter::Response& res);
103 
104  // parameters
105  bool use_abs_;
106  double uv_scale_;
107  std::vector<double> coefficients2_;
108  std::vector<double> coefficients1_;
109  std::vector<double> coefficients0_;
110  private:
111  };
112 }
113 
114 #endif
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
ros::ServiceServer set_calibration_parameter_srv_
virtual void calibrate(const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
DiagnosticNodelet(const std::string &name)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
std::vector< double > coefficients1_
boost::mutex mutex
global mutex.
std::vector< double > coefficients2_
virtual bool setCalibrationParameter(jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res)
message_filters::Subscriber< sensor_msgs::Image > sub_input_
std::vector< double > coefficients0_
virtual double applyModel(double z, int u, int v, double cu, double cv)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46