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
00036
00037 #include <cstdio>
00038 #include <cstdarg>
00039 #include <getopt.h>
00040 #include <execinfo.h>
00041 #include <csignal>
00042 #include <sys/mman.h>
00043 #include <sys/types.h>
00044 #include <sys/stat.h>
00045 #include <unistd.h>
00046 #include <fcntl.h>
00047 #include <pthread.h>
00048 #include <numeric>
00049
00050 #include "ros_ethercat_model/ros_ethercat.hpp"
00051 #include <std_msgs/Float64.h>
00052 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00053
00054 using namespace boost::accumulators;
00055 using std::string;
00056 using std::vector;
00057 using std::accumulate;
00058 using realtime_tools::RealtimePublisher;
00059
00060 static struct
00061 {
00062 char *program_;
00063 char *interface_;
00064 char *rosparam_;
00065 bool allow_unprogrammed_;
00066 bool stats_;
00067 double period;
00068 } g_options;
00069
00070 string g_robot_desc;
00071
00072 void Usage(const string &msg = "")
00073 {
00074 fprintf(stderr, "Usage: %s [options]\n", g_options.program_);
00075 fprintf(stderr, " Available options\n");
00076 fprintf(stderr, " -i, --interface <interface> Connect to EtherCAT devices on this interface\n");
00077 fprintf(stderr, " -p, --period RT loop period in msec\n");
00078 fprintf(stderr, " -s, --stats Publish statistics on the RT loop jitter on \"ros_ros_ethercat_eml/realtime\" in seconds\n");
00079 fprintf(stderr, " -r, --rosparam <param> Load the robot description from this parameter name\n");
00080 fprintf(stderr, " -u, --allow_unprogrammed Allow control loop to run with unprogrammed devices\n");
00081 fprintf(stderr, " -h, --help Print this message and exit\n");
00082 if (msg != "")
00083 {
00084 fprintf(stderr, "Error: %s\n", msg.c_str());
00085 exit(-1);
00086 }
00087 else
00088 exit(0);
00089 }
00090
00091 static int g_quit = 0;
00092 static const int SEC_2_NSEC = 1e+9;
00093 static const int SEC_2_USEC = 1e6;
00094
00095 static struct
00096 {
00097 accumulator_set<double, stats<tag::max, tag::mean> > ec_acc;
00098 accumulator_set<double, stats<tag::max, tag::mean> > cm_acc;
00099 accumulator_set<double, stats<tag::max, tag::mean> > loop_acc;
00100 accumulator_set<double, stats<tag::max, tag::mean> > jitter_acc;
00101 int overruns;
00102 int recent_overruns;
00103 int last_overrun;
00104 int last_severe_overrun;
00105 double overrun_loop_sec;
00106 double overrun_ec;
00107 double overrun_cm;
00108
00109
00110 bool rt_loop_not_making_timing;
00111 double halt_rt_loop_frequency;
00112 double rt_loop_frequency;
00113 } g_stats;
00114
00115 static void publishDiagnostics(RealtimePublisher<diagnostic_msgs::DiagnosticArray> &publisher)
00116 {
00117 if (publisher.trylock())
00118 {
00119 accumulator_set<double, stats<tag::max, tag::mean> > zero;
00120 vector<diagnostic_msgs::DiagnosticStatus> statuses;
00121 diagnostic_updater::DiagnosticStatusWrapper status;
00122
00123 static double max_ec = 0, max_cm = 0, max_loop = 0, max_jitter = 0;
00124 double avg_ec, avg_cm, avg_loop, avg_jitter;
00125
00126 avg_ec = extract_result<tag::mean>(g_stats.ec_acc);
00127 avg_cm = extract_result<tag::mean>(g_stats.cm_acc);
00128 avg_loop = extract_result<tag::mean>(g_stats.loop_acc);
00129 max_ec = std::max(max_ec, extract_result<tag::max>(g_stats.ec_acc));
00130 max_cm = std::max(max_cm, extract_result<tag::max>(g_stats.cm_acc));
00131 max_loop = std::max(max_loop, extract_result<tag::max>(g_stats.loop_acc));
00132 g_stats.ec_acc = zero;
00133 g_stats.cm_acc = zero;
00134 g_stats.loop_acc = zero;
00135
00136
00137 avg_jitter = extract_result<tag::mean>(g_stats.jitter_acc);
00138 max_jitter = std::max(max_jitter, extract_result<tag::max>(g_stats.jitter_acc));
00139 g_stats.jitter_acc = zero;
00140
00141 static bool first = true;
00142 if (first)
00143 {
00144 first = false;
00145 status.add("Robot Description", g_robot_desc);
00146 }
00147
00148 status.addf("Max EtherCAT roundtrip (us)", "%.2f", max_ec * SEC_2_USEC);
00149 status.addf("Avg EtherCAT roundtrip (us)", "%.2f", avg_ec * SEC_2_USEC);
00150 status.addf("Max Controller Manager roundtrip (us)", "%.2f", max_cm * SEC_2_USEC);
00151 status.addf("Avg Controller Manager roundtrip (us)", "%.2f", avg_cm * SEC_2_USEC);
00152 status.addf("Max Total Loop roundtrip (us)", "%.2f", max_loop * SEC_2_USEC);
00153 status.addf("Avg Total Loop roundtrip (us)", "%.2f", avg_loop * SEC_2_USEC);
00154 status.addf("Max Loop Jitter (us)", "%.2f", max_jitter * SEC_2_USEC);
00155 status.addf("Avg Loop Jitter (us)", "%.2f", avg_jitter * SEC_2_USEC);
00156 status.addf("Control Loop Overruns", "%d", g_stats.overruns);
00157 status.addf("Recent Control Loop Overruns", "%d", g_stats.recent_overruns);
00158 status.addf("Last Control Loop Overrun Cause", "ec: %.2fus, cm: %.2fus",
00159 g_stats.overrun_ec*SEC_2_USEC, g_stats.overrun_cm * SEC_2_USEC);
00160 status.addf("Last Overrun Loop Time (us)", "%.2f", g_stats.overrun_loop_sec * SEC_2_USEC);
00161 status.addf("Realtime Loop Frequency", "%.4f", g_stats.rt_loop_frequency);
00162
00163 status.name = "Realtime Control Loop";
00164 if (g_stats.overruns > 0 && g_stats.last_overrun < 30)
00165 {
00166 if (g_stats.last_severe_overrun < 30)
00167 status.level = 1;
00168 else
00169 status.level = 0;
00170 status.message = "Realtime loop used too much time in the last 30 seconds.";
00171 }
00172 else
00173 {
00174 status.level = 0;
00175 status.message = "OK";
00176 }
00177 g_stats.recent_overruns = 0;
00178 ++g_stats.last_overrun;
00179 ++g_stats.last_severe_overrun;
00180
00181 if (g_stats.rt_loop_not_making_timing)
00182 status.mergeSummaryf(status.ERROR, "realtime loop only ran at %.4f Hz", g_stats.halt_rt_loop_frequency);
00183
00184 statuses.push_back(status);
00185 publisher.msg_.status = statuses;
00186 publisher.msg_.header.stamp = ros::Time::now();
00187 publisher.unlockAndPublish();
00188 }
00189 }
00190
00191 static inline double now()
00192 {
00193 struct timespec n;
00194 clock_gettime(CLOCK_MONOTONIC, &n);
00195 return double(n.tv_nsec) / SEC_2_NSEC + n.tv_sec;
00196 }
00197
00198 void *diagnosticLoop(void *args)
00199 {
00200 EthercatHardware * ec((EthercatHardware *) args);
00201 struct timespec tick;
00202 clock_gettime(CLOCK_MONOTONIC, &tick);
00203 while (!g_quit)
00204 {
00205 ec->collectDiagnostics();
00206 ++tick.tv_sec;
00207 clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &tick, NULL);
00208 }
00209 return NULL;
00210 }
00211
00212 static void timespecInc(struct timespec &tick, int nsec)
00213 {
00214 tick.tv_nsec += nsec;
00215 while (tick.tv_nsec >= SEC_2_NSEC)
00216 {
00217 tick.tv_nsec -= SEC_2_NSEC;
00218 ++tick.tv_sec;
00219 }
00220 }
00221
00222 class RTLoopHistory
00223 {
00224 public:
00225
00226 RTLoopHistory(unsigned length, double default_value) :
00227 index_(0),
00228 length_(length),
00229 history_(length, default_value)
00230 {
00231 }
00232
00233 void sample(double value)
00234 {
00235 index_ = (index_ + 1) % length_;
00236 history_[index_] = value;
00237 }
00238
00239 double average() const
00240 {
00241 return accumulate(history_.begin(), history_.end(), 0.0) / (double) length_;
00242 }
00243
00244 protected:
00245 unsigned index_;
00246 unsigned length_;
00247 vector<double> history_;
00248 };
00249
00250 static void* terminate_control(RealtimePublisher<diagnostic_msgs::DiagnosticArray> *publisher,
00251 RealtimePublisher<std_msgs::Float64> *rtpublisher,
00252 const char* message,
00253 const char* data = NULL)
00254 {
00255 ROS_FATAL(message, data);
00256 publisher->stop();
00257 delete rtpublisher;
00258 ros::shutdown();
00259 return (void*) - 1;
00260 }
00261
00262 void *controlLoop(void *)
00263 {
00264 double last_published, last_loop_start;
00265 int policy;
00266 TiXmlElement *root;
00267 TiXmlElement *root_element;
00268
00269 ros::NodeHandle node(name);
00270
00271 RealtimePublisher<diagnostic_msgs::DiagnosticArray> publisher(node, "/diagnostics", 2);
00272 RealtimePublisher<std_msgs::Float64> *rtpublisher = NULL;
00273
00274
00275
00276 double period_in_secs = 1e+9 * g_options.period;
00277 double given_frequency = 1 / period_in_secs;
00278 double min_acceptable_rt_loop_frequency = 0.75 * given_frequency;
00279 if (node.getParam("min_acceptable_rt_loop_frequency", min_acceptable_rt_loop_frequency))
00280 ROS_WARN("min_acceptable_rt_loop_frequency changed to %f", min_acceptable_rt_loop_frequency);
00281
00282 unsigned rt_cycle_count = 0;
00283 double last_rt_monitor_time;
00284
00285
00286 double rt_loop_monitor_period = 0.2;
00287
00288 RTLoopHistory rt_loop_history(3, 1000.0);
00289
00290 if (g_options.stats_)
00291 rtpublisher = new RealtimePublisher<std_msgs::Float64>(node, "realtime", 2);
00292
00293
00294 TiXmlDocument xml;
00295 struct stat st;
00296
00297 if (ros::param::get(g_options.rosparam_, g_robot_desc))
00298 xml.Parse(g_robot_desc.c_str());
00299 else
00300 return terminate_control(&publisher, rtpublisher,
00301 "Could not load the xml from parameter server: %s", g_options.rosparam_);
00302
00303 root_element = xml.RootElement();
00304 root = xml.FirstChildElement("robot");
00305 if (!root || !root_element)
00306 return terminate_control(&publisher, rtpublisher, "Failed to parse the xml from %s", g_options.rosparam_);
00307
00308
00309 ros::NodeHandle nh;
00310 RosEthercat seth(nh, g_options.interface_, g_options.allow_unprogrammed_, root);
00311
00312
00313 controller_manager::ControllerManager cm(&seth);
00314
00315
00316 publishDiagnostics(publisher);
00317
00318
00319 static pthread_t diagnosticThread;
00320 int rv = pthread_create(&diagnosticThread, NULL, diagnosticLoop, &seth.ec_);
00321 if (rv != 0)
00322 return terminate_control(&publisher, rtpublisher,
00323 "Unable to create control thread: rv = %s", boost::lexical_cast<string>(rv).c_str());
00324
00325
00326 struct sched_param thread_param;
00327 policy = SCHED_FIFO;
00328 thread_param.sched_priority = sched_get_priority_max(policy);
00329 pthread_setschedparam(pthread_self(), policy, &thread_param);
00330
00331 struct timespec tick;
00332 clock_gettime(CLOCK_REALTIME, &tick);
00333 ros::Duration durp(g_options.period / 1e+9);
00334
00335
00336 tick.tv_nsec = (tick.tv_nsec / g_options.period + 1) * g_options.period;
00337 clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL);
00338
00339 last_published = now();
00340 last_rt_monitor_time = now();
00341 last_loop_start = now();
00342 while (!g_quit)
00343 {
00344
00345 double this_loop_start = now();
00346 g_stats.loop_acc(this_loop_start - last_loop_start);
00347 last_loop_start = this_loop_start;
00348
00349 double start = now();
00350
00351 ros::Time this_moment(tick.tv_sec, tick.tv_nsec);
00352 seth.read();
00353 double after_ec = now();
00354 cm.update(this_moment, durp);
00355 seth.write();
00356 double end = now();
00357
00358 g_stats.ec_acc(after_ec - start);
00359 g_stats.cm_acc(end - after_ec);
00360
00361 if ((end - last_published) > 1.0)
00362 {
00363 publishDiagnostics(publisher);
00364 last_published = end;
00365 }
00366
00367
00368
00369
00370 ++rt_cycle_count;
00371 if ((start - last_rt_monitor_time) > rt_loop_monitor_period)
00372 {
00373
00374 double rt_loop_frequency = double(rt_cycle_count) / rt_loop_monitor_period;
00375
00376
00377 rt_loop_history.sample(rt_loop_frequency);
00378 double avg_rt_loop_frequency = rt_loop_history.average();
00379 if (avg_rt_loop_frequency < min_acceptable_rt_loop_frequency)
00380 {
00381 if (!g_stats.rt_loop_not_making_timing)
00382 {
00383
00384 g_stats.halt_rt_loop_frequency = avg_rt_loop_frequency;
00385 }
00386 g_stats.rt_loop_not_making_timing = true;
00387 }
00388 g_stats.rt_loop_frequency = avg_rt_loop_frequency;
00389 rt_cycle_count = 0;
00390 last_rt_monitor_time = start;
00391 }
00392
00393
00394 timespecInc(tick, g_options.period);
00395
00396 struct timespec before;
00397 clock_gettime(CLOCK_REALTIME, &before);
00398 if ((before.tv_sec + double(before.tv_nsec) / SEC_2_NSEC) > (tick.tv_sec + double(tick.tv_nsec) / SEC_2_NSEC))
00399 {
00400
00401 g_stats.overrun_loop_sec = (before.tv_sec + double(before.tv_nsec) / SEC_2_NSEC) -
00402 (tick.tv_sec + double(tick.tv_nsec) / SEC_2_NSEC);
00403
00404
00405 tick.tv_sec = before.tv_sec;
00406 tick.tv_nsec = (before.tv_nsec / g_options.period) * g_options.period;
00407 timespecInc(tick, g_options.period);
00408
00409
00410 if (g_stats.overruns == 0)
00411 {
00412 g_stats.last_overrun = 1000;
00413 g_stats.last_severe_overrun = 1000;
00414 }
00415
00416 if (g_stats.recent_overruns > 10)
00417 g_stats.last_severe_overrun = 0;
00418 g_stats.last_overrun = 0;
00419
00420 ++g_stats.overruns;
00421 ++g_stats.recent_overruns;
00422 g_stats.overrun_ec = after_ec - start;
00423 g_stats.overrun_cm = end - after_ec;
00424 }
00425
00426
00427 clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL);
00428
00429
00430 struct timespec after;
00431 clock_gettime(CLOCK_REALTIME, &after);
00432 double jitter = (after.tv_sec - tick.tv_sec + double(after.tv_nsec - tick.tv_nsec) / SEC_2_NSEC);
00433
00434 g_stats.jitter_acc(jitter);
00435
00436
00437 if (rtpublisher && rtpublisher->trylock())
00438 {
00439 rtpublisher->msg_.data = jitter;
00440 rtpublisher->unlockAndPublish();
00441 }
00442 }
00443
00444
00445 seth.shutdown();
00446 seth.ec_.update(false, true);
00447
00448 publisher.stop();
00449 delete rtpublisher;
00450 ros::shutdown();
00451 return NULL;
00452 }
00453
00454 void quitRequested(int sig)
00455 {
00456 g_quit = 1;
00457 }
00458
00459 static int lock_fd(int fd)
00460 {
00461 struct flock lock;
00462
00463 lock.l_type = F_WRLCK;
00464 lock.l_whence = SEEK_SET;
00465 lock.l_start = 0;
00466 lock.l_len = 0;
00467
00468 return fcntl(fd, F_SETLK, &lock);
00469 }
00470
00471
00472 static const char* PIDDIR = "/var/tmp/run/";
00473
00474 string generatePIDFilename(const char* interface)
00475 {
00476 string filename;
00477 filename = string(PIDDIR) + "EtherCAT_" + string(interface) + ".pid";
00478 return filename;
00479 }
00480
00481 static int setupPidFile(const char* interface)
00482 {
00483 pid_t pid;
00484 int fd;
00485 FILE *fp = NULL;
00486
00487 string filename = generatePIDFilename(interface);
00488
00489 umask(0);
00490 mkdir(PIDDIR, 0777);
00491 int PID_FLAGS = O_RDWR | O_CREAT | O_EXCL;
00492 int PID_MODE = S_IWUSR | S_IRUSR | S_IWGRP | S_IRGRP | S_IWOTH | S_IROTH;
00493 fd = open(filename.c_str(), PID_FLAGS, PID_MODE);
00494 if (fd == -1)
00495 {
00496 if (errno != EEXIST)
00497 {
00498 ROS_FATAL("Unable to create pid file '%s': %s", filename.c_str(), strerror(errno));
00499 return -1;
00500 }
00501
00502 if ((fd = open(filename.c_str(), O_RDWR)) < 0)
00503 {
00504 ROS_FATAL("Unable to open pid file '%s': %s", filename.c_str(), strerror(errno));
00505 return -1;
00506 }
00507
00508 if ((fp = fdopen(fd, "rw")) == NULL)
00509 {
00510 ROS_FATAL("Can't read from '%s': %s", filename.c_str(), strerror(errno));
00511 return -1;
00512 }
00513 pid = -1;
00514 if ((fscanf(fp, "%d", &pid) != 1) || (pid == getpid()) || (lock_fd(fileno(fp)) == 0))
00515 {
00516 int rc;
00517
00518 if ((rc = unlink(filename.c_str())) == -1)
00519 {
00520 ROS_FATAL("Can't remove stale pid file '%s': %s", filename.c_str(), strerror(errno));
00521 return -1;
00522 }
00523 }
00524 else
00525 {
00526 ROS_FATAL("Another instance of ros_ethercat is already running with pid: %d", pid);
00527 return -1;
00528 }
00529 }
00530
00531 unlink(filename.c_str());
00532 fd = open(filename.c_str(), PID_FLAGS, PID_MODE);
00533
00534 if (fd == -1)
00535 {
00536 ROS_FATAL("Unable to open pid file '%s': %s", filename.c_str(), strerror(errno));
00537 return -1;
00538 }
00539
00540 if (lock_fd(fd) == -1)
00541 {
00542 ROS_FATAL("Unable to lock pid file '%s': %s", filename.c_str(), strerror(errno));
00543 return -1;
00544 }
00545
00546 if ((fp = fdopen(fd, "w")) == NULL)
00547 {
00548 ROS_FATAL("fdopen failed: %s", strerror(errno));
00549 return -1;
00550 }
00551
00552 fprintf(fp, "%d\n", getpid());
00553
00554
00555 fflush(fp);
00556 fcntl(fd, F_SETFD, (long) 1);
00557
00558 return 0;
00559 }
00560
00561 static void cleanupPidFile(const char* interface)
00562 {
00563 string filename = generatePIDFilename(interface);
00564 unlink(filename.c_str());
00565 }
00566
00567 #define CLOCK_PRIO 0
00568 #define CONTROL_PRIO 0
00569
00570 static pthread_t controlThread;
00571 static pthread_attr_t controlThreadAttr;
00572
00573 int main(int argc, char *argv[])
00574 {
00575
00576 if (mlockall(MCL_CURRENT | MCL_FUTURE) < 0)
00577 {
00578 perror("Failed to lock memory. It is recommended to do rosrun ros_ethercat_loop ros_grant");
00579 exit(EXIT_FAILURE);
00580 }
00581
00582
00583 ros::init(argc, argv, "realtime_loop");
00584
00585
00586 g_options.program_ = argv[0];
00587 g_options.rosparam_ = NULL;
00588 g_options.period = 1e+6;
00589
00590 while (true)
00591 {
00592 static struct option long_options[] = {
00593 {"help", no_argument, 0, 'h'},
00594 {"stats", no_argument, 0, 's'},
00595 {"allow_unprogrammed", no_argument, 0, 'u'},
00596 {"interface", required_argument, 0, 'i'},
00597 {"rosparam", required_argument, 0, 'r'},
00598 {"period", no_argument, 0, 'p'},
00599 };
00600 int option_index = 0;
00601 int c = getopt_long(argc, argv, "hi:usx:r:", long_options, &option_index);
00602 if (c == -1)
00603 break;
00604
00605 switch (c)
00606 {
00607 case 'h':
00608 Usage();
00609 break;
00610 case 'u':
00611 g_options.allow_unprogrammed_ = true;
00612 break;
00613 case 'i':
00614 g_options.interface_ = optarg;
00615 break;
00616 case 'r':
00617 g_options.rosparam_ = optarg;
00618 break;
00619 case 's':
00620 g_options.stats_ = true;
00621 break;
00622 case 'p':
00623
00624 g_options.period = fabs(atof(optarg))*1e+6;
00625 break;
00626 }
00627 }
00628 if (optind < argc)
00629 Usage("Extra arguments");
00630
00631 if (!g_options.interface_)
00632 Usage("You must specify a network interface");
00633 if (!g_options.rosparam_)
00634 Usage("You must specify a rosparam for robot description");
00635
00636
00637 if (setupPidFile(g_options.interface_) < 0)
00638 exit(EXIT_FAILURE);
00639
00640 ros::NodeHandle node(name);
00641
00642
00643 signal(SIGTERM, quitRequested);
00644 signal(SIGINT, quitRequested);
00645 signal(SIGHUP, quitRequested);
00646
00647
00648 int rv = pthread_create(&controlThread, &controlThreadAttr, controlLoop, 0);
00649 if (rv != 0)
00650 {
00651 ROS_FATAL("Unable to create control thread: rv = %d", rv);
00652 exit(EXIT_FAILURE);
00653 }
00654
00655 ros::spin();
00656 pthread_join(controlThread, (void **) &rv);
00657
00658
00659 cleanupPidFile(NULL);
00660 cleanupPidFile(g_options.interface_);
00661
00662 return rv;
00663 }
00664