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/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 
37 #include <jsk_topic_tools/rosparam_utils.h>
38 #include <cv_bridge/cv_bridge.h>
40 
41 namespace jsk_pcl_ros
42 {
44  {
45  DiagnosticNodelet::onInit();
46  if (pnh_->hasParam("coefficients2")) {
47  jsk_topic_tools::readVectorParameter(
48  *pnh_, "coefficients2", coefficients2_);
49  }
50  else {
51  coefficients2_.assign(5, 0);
52  }
53  if (pnh_->hasParam("coefficients1")) {
54  jsk_topic_tools::readVectorParameter(
55  *pnh_, "coefficients1", coefficients1_);
56  }
57  else {
58  coefficients1_.assign(5, 0);
59  coefficients1_[4] = 1.0;
60  }
61  if (pnh_->hasParam("coefficients0")) {
62  jsk_topic_tools::readVectorParameter(
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);
76  onInitPostProcess();
77  }
78 
80  // message_filters::Synchronizer needs to be called reset
81  // before message_filters::Subscriber is freed.
82  // Calling reset fixes the following error on shutdown of the nodelet:
83  // terminate called after throwing an instance of
84  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
85  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
86  // Also see https://github.com/ros/ros_comm/issues/720 .
87  sync_.reset();
88  }
89 
91  {
92  NODELET_INFO("C2(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
94  NODELET_INFO("C1(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
96  NODELET_INFO("C0(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
98  if (use_abs_) {
99  NODELET_INFO("use_abs: True");
100  }
101  else {
102  NODELET_INFO("use_abs: False");
103  }
104  }
105 
107  jsk_recognition_msgs::SetDepthCalibrationParameter::Request& req,
108  jsk_recognition_msgs::SetDepthCalibrationParameter::Response& res)
109  {
110  boost::mutex::scoped_lock lock(mutex_);
111  coefficients2_ = req.parameter.coefficients2;
112  coefficients1_ = req.parameter.coefficients1;
113  coefficients0_ = req.parameter.coefficients0;
114  use_abs_ = req.parameter.use_abs;
115  printModel();
116  return true;
117  }
118 
120  {
121  sub_input_.subscribe(*pnh_, "input", 1);
122  sub_camera_info_.subscribe(*pnh_, "camera_info", 1);
123  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
124  sync_->connectInput(sub_input_, sub_camera_info_);
125  sync_->registerCallback(boost::bind(&DepthCalibration::calibrate, this, _1, _2));
126  }
127 
129  {
132  }
133 
135  const sensor_msgs::Image::ConstPtr& msg,
136  const sensor_msgs::CameraInfo::ConstPtr& camera_info)
137  {
138  boost::mutex::scoped_lock lock(mutex_);
139  cv_bridge::CvImagePtr cv_ptr;
140  try
141  {
143  }
144  catch (cv_bridge::Exception& e)
145  {
146  NODELET_ERROR("cv_bridge exception: %s", e.what());
147  return;
148  }
149  cv::Mat image = cv_ptr->image;
150  cv::Mat output_image = image.clone();
151  double cu = camera_info->P[2];
152  double cv = camera_info->P[6];
153  for(int v = 0; v < image.rows; v++) {
154  for(int u = 0; u < image.cols; u++) {
155  float z = image.at<float>(v, u);
156  if (std::isnan(z)) {
157  output_image.at<float>(v, u) = z;
158  }
159  else {
160  output_image.at<float>(v, u) = applyModel(z, u, v, cu, cv);
161  }
162  //NODELET_INFO("z: %f", z);
163  }
164  }
165  sensor_msgs::Image::Ptr ros_image = cv_bridge::CvImage(msg->header, "32FC1", output_image).toImageMsg();
166  pub_.publish(ros_image);
167  }
168 
169 }
NODELET_ERROR
#define NODELET_ERROR(...)
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
image_encodings.h
boost::shared_ptr< CvImage >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
jsk_pcl_ros::DepthCalibration
Definition: depth_calibration.h:86
jsk_pcl_ros::DepthCalibration::pub_
ros::Publisher pub_
Definition: depth_calibration.h:165
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
cv_bridge::Exception
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::DepthCalibration::use_abs_
bool use_abs_
Definition: depth_calibration.h:170
class_list_macros.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
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::DepthCalibration, nodelet::Nodelet)
jsk_pcl_ros::DepthCalibration::coefficients1_
std::vector< double > coefficients1_
Definition: depth_calibration.h:173
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
depth_calibration.h
nodelet::Nodelet
jsk_pcl_ros::DepthCalibration::printModel
virtual void printModel()
Definition: depth_calibration_nodelet.cpp:122
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
jsk_pcl_ros::DepthCalibration::set_calibration_parameter_srv_
ros::ServiceServer set_calibration_parameter_srv_
Definition: depth_calibration.h:166
cv_bridge.h
cv_bridge::CvImage
jsk_pcl_ros::DepthCalibration::unsubscribe
virtual void unsubscribe()
Definition: depth_calibration_nodelet.cpp:160
jsk_pcl_ros::DepthCalibration::onInit
virtual void onInit()
Definition: depth_calibration_nodelet.cpp:75
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