37 #include <jsk_topic_tools/rosparam_utils.h>
45 DiagnosticNodelet::onInit();
46 if (pnh_->hasParam(
"coefficients2")) {
47 jsk_topic_tools::readVectorParameter(
53 if (pnh_->hasParam(
"coefficients1")) {
54 jsk_topic_tools::readVectorParameter(
61 if (pnh_->hasParam(
"coefficients0")) {
62 jsk_topic_tools::readVectorParameter(
68 pnh_->param(
"use_abs",
use_abs_,
false);
72 "set_calibration_parameter",
75 pub_ = advertise<sensor_msgs::Image>(*pnh_,
"output", 1);
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",
107 jsk_recognition_msgs::SetDepthCalibrationParameter::Request&
req,
108 jsk_recognition_msgs::SetDepthCalibrationParameter::Response&
res)
123 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
135 const sensor_msgs::Image::ConstPtr&
msg,
136 const sensor_msgs::CameraInfo::ConstPtr& camera_info)
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);
157 output_image.at<
float>(
v, u) =
z;