depth_calibration_nodelet.cpp
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 
38 #include <cv_bridge/cv_bridge.h>
40 
41 namespace jsk_pcl_ros
42 {
44  {
45  DiagnosticNodelet::onInit();
46  if (pnh_->hasParam("coefficients2")) {
48  *pnh_, "coefficients2", coefficients2_);
49  }
50  else {
51  coefficients2_.assign(5, 0);
52  }
53  if (pnh_->hasParam("coefficients1")) {
55  *pnh_, "coefficients1", coefficients1_);
56  }
57  else {
58  coefficients1_.assign(5, 0);
59  coefficients1_[4] = 1.0;
60  }
61  if (pnh_->hasParam("coefficients0")) {
63  *pnh_, "coefficients0", coefficients0_);
64  }
65  else {
66  coefficients0_.assign(5, 0);
67  }
68  pnh_->param("use_abs", use_abs_, false);
69  pnh_->param("uv_scale", uv_scale_, 1.0);
70  printModel();
71  set_calibration_parameter_srv_ = pnh_->advertiseService(
72  "set_calibration_parameter",
74  this);
75  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
77  }
78 
80  {
81  NODELET_INFO("C2(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
83  NODELET_INFO("C1(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
85  NODELET_INFO("C0(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
87  if (use_abs_) {
88  NODELET_INFO("use_abs: True");
89  }
90  else {
91  NODELET_INFO("use_abs: False");
92  }
93  }
94 
96  jsk_recognition_msgs::SetDepthCalibrationParameter::Request& req,
97  jsk_recognition_msgs::SetDepthCalibrationParameter::Response& res)
98  {
99  boost::mutex::scoped_lock lock(mutex_);
100  coefficients2_ = req.parameter.coefficients2;
101  coefficients1_ = req.parameter.coefficients1;
102  coefficients0_ = req.parameter.coefficients0;
103  use_abs_ = req.parameter.use_abs;
104  printModel();
105  return true;
106  }
107 
109  {
110  sub_input_.subscribe(*pnh_, "input", 1);
111  sub_camera_info_.subscribe(*pnh_, "camera_info", 1);
112  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
113  sync_->connectInput(sub_input_, sub_camera_info_);
114  sync_->registerCallback(boost::bind(&DepthCalibration::calibrate, this, _1, _2));
115  }
116 
118  {
121  }
122 
124  const sensor_msgs::Image::ConstPtr& msg,
125  const sensor_msgs::CameraInfo::ConstPtr& camera_info)
126  {
127  boost::mutex::scoped_lock lock(mutex_);
128  cv_bridge::CvImagePtr cv_ptr;
129  try
130  {
132  }
133  catch (cv_bridge::Exception& e)
134  {
135  NODELET_ERROR("cv_bridge exception: %s", e.what());
136  return;
137  }
138  cv::Mat image = cv_ptr->image;
139  cv::Mat output_image = image.clone();
140  double cu = camera_info->P[2];
141  double cv = camera_info->P[6];
142  for(int v = 0; v < image.rows; v++) {
143  for(int u = 0; u < image.cols; u++) {
144  float z = image.at<float>(v, u);
145  if (std::isnan(z)) {
146  output_image.at<float>(v, u) = z;
147  }
148  else {
149  output_image.at<float>(v, u) = applyModel(z, u, v, cu, cv);
150  }
151  //NODELET_INFO("z: %f", z);
152  }
153  }
154  sensor_msgs::Image::Ptr ros_image = cv_bridge::CvImage(msg->header, "32FC1", output_image).toImageMsg();
155  pub_.publish(ros_image);
156  }
157 
158 }
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::DepthCalibration, nodelet::Nodelet)
ros::ServiceServer set_calibration_parameter_srv_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void calibrate(const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
boost::shared_ptr< ros::NodeHandle > pnh_
const std::string TYPE_32FC1
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
std::vector< double > coefficients1_
std::vector< double > coefficients2_
#define NODELET_INFO(...)
virtual bool setCalibrationParameter(jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
GLfloat v[8][3]
message_filters::Subscriber< sensor_msgs::Image > sub_input_
std::vector< double > coefficients0_
sensor_msgs::ImagePtr toImageMsg() const
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