depth_camera_error_visualization.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
38 #include <ros/ros.h>
40 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <sensor_msgs/CameraInfo.h>
43 
45 
49 #include <cv_bridge/cv_bridge.h>
51 #include <jsk_recognition_msgs/PlotData.h>
52 #include "one_data_stat.h"
53 
54 using namespace jsk_pcl_ros;
55 
66  sensor_msgs::CameraInfo,
67  sensor_msgs::Image,
68  sensor_msgs::PointCloud2 > SyncPolicy;
69 
75 
81 
87 
92 sensor_msgs::PointCloud2::ConstPtr ground_truth;
93 
98 std::vector<OneDataStat::Ptr> stats;
99 
100 void groundTruthCallback(const sensor_msgs::PointCloud2::ConstPtr& msg)
101 {
102  boost::mutex::scoped_lock lock(mutex);
103  ground_truth = msg;
104 }
105 
111  const std::vector<OneDataStat::Ptr>& stats,
112  cv::Mat& image,
113  boost::function<double(OneDataStat&)> accessor)
114 {
115  for (size_t i = 0; i < image.rows; i++) {
116  for (size_t j = 0; j < image.cols; j++) {
117  size_t index = i * image.cols + j;
118  if (stats[index]->count() > 2) {
119  image.at<float>(i, j) = accessor(*stats[index]);
120  }
121  }
122  }
123 }
124 
125 void publishImage(const cv::Mat& image, ros::Publisher& pub)
126 {
127  std_msgs::Header header;
128  header.stamp = ros::Time::now();
130 }
131 
132 void publishPlotData(const std::vector<OneDataStat::Ptr>& stats,
134  boost::function<double(OneDataStat&)> accessor)
135 {
136  jsk_recognition_msgs::PlotData msg;
137  for (size_t i = 0; i < stats.size(); i++) {
138  if (i % 8 == 0) {
139  if (stats[i]->count() > 2) {
140  msg.xs.push_back(stats[i]->mean());
141  msg.ys.push_back(accessor(*stats[i]));
142  }
143  }
144  }
145  pub.publish(msg);
146 }
147 
149  const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
150  const sensor_msgs::Image::ConstPtr& left_image_msg,
151  const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg)
152 {
153  boost::mutex::scoped_lock lock(mutex);
154  // if (!ground_truth) {
155  // ROS_ERROR("no ground truth pointcloud");
156  // return;
157  // }
158  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
159  pcl::fromROSMsg(*point_cloud_msg, *cloud);
160 
161  // stats looks not initialized yet
162  if (stats.size() == 0) {
163  for (size_t i = 0; i < cloud->points.size(); i++) {
164  stats.push_back(OneDataStat::Ptr(new OneDataStat));
165  }
166  }
167 
168 
169  // Initialize accumurator
170  // 1 loop for all the points
171  // 2 check the point can have good ground_truth by 3-D -> 2-D projection
172  // based on camera internal parameter
173  // 3 compute error from ground truth
174 
175  // at this time, we do not implement step 2
176  for (size_t i = 0; i < cloud->points.size(); i++) {
177  pcl::PointXYZ p = cloud->points[i];
178  // We expect organized pointcloud in input/point_cloud message.
179  // So we need to check nan.
180  if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
181  continue;
182  }
183  stats[i]->addData(p.z);
184  }
185 
186  // visualization as image
187  cv::Mat mean_image = cv::Mat::zeros(cloud->height, cloud->width, CV_32FC1);
188  cv::Mat variance_image = cv::Mat::zeros(cloud->height, cloud->width, CV_32FC1);
189  cv::Mat stddev_image = cv::Mat::zeros(cloud->height, cloud->width, CV_32FC1);
190  generateImage(stats, mean_image, &mean);
191  generateImage(stats, variance_image, &variance);
192  generateImage(stats, stddev_image, &stddev);
193  publishImage(mean_image, pub_mean_image);
194  publishImage(variance_image, pub_variance_image);
195  publishImage(stddev_image, pub_stddev_image);
198 }
199 
200 int main(int argc, char** argv)
201 {
202  ros::init(argc, argv, "depth_camera_error_visualization");
203  ros::NodeHandle nh("~");
204  // Setup publishers
205  pub_error_image = nh.advertise<sensor_msgs::Image>("output/error_image", 1);
206  pub_variance_image = nh.advertise<sensor_msgs::Image>("output/variance_image", 1);
207  pub_stddev_image = nh.advertise<sensor_msgs::Image>("output/stddev_image", 1);
208  pub_mean_image = nh.advertise<sensor_msgs::Image>("output/mean_image", 1);
209  pub_error_plot = nh.advertise<jsk_recognition_msgs::PlotData>("output/error_plot", 1);
210  pub_variance_plot = nh.advertise<jsk_recognition_msgs::PlotData>("output/variance_plot", 1);
211  pub_stddev_plot = nh.advertise<jsk_recognition_msgs::PlotData>("output/stddev_plot", 1);
212  //ros::Subscriber sub_ground_truth = nh.subscribe("input/ground_truth", 1, &groundTruthCallback);
216  sub_camera_info.subscribe(nh, "input/camera_info", 1);
217  sub_left_image.subscribe(nh, "input/left_image", 1);
218  sub_point_cloud.subscribe(nh, "input/point_cloud", 1);
220  sync.connectInput(sub_camera_info, sub_left_image, sub_point_cloud);
221  sync.registerCallback(&dataCallback);
222  ros::spin();
223  return 0;
224 }
pub_variance_plot
ros::Publisher pub_variance_plot
Definition: depth_camera_error_visualization.cpp:80
one_data_stat.h
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
ros::Publisher
publishPlotData
void publishPlotData(const std::vector< OneDataStat::Ptr > &stats, ros::Publisher &pub, boost::function< double(OneDataStat &)> accessor)
Definition: depth_camera_error_visualization.cpp:132
image_encodings.h
stats
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
Definition: depth_camera_error_visualization.cpp:98
pub_error_plot
ros::Publisher pub_error_plot
publishers for plot data
Definition: depth_camera_error_visualization.cpp:80
message_filters::Synchronizer
boost::shared_ptr
i
int i
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
pinhole_camera_model.h
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
p
p
ros.h
jsk_pcl_ros::variance
double variance(const OneDataStat &d)
wrapper function for variance method for boost::function
Definition: one_data_stat.h:153
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
time_synchronizer.h
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ground_truth
sensor_msgs::PointCloud2::ConstPtr ground_truth
pointcloud of ground truth
Definition: depth_camera_error_visualization.cpp:92
cloud
cloud
message_filters::Subscriber< sensor_msgs::CameraInfo >
pcl_conversion_util.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::stddev
double stddev(const OneDataStat &d)
wrapper function for stddev method for boost::function
Definition: one_data_stat.h:162
subscriber.h
jsk_pcl_ros::OneDataStat
class to store sensor value and compute mean, error and stddev and so on.
Definition: one_data_stat.h:85
argv
ROS_INFO ROS_ERROR int pointer * argv
pub_stddev_plot
ros::Publisher pub_stddev_plot
Definition: depth_camera_error_visualization.cpp:80
jsk_pcl_ros::count
double count(const OneDataStat &d)
wrapper function for count method for boost::function
Definition: one_data_stat.h:144
sync
double sync(double x)
pub_error_image
ros::Publisher pub_error_image
publishers for image visualization.
Definition: depth_camera_error_visualization.cpp:74
message_filters::Subscriber::subscribe
void subscribe()
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
cv_bridge.h
cv_bridge::CvImage
groundTruthCallback
void groundTruthCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: depth_camera_error_visualization.cpp:100
index
unsigned int index
dataCallback
void dataCallback(const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg, const sensor_msgs::Image::ConstPtr &left_image_msg, const sensor_msgs::PointCloud2::ConstPtr &point_cloud_msg)
Definition: depth_camera_error_visualization.cpp:148
synchronizer.h
main
int main(int argc, char **argv)
Definition: depth_camera_error_visualization.cpp:200
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
ros::spin
ROSCPP_DECL void spin()
SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::PointCloud2 > SyncPolicy
Definition: depth_camera_error_visualization.cpp:68
message_filters::sync_policies::ExactTime
publishImage
void publishImage(const cv::Mat &image, ros::Publisher &pub)
Definition: depth_camera_error_visualization.cpp:125
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
generateImage
void generateImage(const std::vector< OneDataStat::Ptr > &stats, cv::Mat &image, boost::function< double(OneDataStat &)> accessor)
generate a image generated by accessor
Definition: depth_camera_error_visualization.cpp:110
pub_mean_image
ros::Publisher pub_mean_image
Definition: depth_camera_error_visualization.cpp:74
pub_stddev_image
ros::Publisher pub_stddev_image
Definition: depth_camera_error_visualization.cpp:74
pub_variance_image
ros::Publisher pub_variance_image
Definition: depth_camera_error_visualization.cpp:74
ros::NodeHandle
ros::Time::now
static Time now()
jsk_pcl_ros::mean
double mean(const OneDataStat &d)
wrapper function for mean method for boost::function
Definition: one_data_stat.h:117


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44