depth_calibration.h
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #ifndef JSK_PCL_ROS_DEPTH_CALIBRATION_H_
00037 #define JSK_PCL_ROS_DEPTH_CALIBRATION_H_
00038 
00039 #include "pcl_ros/pcl_nodelet.h"
00040 #include "jsk_topic_tools/diagnostic_nodelet.h"
00041 #include "jsk_pcl_ros/SetDepthCalibrationParameter.h"
00042 #include <message_filters/subscriber.h>
00043 #include <message_filters/time_synchronizer.h>
00044 #include <message_filters/synchronizer.h>
00045 #include <sensor_msgs/CameraInfo.h>
00046 #include <sensor_msgs/Image.h>
00047 
00048 namespace jsk_pcl_ros
00049 {
00050 
00051   // calibration:
00052   // z' = C_2(u, v) z^2 + C_1(u, v) z + C_0(u, v)
00053   // C_i(u, v) = au + bv + c
00054   class DepthCalibration: public jsk_topic_tools::DiagnosticNodelet
00055   {
00056   public:
00057     typedef pcl::PointXYZRGB PointT;
00058     typedef message_filters::sync_policies::ExactTime<
00059         sensor_msgs::Image,
00060         sensor_msgs::CameraInfo> SyncPolicy;
00061 
00062     DepthCalibration(): DiagnosticNodelet("DepthCalibration") { }
00063   protected:
00064     virtual void onInit();
00065     virtual void calibrate(
00066       const sensor_msgs::Image::ConstPtr& msg,
00067       const sensor_msgs::CameraInfo::ConstPtr& camera_info);
00068     virtual void subscribe();
00069     virtual void unsubscribe();
00070     virtual void printModel();
00071     virtual void updateDiagnostic(
00072       diagnostic_updater::DiagnosticStatusWrapper &stat);
00073     virtual inline double applyModel(double z, int u, int v, double cu, double cv) {
00074       double z2 = z * z;
00075       double uu, vv;
00076       if (use_abs_) {
00077         uu = uv_scale_ * std::abs(u - cu);
00078         vv = uv_scale_ * std::abs(v - cv);
00079       }
00080       else {
00081         uu = uv_scale_ * u;
00082         vv = uv_scale_ * v;
00083       }
00084       double c2 = coefficients2_[0] * uu * uu + coefficients2_[1] * uu +
00085         coefficients2_[2] * vv * vv + coefficients2_[3] * vv + 
00086         coefficients2_[4];
00087       double c1 = coefficients1_[0] * uu * uu + coefficients1_[1] * uu +
00088         coefficients1_[2] * vv * vv + coefficients1_[3] * vv + 
00089         coefficients1_[4];
00090       double c0 = coefficients0_[0] * uu * uu + coefficients0_[1] * uu +
00091         coefficients0_[2] * vv * vv + coefficients0_[3] * vv + 
00092         coefficients0_[4];
00093       return c2 * z2 + c1 * z + c0;
00094     }
00095     
00096     virtual bool setCalibrationParameter(
00097       SetDepthCalibrationParameter::Request& req,
00098       SetDepthCalibrationParameter::Response& res);
00099     message_filters::Subscriber<sensor_msgs::Image> sub_input_;
00100     message_filters::Subscriber<sensor_msgs::CameraInfo> sub_camera_info_;
00101     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00102     ros::Publisher pub_;
00103     ros::ServiceServer set_calibration_parameter_srv_;
00104     boost::mutex mutex_;
00105     
00106     // parameters
00107     bool use_abs_;
00108     double uv_scale_;
00109     std::vector<double> coefficients2_;
00110     std::vector<double> coefficients1_;
00111     std::vector<double> coefficients0_;
00112   private:
00113   };
00114 }
00115 
00116 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47