range_sensor_error_visualization.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00041 #define BOOST_PARAMETER_MAX_ARITY 7
00042 
00043 #include <ros/ros.h>
00044 
00045 #include <sensor_msgs/LaserScan.h>
00046 #include <sensor_msgs/Image.h>
00047 #include <cv_bridge/cv_bridge.h>
00048 #include <sensor_msgs/image_encodings.h>
00049 #include <jsk_recognition_msgs/PlotData.h>
00050 #include "one_data_stat.h"
00051 
00052 using namespace jsk_pcl_ros;
00053 
00058 void generateImage(const std::vector<OneDataStat::Ptr>& stats,
00059                    cv::Mat& image,
00060                    boost::function<double(OneDataStat&)> accessor)
00061 {
00062   // Scan values in order to compute min and max
00063   typedef boost::accumulators::accumulator_set<
00064     double,
00065     boost::accumulators::stats<boost::accumulators::tag::min,
00066                                boost::accumulators::tag::max> > MinMaxAccumulator;
00067   MinMaxAccumulator acc;
00068   for (size_t i = 0; i < stats.size(); i++) {
00069     acc(accessor(*stats[i]));
00070   }
00071   
00072   double min = boost::accumulators::min(acc);
00073   double max = boost::accumulators::max(acc);
00074 
00075   for (size_t i = 0; i < stats.size(); i++) {
00076     double v = accessor(*stats[i]);
00077     double relative_value = (v - min) / (max - min);
00078     image.at<float>(0, i) = relative_value;
00079   }
00080 }
00081 
00086 std::vector<OneDataStat::Ptr> g_data;
00087 
00092 ros::Publisher pub_mean, pub_variance, pub_stddev;
00093 
00098 ros::Publisher pub_variance_plot, pub_stddev_plot;
00099 
00105 void publishImage(const cv::Mat& image, ros::Publisher& pub)
00106 {
00107   std_msgs::Header header;
00108   header.stamp = ros::Time::now();
00109   pub.publish(cv_bridge::CvImage(
00110                 header, sensor_msgs::image_encodings::TYPE_32FC1, image).toImageMsg());
00111 }
00112 
00117 void callback(const sensor_msgs::LaserScan::ConstPtr& msg)
00118 {
00119   if (g_data.size() == 0) {
00120     // first time, g_data is not initialized
00121     for (size_t i = 0; i < msg->ranges.size(); i++) {
00122       g_data.push_back(OneDataStat::Ptr(new OneDataStat()));
00123     }
00124   }
00125   if (g_data.size() != msg->ranges.size()) {
00126     ROS_ERROR("Size of g_data and ~input/ranges are not same");
00127     return;
00128   }
00129 
00130   for (size_t i = 0; i < msg->ranges.size(); i++) {
00131     g_data[i]->addData(msg->ranges[i]);
00132   }
00133 
00134   // Visualize current error and so on
00135   if (g_data[0]->count() > 2) {
00136     // compute only if it receives two more images.
00137     // because no stats can be computed with one message.
00138     cv::Mat mean_image(1, msg->ranges.size(), CV_32FC1);
00139     cv::Mat variance_image(1, msg->ranges.size(), CV_32FC1);
00140     cv::Mat stddev_image(1, msg->ranges.size(), CV_32FC1);
00141     generateImage(g_data, mean_image, &mean);
00142     generateImage(g_data, variance_image, &variance);
00143     generateImage(g_data, stddev_image, &stddev);
00144     publishImage(mean_image, pub_mean);
00145     publishImage(variance_image, pub_variance);
00146     publishImage(stddev_image, pub_stddev);
00147 
00148     jsk_recognition_msgs::PlotData plot_data;
00149     jsk_recognition_msgs::PlotData plot_stddev_data;
00150     for (size_t i = 0; i < g_data.size(); i++) {
00151       double x = g_data[i]->mean();
00152       double y = g_data[i]->variance();
00153       double stddev = g_data[i]->stddev();
00154       if (x > 1.0 && x < 40 && stddev < 0.100) {            // 10cm
00155         plot_data.xs.push_back(x);
00156         plot_data.ys.push_back(y);
00157         plot_stddev_data.xs.push_back(x);
00158         plot_stddev_data.ys.push_back(stddev);
00159       }
00160     }
00161     pub_variance_plot.publish(plot_data);
00162     pub_stddev_plot.publish(plot_stddev_data);
00163   }
00164 }
00165 
00166 int main(int argc, char** argv)
00167 {
00168   ros::init(argc, argv, "range_sensor_error_visualization");
00169   ros::NodeHandle pnh("~");
00170 
00171   // Setup publishers before subscribe topic
00172   pub_mean = pnh.advertise<sensor_msgs::Image>("output/mean", 1);
00173   pub_variance = pnh.advertise<sensor_msgs::Image>("output/variance", 1);
00174   pub_stddev = pnh.advertise<sensor_msgs::Image>("output/stddev", 1);
00175   pub_variance_plot = pnh.advertise<jsk_recognition_msgs::PlotData>("output/variance_plot", 1);
00176   pub_stddev_plot = pnh.advertise<jsk_recognition_msgs::PlotData>("output/stddev_plot", 1);
00177   ros::Subscriber sub = pnh.subscribe("input", 1, &callback);
00178   ros::spin();
00179 
00180 }
00181 


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48