range_sensor_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/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 
41 #define BOOST_PARAMETER_MAX_ARITY 7
42 
43 #include <ros/ros.h>
44 
45 #include <sensor_msgs/LaserScan.h>
46 #include <sensor_msgs/Image.h>
47 #include <cv_bridge/cv_bridge.h>
49 #include <jsk_recognition_msgs/PlotData.h>
50 #include "one_data_stat.h"
51 
52 using namespace jsk_pcl_ros;
53 
58 void generateImage(const std::vector<OneDataStat::Ptr>& stats,
59  cv::Mat& image,
60  boost::function<double(OneDataStat&)> accessor)
61 {
62  // Scan values in order to compute min and max
63  typedef boost::accumulators::accumulator_set<
64  double,
66  boost::accumulators::tag::max> > MinMaxAccumulator;
67  MinMaxAccumulator acc;
68  for (size_t i = 0; i < stats.size(); i++) {
69  acc(accessor(*stats[i]));
70  }
71 
72  double min = boost::accumulators::min(acc);
73  double max = boost::accumulators::max(acc);
74 
75  for (size_t i = 0; i < stats.size(); i++) {
76  double v = accessor(*stats[i]);
77  double relative_value = (v - min) / (max - min);
78  image.at<float>(0, i) = relative_value;
79  }
80 }
81 
86 std::vector<OneDataStat::Ptr> g_data;
87 
93 
99 
105 void publishImage(const cv::Mat& image, ros::Publisher& pub)
106 {
107  std_msgs::Header header;
108  header.stamp = ros::Time::now();
110  header, sensor_msgs::image_encodings::TYPE_32FC1, image).toImageMsg());
111 }
112 
117 void callback(const sensor_msgs::LaserScan::ConstPtr& msg)
118 {
119  if (g_data.size() == 0) {
120  // first time, g_data is not initialized
121  for (size_t i = 0; i < msg->ranges.size(); i++) {
122  g_data.push_back(OneDataStat::Ptr(new OneDataStat()));
123  }
124  }
125  if (g_data.size() != msg->ranges.size()) {
126  ROS_ERROR("Size of g_data and ~input/ranges are not same");
127  return;
128  }
129 
130  for (size_t i = 0; i < msg->ranges.size(); i++) {
131  g_data[i]->addData(msg->ranges[i]);
132  }
133 
134  // Visualize current error and so on
135  if (g_data[0]->count() > 2) {
136  // compute only if it receives two more images.
137  // because no stats can be computed with one message.
138  cv::Mat mean_image(1, msg->ranges.size(), CV_32FC1);
139  cv::Mat variance_image(1, msg->ranges.size(), CV_32FC1);
140  cv::Mat stddev_image(1, msg->ranges.size(), CV_32FC1);
141  generateImage(g_data, mean_image, &mean);
142  generateImage(g_data, variance_image, &variance);
143  generateImage(g_data, stddev_image, &stddev);
144  publishImage(mean_image, pub_mean);
145  publishImage(variance_image, pub_variance);
146  publishImage(stddev_image, pub_stddev);
147 
148  jsk_recognition_msgs::PlotData plot_data;
149  jsk_recognition_msgs::PlotData plot_stddev_data;
150  for (size_t i = 0; i < g_data.size(); i++) {
151  double x = g_data[i]->mean();
152  double y = g_data[i]->variance();
153  double stddev = g_data[i]->stddev();
154  if (x > 1.0 && x < 40 && stddev < 0.100) { // 10cm
155  plot_data.xs.push_back(x);
156  plot_data.ys.push_back(y);
157  plot_stddev_data.xs.push_back(x);
158  plot_stddev_data.ys.push_back(stddev);
159  }
160  }
161  pub_variance_plot.publish(plot_data);
162  pub_stddev_plot.publish(plot_stddev_data);
163  }
164 }
165 
166 int main(int argc, char** argv)
167 {
168  ros::init(argc, argv, "range_sensor_error_visualization");
169  ros::NodeHandle pnh("~");
170 
171  // Setup publishers before subscribe topic
172  pub_mean = pnh.advertise<sensor_msgs::Image>("output/mean", 1);
173  pub_variance = pnh.advertise<sensor_msgs::Image>("output/variance", 1);
174  pub_stddev = pnh.advertise<sensor_msgs::Image>("output/stddev", 1);
175  pub_variance_plot = pnh.advertise<jsk_recognition_msgs::PlotData>("output/variance_plot", 1);
176  pub_stddev_plot = pnh.advertise<jsk_recognition_msgs::PlotData>("output/stddev_plot", 1);
177  ros::Subscriber sub = pnh.subscribe("input", 1, &callback);
178  ros::spin();
179 
180 }
181 
double min(const OneDataStat &d)
wrapper function for min method for boost::function
Definition: one_data_stat.h:94
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double max(const OneDataStat &d)
wrapper function for max method for boost::function
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double mean(const OneDataStat &d)
wrapper function for mean method for boost::function
Definition: one_data_stat.h:85
ros::Publisher pub_mean
publisher for mean, variance and standard deviation images
class to store sensor value and compute mean, error and stddev and so on.
Definition: one_data_stat.h:53
ROSCPP_DECL void spin(Spinner &spinner)
void publishImage(const cv::Mat &image, ros::Publisher &pub)
publish a float image.
std::vector< OneDataStat::Ptr > g_data
global variable to store stat information.
double variance(const OneDataStat &d)
wrapper function for variance method for boost::function
double stddev(const OneDataStat &d)
wrapper function for stddev method for boost::function
const std::string TYPE_32FC1
void generateImage(const std::vector< OneDataStat::Ptr > &stats, cv::Mat &image, boost::function< double(OneDataStat &)> accessor)
generate a float image according to accessor.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_variance
ros::Publisher pub_stddev
ros::Publisher pub_stddev_plot
GLfloat v[8][3]
static Time now()
double count(const OneDataStat &d)
wrapper function for count method for boost::function
ros::Publisher pub_variance_plot
publisher for variance and standard deviation values for plotting
void callback(const sensor_msgs::LaserScan::ConstPtr &msg)
callback function
#define ROS_ERROR(...)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47