41 #define BOOST_PARAMETER_MAX_ARITY 7 45 #include <sensor_msgs/LaserScan.h> 46 #include <sensor_msgs/Image.h> 49 #include <jsk_recognition_msgs/PlotData.h> 63 typedef boost::accumulators::accumulator_set<
67 MinMaxAccumulator acc;
68 for (
size_t i = 0; i < stats.size(); i++) {
69 acc(accessor(*stats[i]));
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;
86 std::vector<OneDataStat::Ptr>
g_data;
119 if (g_data.size() == 0) {
121 for (
size_t i = 0; i < msg->ranges.size(); i++) {
125 if (g_data.size() != msg->ranges.size()) {
126 ROS_ERROR(
"Size of g_data and ~input/ranges are not same");
130 for (
size_t i = 0; i < msg->ranges.size(); i++) {
131 g_data[i]->addData(msg->ranges[i]);
135 if (g_data[0]->
count() > 2) {
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);
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) {
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);
161 pub_variance_plot.
publish(plot_data);
162 pub_stddev_plot.
publish(plot_stddev_data);
166 int main(
int argc,
char** argv)
168 ros::init(argc, argv,
"range_sensor_error_visualization");
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);
double min(const OneDataStat &d)
wrapper function for min method for boost::function
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
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.
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
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