45 #include <boost/accumulators/accumulators.hpp>
46 #include <boost/accumulators/statistics/stats.hpp>
47 #include <boost/accumulators/statistics/max.hpp>
48 #include <boost/accumulators/statistics/mean.hpp>
51 #include <diagnostic_msgs/DiagnosticArray.h>
58 using boost::accumulators::accumulator_set;
59 using boost::accumulators::stats;
60 using boost::accumulators::extract_result;
61 using boost::accumulators::tag::max;
62 using boost::accumulators::tag::mean;
65 using std::accumulate;
79 void Usage(
const string &msg =
"" )
81 fprintf(stderr,
"Usage: %s [options]\n",
g_options.program_);
82 fprintf(stderr,
" Available options\n");
83 fprintf(stderr,
" -i, --ip IP address for Controller\n");
84 fprintf(stderr,
" -l, --loopback Use loopback interface for Controller (i.e. simulation mode)\n");
85 fprintf(stderr,
" -p, --period RT loop period in msec\n");
86 fprintf(stderr,
" -v, --viewer Viewing robot through Rviz\n");
87 fprintf(stderr,
" -r, --robot Robot name\n");
88 fprintf(stderr,
" -h, --help Print this message and exit\n");
91 fprintf(stderr,
"Error: %s\n",
msg.c_str());
109 accumulator_set<double, stats<max, mean> >
read_acc;
111 accumulator_set<double, stats<max, mean> >
loop_acc;
132 accumulator_set<double, stats<max, mean> > zero;
133 vector<diagnostic_msgs::DiagnosticStatus> statuses;
136 static double max_read = 0, max_write = 0, max_loop = 0, max_jitter = 0;
137 double avg_read, avg_write, avg_loop, avg_jitter;
139 avg_read = extract_result<mean>(
g_stats.read_acc);
140 avg_write = extract_result<mean>(
g_stats.write_acc);
141 avg_loop = extract_result<mean>(
g_stats.loop_acc);
142 max_read = std::max(max_read, extract_result<max>(
g_stats.read_acc));
143 max_write = std::max(max_write, extract_result<max>(
g_stats.write_acc));
144 max_loop = std::max(max_loop, extract_result<max>(
g_stats.loop_acc));
150 avg_jitter = extract_result<mean>(
g_stats.jitter_acc);
151 max_jitter = std::max(max_jitter, extract_result<max>(
g_stats.jitter_acc));
154 status.
addf(
"Max READ roundtrip (us)",
"%.2f", max_read *
SEC_2_USEC);
155 status.
addf(
"Avg READ roundtrip (us)",
"%.2f", avg_read *
SEC_2_USEC);
156 status.
addf(
"Max WRITE roundtrip (us)",
"%.2f", max_write *
SEC_2_USEC);
157 status.
addf(
"Avg WRITE roundtrip (us)",
"%.2f", avg_write *
SEC_2_USEC);
158 status.
addf(
"Max Total Loop roundtrip (us)",
"%.2f", max_loop *
SEC_2_USEC);
159 status.
addf(
"Avg Total Loop roundtrip (us)",
"%.2f", avg_loop *
SEC_2_USEC);
160 status.
addf(
"Max Loop Jitter (us)",
"%.2f", max_jitter *
SEC_2_USEC);
161 status.
addf(
"Avg Loop Jitter (us)",
"%.2f", avg_jitter *
SEC_2_USEC);
162 status.
addf(
"Control Loop Overruns",
"%d",
g_stats.overruns);
163 status.
addf(
"Recent Control Loop Overruns",
"%d",
g_stats.recent_overruns);
164 status.
addf(
"Last Control Loop Overrun Cause",
"READ: %.2fus, WRITE: %.2fus",
167 status.
addf(
"Realtime Loop Frequency",
"%.4f",
g_stats.rt_loop_frequency);
169 status.name =
"Realtime Control Loop";
172 if (
g_stats.last_severe_overrun < 30)
176 status.message =
"Realtime loop used too much time in the last 30 seconds.";
181 status.message =
"OK";
187 if (
g_stats.rt_loop_not_making_timing)
188 status.
mergeSummaryf(status.ERROR,
"realtime loop only ran at %.4f Hz",
g_stats.halt_rt_loop_frequency);
190 statuses.push_back(status);
191 publisher.
msg_.status = statuses;
197 static inline double now()
200 clock_gettime( CLOCK_MONOTONIC, &n );
201 return static_cast<double>(n.tv_nsec) /
SEC_2_NSEC + n.tv_sec;
206 tick.tv_nsec += nsec;
207 if ( tick.tv_nsec > 0 )
217 while (tick.tv_nsec < 0)
261 ROS_ERROR(
"Failed to activate KHI robot" );
265 clock_gettime( CLOCK_REALTIME, tick );
269 clock_nanosleep( CLOCK_REALTIME, TIMER_ABSTIME, tick, NULL );
280 ROS_WARN(
"received signal %d", sig );
298 const double rt_loop_monitor_period = 0.2;
299 const double period_in_secs = 1e+9 *
g_options.period_;
300 const double given_frequency = 1 / period_in_secs;
301 double min_acceptable_rt_loop_frequency = 0.75 * given_frequency;
302 if ( nh.
getParam(
"min_acceptable_rt_loop_frequency", min_acceptable_rt_loop_frequency ) )
304 ROS_WARN(
"min_acceptable_rt_loop_frequency changed to %f", min_acceptable_rt_loop_frequency);
306 unsigned rt_cycle_count = 0;
310 struct sched_param thread_param;
311 int policy = SCHED_FIFO;
312 thread_param.sched_priority = sched_get_priority_max( policy );
313 if ( pthread_setschedparam( pthread_self(), policy, &thread_param ) == 0 )
315 ROS_INFO(
"KHI robot control started. [REALTIME]" );
319 ROS_INFO(
"KHI robot control started. [NOT REALTIME]" );
326 struct timespec tick;
329 double period_diff = 0;
354 double this_loop_start =
now();
360 ros::Time this_moment( tick.tv_sec, tick.tv_nsec );
361 robot.
read( this_moment, durp );
363 double after_read =
now();
365 cm.
update( this_moment, durp );
380 ros::Time activate_moment( tick.tv_sec, tick.tv_nsec );
381 robot.
read( activate_moment, durp );
382 cm.
update( activate_moment, durp,
true );
392 robot.
write( this_moment, durp );
404 g_stats.write_acc( end - after_read );
417 double rt_loop_frequency =
static_cast<double>(rt_cycle_count) / rt_loop_monitor_period;
421 double avg_rt_loop_frequency = rt_loop_history.
average();
422 if ( avg_rt_loop_frequency < min_acceptable_rt_loop_frequency )
424 if ( !
g_stats.rt_loop_not_making_timing )
427 g_stats.halt_rt_loop_frequency = avg_rt_loop_frequency;
429 g_stats.rt_loop_not_making_timing =
true;
431 g_stats.rt_loop_frequency = avg_rt_loop_frequency;
440 struct timespec before;
441 clock_gettime( CLOCK_REALTIME, &before );
442 if ( ( before.tv_sec +
static_cast<double>(before.tv_nsec) /
SEC_2_NSEC) >
443 ( tick.tv_sec +
static_cast<double>(tick.tv_nsec) /
SEC_2_NSEC ) )
446 g_stats.overrun_loop_sec = ( before.tv_sec +
static_cast<double>(before.tv_nsec) /
SEC_2_NSEC ) -
447 ( tick.tv_sec +
static_cast<double>(tick.tv_nsec) /
SEC_2_NSEC );
450 tick.tv_sec = before.tv_sec;
458 g_stats.last_severe_overrun = 1000;
461 if (
g_stats.recent_overruns > 10 )
463 g_stats.last_severe_overrun = 0;
470 g_stats.overrun_write = end - after_read;
474 clock_nanosleep( CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL );
477 struct timespec after;
478 clock_gettime( CLOCK_REALTIME, &after );
479 double jitter = ( after.tv_sec - tick.tv_sec +
static_cast<double>(after.tv_nsec - tick.tv_nsec) /
SEC_2_NSEC );
486 ROS_INFO(
"KHI robot control ended." );
494 int main(
int argc,
char *argv[])
497 ros::init( argc, argv,
"KhiRobotControl" );
507 static struct option long_options[] =
509 {
"help", no_argument, 0,
'h'},
510 {
"interface", required_argument, 0,
'i'},
511 {
"loopback", no_argument, 0,
'l'},
512 {
"viewer", no_argument, 0,
'v'},
513 {
"period", required_argument, 0,
'p'},
514 {
"robot", required_argument, 0,
'r'},
516 int option_index = 0;
517 int c = getopt_long( argc, argv,
"hi:lvp:r:", long_options, &option_index );
540 g_options.period_ = fabs(atof(optarg))*1e+6;
552 Usage(
"Extra arguments" );
559 ROS_FATAL(
"Unable to create control thread: rv = %d", rv );
560 exit( EXIT_FAILURE );