32 #ifndef MECHANISM_CONTROL_CONTROL_SPEC_H 33 #define MECHANISM_CONTROL_CONTROL_SPEC_H 35 #pragma GCC diagnostic ignored "-Wextra" 41 #include <boost/circular_buffer.hpp> 42 #include <boost/thread/mutex.hpp> 43 #include <boost/accumulators/accumulators.hpp> 44 #include <boost/accumulators/statistics/stats.hpp> 45 #include <boost/accumulators/statistics/max.hpp> 46 #include <boost/accumulators/statistics/mean.hpp> 47 #include <boost/accumulators/statistics/variance.hpp> 49 typedef boost::accumulators::accumulator_set<
50 double, boost::accumulators::stats<boost::accumulators::tag::max,
51 boost::accumulators::tag::mean,
59 boost::circular_buffer<double>
max1;
60 Statistics() : num_control_loop_overruns(0), max(0), max1(60) {}
70 : name(spec.name), c(spec.c), stats(spec.stats) {}
ros::Time time_last_control_loop_overrun
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::max, boost::accumulators::tag::mean, boost::accumulators::tag::variance > > TimeStatistics
boost::shared_ptr< pr2_controller_interface::Controller > c
ControllerSpec(const ControllerSpec &spec)
boost::circular_buffer< double > max1
boost::shared_ptr< Statistics > stats
unsigned int num_control_loop_overruns