Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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
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
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
00135 if (g_data[0]->count() > 2) {
00136
00137
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) {
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
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