Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_ONE_DATA_STAT_H_
38 #define JSK_PCL_ROS_ONE_DATA_STAT_H_
40 #include <boost/accumulators/accumulators.hpp>
41 #include <boost/accumulators/statistics/stats.hpp>
42 #include <boost/accumulators/statistics/min.hpp>
43 #include <boost/accumulators/statistics/max.hpp>
44 #include <boost/accumulators/statistics/variance.hpp>
45 #include <boost/accumulators/statistics/count.hpp>
57 typedef boost::accumulators::accumulator_set<
62 boost::accumulators::tag::max,
71 virtual double max()
const {
return boost::accumulators::max(
acc_); }
103 double max(
const OneDataStat& d)
112 double count(
const OneDataStat& d)
121 double variance(
const OneDataStat& d)
130 double stddev(
const OneDataStat& d)
virtual double variance() const
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::count, boost::accumulators::tag::mean, boost::accumulators::tag::min, boost::accumulators::tag::max, boost::accumulators::tag::variance > > Accumulator
double variance(const OneDataStat &d)
wrapper function for variance method for boost::function
double min(const OneDataStat &d)
wrapper function for min method for boost::function
virtual double max() const
virtual double count() const
virtual double min() const
virtual double mean() const
double stddev(const OneDataStat &d)
wrapper function for stddev method for boost::function
class to store sensor value and compute mean, error and stddev and so on.
double count(const OneDataStat &d)
wrapper function for count method for boost::function
boost::shared_ptr< OneDataStat > Ptr
virtual double stddev() const
double max(const OneDataStat &d)
wrapper function for max method for boost::function
virtual void addData(float r)
double mean(const OneDataStat &d)
wrapper function for mean method for boost::function
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45