main.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <stdio.h>
36 #include <getopt.h>
37 #include <execinfo.h>
38 #include <signal.h>
39 #include <sys/mman.h>
40 #include <sys/types.h>
41 #include <sys/stat.h>
42 #include <unistd.h>
43 #include <fcntl.h>
44 #include <pthread.h>
45 
49 
50 #include <ros/ros.h>
51 #include <std_srvs/Empty.h>
52 
54 #include <std_msgs/Float64.h>
55 
56 #include <boost/accumulators/accumulators.hpp>
57 #include <boost/accumulators/statistics/stats.hpp>
58 #include <boost/accumulators/statistics/max.hpp>
59 #include <boost/accumulators/statistics/mean.hpp>
60 using namespace boost::accumulators;
61 
62 static const std::string name = "pr2_ethercat";
63 
64 
65 static struct
66 {
67  char *program_;
68  char *interface_;
69  char *xml_;
70  char *rosparam_;
72  bool stats_;
73 } g_options;
74 
75 std::string g_robot_desc;
76 
77 void Usage(string msg = "")
78 {
79  fprintf(stderr, "Usage: %s [options]\n", g_options.program_);
80  fprintf(stderr, " Available options\n");
81  fprintf(stderr, " -i, --interface <interface> Connect to EtherCAT devices on this interface\n");
82  fprintf(stderr, " -s, --stats Publish statistics on the RT loop jitter on \"pr2_ethercat/realtime\" in seconds\n");
83  fprintf(stderr, " -x, --xml <file> Load the robot description from this file\n");
84  fprintf(stderr, " -r, --rosparam <param> Load the robot description from this parameter name\n");
85  fprintf(stderr, " -u, --allow_unprogrammed Allow control loop to run with unprogrammed devices\n");
86  fprintf(stderr, " -h, --help Print this message and exit\n");
87  if (msg != "")
88  {
89  fprintf(stderr, "Error: %s\n", msg.c_str());
90  exit(-1);
91  }
92  else
93  {
94  exit(0);
95  }
96 }
97 
98 static int g_quit = 0;
99 static bool g_reset_motors = true;
100 static bool g_halt_motors = false;
101 static bool g_halt_requested = false;
102 static volatile bool g_publish_trace_requested = false;
103 static const int NSEC_PER_SECOND = 1e+9;
104 static const int USEC_PER_SECOND = 1e6;
105 
106 static struct
107 {
108  accumulator_set<double, stats<tag::max, tag::mean> > ec_acc;
109  accumulator_set<double, stats<tag::max, tag::mean> > cm_acc;
110  accumulator_set<double, stats<tag::max, tag::mean> > loop_acc;
111  accumulator_set<double, stats<tag::max, tag::mean> > jitter_acc;
112  int overruns;
117  double overrun_ec;
118  double overrun_cm;
119 
120  // These values are set when realtime loop does not meet performace expections
124 } g_stats;
125 
127 {
128  if (publisher.trylock())
129  {
130  accumulator_set<double, stats<tag::max, tag::mean> > zero;
131  vector<diagnostic_msgs::DiagnosticStatus> statuses;
133 
134  static double max_ec = 0, max_cm = 0, max_loop = 0, max_jitter = 0;
135  double avg_ec, avg_cm, avg_loop, avg_jitter;
136 
137  avg_ec = extract_result<tag::mean>(g_stats.ec_acc);
138  avg_cm = extract_result<tag::mean>(g_stats.cm_acc);
139  avg_loop = extract_result<tag::mean>(g_stats.loop_acc);
140  max_ec = std::max(max_ec, extract_result<tag::max>(g_stats.ec_acc));
141  max_cm = std::max(max_cm, extract_result<tag::max>(g_stats.cm_acc));
142  max_loop = std::max(max_loop, extract_result<tag::max>(g_stats.loop_acc));
143  g_stats.ec_acc = zero;
144  g_stats.cm_acc = zero;
145  g_stats.loop_acc = zero;
146 
147  // Publish average loop jitter
148  avg_jitter = extract_result<tag::mean>(g_stats.jitter_acc);
149  max_jitter = std::max(max_jitter, extract_result<tag::max>(g_stats.jitter_acc));
150  g_stats.jitter_acc = zero;
151 
152  static bool first = true;
153  if (first)
154  {
155  first = false;
156  status.add("Robot Description", g_robot_desc);
157  }
158 
159  status.addf("Max EtherCAT roundtrip (us)", "%.2f", max_ec*USEC_PER_SECOND);
160  status.addf("Avg EtherCAT roundtrip (us)", "%.2f", avg_ec*USEC_PER_SECOND);
161  status.addf("Max Controller Manager roundtrip (us)", "%.2f", max_cm*USEC_PER_SECOND);
162  status.addf("Avg Controller Manager roundtrip (us)", "%.2f", avg_cm*USEC_PER_SECOND);
163  status.addf("Max Total Loop roundtrip (us)", "%.2f", max_loop*USEC_PER_SECOND);
164  status.addf("Avg Total Loop roundtrip (us)", "%.2f", avg_loop*USEC_PER_SECOND);
165  status.addf("Max Loop Jitter (us)", "%.2f", max_jitter * USEC_PER_SECOND);
166  status.addf("Avg Loop Jitter (us)", "%.2f", avg_jitter * USEC_PER_SECOND);
167  status.addf("Control Loop Overruns", "%d", g_stats.overruns);
168  status.addf("Recent Control Loop Overruns", "%d", g_stats.recent_overruns);
169  status.addf("Last Control Loop Overrun Cause", "ec: %.2fus, cm: %.2fus",
170  g_stats.overrun_ec*USEC_PER_SECOND, g_stats.overrun_cm*USEC_PER_SECOND);
171  status.addf("Last Overrun Loop Time (us)", "%.2f", g_stats.overrun_loop_sec * USEC_PER_SECOND);
172  status.addf("Realtime Loop Frequency", "%.4f", g_stats.rt_loop_frequency);
173 
174  status.name = "Realtime Control Loop";
175  if (g_stats.overruns > 0 && g_stats.last_overrun < 30)
176  {
177  if (g_stats.last_severe_overrun < 30)
178  status.level = 1;
179  else
180  status.level = 0;
181  status.message = "Realtime loop used too much time in the last 30 seconds.";
182  }
183  else
184  {
185  status.level = 0;
186  status.message = "OK";
187  }
188  g_stats.recent_overruns = 0;
189  g_stats.last_overrun++;
190  g_stats.last_severe_overrun++;
191 
192  if (g_stats.rt_loop_not_making_timing)
193  {
194  status.mergeSummaryf(status.ERROR, "Halting, realtime loop only ran at %.4f Hz", g_stats.halt_rt_loop_frequency);
195  }
196 
197  statuses.push_back(status);
198  publisher.msg_.status = statuses;
199  publisher.msg_.header.stamp = ros::Time::now();
200  publisher.unlockAndPublish();
201  }
202 }
203 
204 static inline double now()
205 {
206  struct timespec n;
207  clock_gettime(CLOCK_MONOTONIC, &n);
208  return double(n.tv_nsec) / NSEC_PER_SECOND + n.tv_sec;
209 }
210 
211 
212 void *diagnosticLoop(void *args)
213 {
214  EthercatHardware *ec((EthercatHardware *) args);
215  struct timespec tick;
216  clock_gettime(CLOCK_MONOTONIC, &tick);
217  while (!g_quit) {
218  ec->collectDiagnostics();
219  tick.tv_sec += 1;
220  clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &tick, NULL);
221  }
222  return NULL;
223 }
224 
225 static void timespecInc(struct timespec &tick, int nsec)
226 {
227  tick.tv_nsec += nsec;
228  while (tick.tv_nsec >= NSEC_PER_SECOND)
229  {
230  tick.tv_nsec -= NSEC_PER_SECOND;
231  tick.tv_sec++;
232  }
233 }
234 
235 
237 {
238 public:
239  RTLoopHistory(unsigned length, double default_value) :
240  index_(0),
241  length_(length),
242  history_(new double[length])
243  {
244  for (unsigned i=0; i<length_; ++i)
245  history_[i] = default_value;
246  }
247 
249  {
250  delete[] history_;
251  history_ = NULL;
252  }
253 
254  void sample(double value)
255  {
256  index_ = (index_+1) % length_;
257  history_[index_] = value;
258  }
259 
260  double average() const
261  {
262  double sum(0.0);
263  for (unsigned i=0; i<length_; ++i)
264  sum+=history_[i];
265  return sum / double(length_);
266  }
267 
268 protected:
269  unsigned index_;
270  unsigned length_;
271  double *history_;
272 };
273 
274 
275 void *controlLoop(void *)
276 {
277  int rv = 0;
278  double last_published, last_loop_start;
279  int period;
280  int policy;
281  TiXmlElement *root;
282  TiXmlElement *root_element;
283 
284  ros::NodeHandle node(name);
285 
288 
289  // Realtime loop should be running at least 750Hz
290  // Calculate realtime loop frequency every 200mseec
291  // Halt motors if average frequency over last 600msec is less than 750Hz
292  double min_acceptable_rt_loop_frequency;
293  if (!node.getParam("min_acceptable_rt_loop_frequency", min_acceptable_rt_loop_frequency))
294  {
295  min_acceptable_rt_loop_frequency = 750.0;
296  }
297  else
298  {
299  ROS_WARN("min_acceptable_rt_loop_frequency changed to %f", min_acceptable_rt_loop_frequency);
300  }
301  unsigned rt_cycle_count = 0;
302  double last_rt_monitor_time;
303  double rt_loop_monitor_period = 0.6 / 3;
304  // Keep history of last 3 calculation intervals.
305  RTLoopHistory rt_loop_history(3, 1000.0);
306 
307  if (g_options.stats_){
308  rtpublisher = new realtime_tools::RealtimePublisher<std_msgs::Float64>(node, "realtime", 2);
309  }
310 
311  // Initialize the hardware interface
313  ec.init(g_options.interface_, g_options.allow_unprogrammed_);
314 
315  // Create controller manager
317 
318  // Load robot description
319  TiXmlDocument xml;
320  struct stat st;
321  if (g_options.rosparam_ != NULL)
322  {
323  if (ros::param::get(g_options.rosparam_, g_robot_desc))
324  {
325  xml.Parse(g_robot_desc.c_str());
326  }
327  else
328  {
329  ROS_FATAL("Could not load the xml from parameter server: %s", g_options.rosparam_);
330  rv = -1;
331  goto end;
332  }
333  }
334  else if (0 == stat(g_options.xml_, &st))
335  {
336  xml.LoadFile(g_options.xml_);
337  }
338  else
339  {
340  // In ROS Galapagos remove this fall-back to rosparam functionality
341  ROS_INFO("Xml file not found, reading from parameter server");
342  ros::NodeHandle top_level_node;
343  if (top_level_node.getParam(g_options.xml_, g_robot_desc))
344  {
345  xml.Parse(g_robot_desc.c_str());
346  ROS_WARN("Using -x to load robot description from parameter server is depricated. Use -r instead.");
347  }
348  else
349  {
350  ROS_FATAL("Could not load the xml from parameter server: %s", g_options.xml_);
351  rv = -1;
352  goto end;
353  }
354  }
355 
356  root_element = xml.RootElement();
357  root = xml.FirstChildElement("robot");
358  if (!root || !root_element)
359  {
360  ROS_FATAL("Could not parse the xml from %s", g_options.xml_);
361  rv = -1;
362  goto end;
363  }
364 
365  // Initialize the controller manager from robot description
366  if (!cm.initXml(root))
367  {
368  ROS_FATAL("Could not initialize the controller manager");
369  rv = -1;
370  goto end;
371  }
372 
373  // Publish one-time before entering real-time to pre-allocate message vectors
374  publishDiagnostics(publisher);
375 
376  //Start Non-realtime diagonostic thread
377  static pthread_t diagnosticThread;
378  if ((rv = pthread_create(&diagnosticThread, NULL, diagnosticLoop, &ec)) != 0)
379  {
380  ROS_FATAL("Unable to create control thread: rv = %d", rv);
381  goto end;
382  }
383 
384  // Set to realtime scheduler for this thread
385  struct sched_param thread_param;
386  policy = SCHED_FIFO;
387  thread_param.sched_priority = sched_get_priority_max(policy);
388  pthread_setschedparam(pthread_self(), policy, &thread_param);
389 
390  struct timespec tick;
391  clock_gettime(CLOCK_REALTIME, &tick);
392  period = 1e+6; // 1 ms in nanoseconds
393 
394  // Snap to the nearest second
395  tick.tv_sec = tick.tv_sec;
396  tick.tv_nsec = (tick.tv_nsec / period + 1) * period;
397  clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL);
398 
399  last_published = now();
400  last_rt_monitor_time = now();
401  last_loop_start = now();
402  while (!g_quit)
403  {
404  // Track how long the actual loop takes
405  double this_loop_start = now();
406  g_stats.loop_acc(this_loop_start - last_loop_start);
407  last_loop_start = this_loop_start;
408 
409  double start = now();
410  if (g_reset_motors)
411  {
412  ec.update(true, g_halt_motors);
413  g_reset_motors = false;
414  // Also, clear error flags when motor reset is requested
415  g_stats.rt_loop_not_making_timing = false;
416  }
417  else
418  {
419  ec.update(false, g_halt_motors);
420  }
422  {
424  ec.publishTrace(-1,"",0,0);
425  }
426  g_halt_motors = false;
427  double after_ec = now();
428  cm.update();
429  double end = now();
430 
431  g_stats.ec_acc(after_ec - start);
432  g_stats.cm_acc(end - after_ec);
433 
434  if ((end - last_published) > 1.0)
435  {
436  publishDiagnostics(publisher);
437  last_published = end;
438  }
439 
440  // Realtime loop should run about 1000Hz.
441  // Missing timing on a control cycles usually causes a controller glitch and actuators to jerk.
442  // When realtime loop misses a lot of cycles controllers will perform poorly and may cause robot to shake.
443  // Halt motors if realtime loop does not run enough cycles over a given period.
444  ++rt_cycle_count;
445  if ((start - last_rt_monitor_time) > rt_loop_monitor_period)
446  {
447  // Calculate new average rt loop frequency
448  double rt_loop_frequency = double(rt_cycle_count) / rt_loop_monitor_period;
449 
450  // Use last X samples of frequency when deciding whether or not to halt
451  rt_loop_history.sample(rt_loop_frequency);
452  double avg_rt_loop_frequency = rt_loop_history.average();
453  if (avg_rt_loop_frequency < min_acceptable_rt_loop_frequency)
454  {
455  g_halt_motors = true;
456  if (!g_stats.rt_loop_not_making_timing)
457  {
458  // Only update this value if motors when this first occurs (used for diagnostics error message)
459  g_stats.halt_rt_loop_frequency = avg_rt_loop_frequency;
460  }
461  g_stats.rt_loop_not_making_timing = true;
462  }
463  g_stats.rt_loop_frequency = avg_rt_loop_frequency;
464  rt_cycle_count = 0;
465  last_rt_monitor_time = start;
466  }
467 
468  // Compute end of next period
469  timespecInc(tick, period);
470 
471  struct timespec before;
472  clock_gettime(CLOCK_REALTIME, &before);
473  if ((before.tv_sec + double(before.tv_nsec)/NSEC_PER_SECOND) > (tick.tv_sec + double(tick.tv_nsec)/NSEC_PER_SECOND))
474  {
475  // Total amount of time the loop took to run
476  g_stats.overrun_loop_sec = (before.tv_sec + double(before.tv_nsec)/NSEC_PER_SECOND) -
477  (tick.tv_sec + double(tick.tv_nsec)/NSEC_PER_SECOND);
478 
479  // We overran, snap to next "period"
480  tick.tv_sec = before.tv_sec;
481  tick.tv_nsec = (before.tv_nsec / period) * period;
482  timespecInc(tick, period);
483 
484  // initialize overruns
485  if (g_stats.overruns == 0){
486  g_stats.last_overrun = 1000;
487  g_stats.last_severe_overrun = 1000;
488  }
489  // check for overruns
490  if (g_stats.recent_overruns > 10)
491  g_stats.last_severe_overrun = 0;
492  g_stats.last_overrun = 0;
493 
494  g_stats.overruns++;
495  g_stats.recent_overruns++;
496  g_stats.overrun_ec = after_ec - start;
497  g_stats.overrun_cm = end - after_ec;
498  }
499 
500  // Sleep until end of period
501  clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL);
502 
503  // Calculate RT loop jitter
504  struct timespec after;
505  clock_gettime(CLOCK_REALTIME, &after);
506  double jitter = (after.tv_sec - tick.tv_sec + double(after.tv_nsec-tick.tv_nsec)/NSEC_PER_SECOND);
507 
508  g_stats.jitter_acc(jitter);
509 
510  // Publish realtime loops statistics, if requested
511  if (rtpublisher)
512  {
513  if (rtpublisher->trylock())
514  {
515  rtpublisher->msg_.data = jitter;
516  rtpublisher->unlockAndPublish();
517  }
518  }
519 
520  // Halt the motors, if requested by a service call
521  if (g_halt_requested)
522  {
523  g_halt_motors = true;
524  g_halt_requested = false;
525  }
526  }
527 
528  /* Shutdown all of the motors on exit */
529  for (pr2_hardware_interface::ActuatorMap::const_iterator it = ec.hw_->actuators_.begin(); it != ec.hw_->actuators_.end(); ++it)
530  {
531  it->second->command_.enable_ = false;
532  it->second->command_.effort_ = 0;
533  }
534  ec.update(false, true);
535 
536  //pthread_join(diagnosticThread, 0);
537 
538 end:
539  publisher.stop();
540  delete rtpublisher;
541 
542  ros::shutdown();
543 
544  return (void *) (intptr_t) rv;
545 }
546 
547 void quitRequested(int sig)
548 {
549  g_quit = 1;
550 }
551 
552 bool resetMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
553 {
554  g_reset_motors = true;
555  return true;
556 }
557 
558 bool haltMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
559 {
560  g_halt_requested = true;
561  return true;
562 }
563 
564 bool publishTraceService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
565 {
567  return true;
568 }
569 
570 static int
571 lock_fd(int fd)
572 {
573  struct flock lock;
574  int rv;
575 
576  lock.l_type = F_WRLCK;
577  lock.l_whence = SEEK_SET;
578  lock.l_start = 0;
579  lock.l_len = 0;
580 
581  rv = fcntl(fd, F_SETLK, &lock);
582  return rv;
583 }
584 
585 
586 static const char* PIDDIR = "/var/tmp/run/";
587 
588 std::string generatePIDFilename(const char* interface)
589 {
590  std::string filename;
591  if (interface != NULL)
592  {
593  // There should a lock file for each EtherCAT interface instead of for entire computer
594  // It is entirely possible to have different EtherCAT utilities operating indepedantly
595  // on different interfaces
596  filename = std::string(PIDDIR) + "EtherCAT_" + std::string(interface) + ".pid";
597  }
598  else
599  {
600  filename = std::string(PIDDIR) + std::string("pr2_etherCAT.pid");
601  }
602  return filename;
603 }
604 
605 
606 static int setupPidFile(const char* interface)
607 {
608  int rv = -1;
609  pid_t pid;
610  int fd;
611  FILE *fp = NULL;
612 
613  std::string filename = generatePIDFilename(interface);
614 
615  umask(0);
616  mkdir(PIDDIR, 0777);
617  fd = open(filename.c_str(), O_RDWR | O_CREAT | O_EXCL, S_IWUSR | S_IRUSR | S_IWGRP | S_IRGRP | S_IWOTH | S_IROTH);
618  if (fd == -1)
619  {
620  if (errno != EEXIST)
621  {
622  ROS_FATAL("Unable to create pid file '%s': %s", filename.c_str(), strerror(errno));
623  goto end;
624  }
625 
626  if ((fd = open(filename.c_str(), O_RDWR)) < 0)
627  {
628  ROS_FATAL("Unable to open pid file '%s': %s", filename.c_str(), strerror(errno));
629  goto end;
630  }
631 
632  if ((fp = fdopen(fd, "rw")) == NULL)
633  {
634  ROS_FATAL("Can't read from '%s': %s", filename.c_str(), strerror(errno));
635  goto end;
636  }
637  pid = -1;
638  if ((fscanf(fp, "%d", &pid) != 1) || (pid == getpid()) || (lock_fd(fileno(fp)) == 0))
639  {
640  int rc;
641 
642  if ((rc = unlink(filename.c_str())) == -1)
643  {
644  ROS_FATAL("Can't remove stale pid file '%s': %s", filename.c_str(), strerror(errno));
645  goto end;
646  }
647  } else {
648  ROS_FATAL("Another instance of pr2_ethercat is already running with pid: %d", pid);
649  goto end;
650  }
651  }
652 
653  unlink(filename.c_str());
654  fd = open(filename.c_str(), O_RDWR | O_CREAT | O_EXCL, S_IWUSR | S_IRUSR | S_IWGRP | S_IRGRP | S_IWOTH | S_IROTH);
655 
656  if (fd == -1)
657  {
658  ROS_FATAL("Unable to open pid file '%s': %s", filename.c_str(), strerror(errno));
659  goto end;
660  }
661 
662  if (lock_fd(fd) == -1)
663  {
664  ROS_FATAL("Unable to lock pid file '%s': %s", filename.c_str(), strerror(errno));
665  goto end;
666  }
667 
668  if ((fp = fdopen(fd, "w")) == NULL)
669  {
670  ROS_FATAL("fdopen failed: %s", strerror(errno));
671  goto end;
672  }
673 
674  fprintf(fp, "%d\n", getpid());
675 
676  /* We do NOT close fd, since we want to keep the lock. */
677  fflush(fp);
678  fcntl(fd, F_SETFD, (long) 1);
679  rv = 0;
680 end:
681  return rv;
682 }
683 
684 static void cleanupPidFile(const char* interface)
685 {
686  std::string filename = generatePIDFilename(interface);
687  unlink(filename.c_str());
688 }
689 
690 #define CLOCK_PRIO 0
691 #define CONTROL_PRIO 0
692 
693 static pthread_t controlThread;
694 static pthread_attr_t controlThreadAttr;
695 int main(int argc, char *argv[])
696 {
697  // Keep the kernel from swapping us out
698  if (mlockall(MCL_CURRENT | MCL_FUTURE) < 0) {
699  perror("mlockall");
700  return -1;
701  }
702 
703  // Initialize ROS and parse command-line arguments
704  ros::init(argc, argv, "realtime_loop");
705 
706  // Parse options
707  g_options.program_ = argv[0];
708  g_options.xml_ = NULL;
709  g_options.rosparam_ = NULL;
710  while (1)
711  {
712  static struct option long_options[] = {
713  {"help", no_argument, 0, 'h'},
714  {"stats", no_argument, 0, 's'},
715  {"allow_unprogrammed", no_argument, 0, 'u'},
716  {"interface", required_argument, 0, 'i'},
717  {"xml", required_argument, 0, 'x'},
718  {"rosparam", required_argument, 0, 'r'},
719  };
720  int option_index = 0;
721  int c = getopt_long(argc, argv, "hi:usx:r:", long_options, &option_index);
722  if (c == -1) break;
723  switch (c)
724  {
725  case 'h':
726  Usage();
727  break;
728  case 'u':
729  g_options.allow_unprogrammed_ = 1;
730  break;
731  case 'i':
732  g_options.interface_ = optarg;
733  break;
734  case 'x':
735  g_options.xml_ = optarg;
736  break;
737  case 'r':
738  g_options.rosparam_ = optarg;
739  break;
740  case 's':
741  g_options.stats_ = 1;
742  break;
743  }
744  }
745  if (optind < argc)
746  {
747  Usage("Extra arguments");
748  }
749 
750  if (!g_options.interface_)
751  Usage("You must specify a network interface");
752  if (!g_options.xml_ && !g_options.rosparam_)
753  {
754  Usage("You must specify either an XML file or rosparam for robot description");
755  }
756  if (g_options.xml_ && g_options.rosparam_)
757  {
758  Usage("You must not specify both a rosparm and XML file for robot description");
759  }
760 
761  // The previous EtherCAT software created a lock for any EtherCAT master.
762  // This lock prevented two EtherCAT masters from running on the same computer.
763  // However, this locking scheme was too restrictive.
764  // Two EtherCAT masters can run without conflicting with each other
765  // as long as they are communication with different sets of EtherCAT devices.
766  // A better locking scheme is to prevent two EtherCAT
767  // masters from running on same Ethernet interface.
768  // Therefore in the Groovy Galapagos ROS release, the global EtherCAT lock has been removed
769  // and only the per-interface lock will remain.
770  if (setupPidFile(g_options.interface_) < 0) return -1;
771 
772  ros::NodeHandle node(name);
773 
774  // Catch attempts to quit
775  signal(SIGTERM, quitRequested);
776  signal(SIGINT, quitRequested);
777  signal(SIGHUP, quitRequested);
778 
781  ros::ServiceServer publishTrace = node.advertiseService("publish_trace", publishTraceService);
782 
783  //Start thread
784  int rv;
785  if ((rv = pthread_create(&controlThread, &controlThreadAttr, controlLoop, 0)) != 0)
786  {
787  ROS_FATAL("Unable to create control thread: rv = %d", rv);
788  exit(EXIT_FAILURE);
789  }
790 
791  ros::spin();
792  pthread_join(controlThread, (void **)&rv);
793 
794  // Cleanup pid files
795  cleanupPidFile(NULL);
796  cleanupPidFile(g_options.interface_);
797 
798  return rv;
799 }
800 
msg
bool publishTraceService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
Definition: main.cpp:564
std::string g_robot_desc
Definition: main.cpp:75
bool resetMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
Definition: main.cpp:552
double overrun_loop_sec
Definition: main.cpp:116
void quitRequested(int sig)
Definition: main.cpp:547
#define ROS_FATAL(...)
std::string generatePIDFilename(const char *interface)
Definition: main.cpp:588
accumulator_set< double, stats< tag::max, tag::mean > > loop_acc
Definition: main.cpp:110
static bool g_reset_motors
Definition: main.cpp:99
accumulator_set< double, stats< tag::max, tag::mean > > cm_acc
Definition: main.cpp:109
void Usage(string msg="")
Definition: main.cpp:77
static const int USEC_PER_SECOND
Definition: main.cpp:104
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool allow_unprogrammed_
Definition: main.cpp:71
double overrun_ec
Definition: main.cpp:117
char * rosparam_
Definition: main.cpp:70
static pthread_t controlThread
Definition: main.cpp:693
unsigned length_
Definition: main.cpp:270
double average() const
Definition: main.cpp:260
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static int g_quit
Definition: main.cpp:98
#define ROS_WARN(...)
stderr
double overrun_cm
Definition: main.cpp:118
void addf(const std::string &key, const char *format,...)
bool rt_loop_not_making_timing
Definition: main.cpp:121
static volatile bool g_publish_trace_requested
Definition: main.cpp:102
void sample(double value)
Definition: main.cpp:254
static int lock_fd(int fd)
Definition: main.cpp:571
static void timespecInc(struct timespec &tick, int nsec)
Definition: main.cpp:225
void collectDiagnostics()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
uint16_t status
double * history_
Definition: main.cpp:271
#define ROS_INFO(...)
int overruns
Definition: main.cpp:112
unsigned index_
Definition: main.cpp:269
bool stats_
Definition: main.cpp:72
void zero()
accumulator_set< double, stats< tag::max, tag::mean > > ec_acc
Definition: main.cpp:108
ROSCPP_DECL void spin()
static pthread_attr_t controlThreadAttr
Definition: main.cpp:694
int last_severe_overrun
Definition: main.cpp:115
static struct @1 g_stats
static const int NSEC_PER_SECOND
Definition: main.cpp:103
bool initXml(TiXmlElement *config)
void * diagnosticLoop(void *args)
Definition: main.cpp:212
static void publishDiagnostics(realtime_tools::RealtimePublisher< diagnostic_msgs::DiagnosticArray > &publisher)
Definition: main.cpp:126
static struct @0 g_options
static const std::string name
Definition: main.cpp:62
void init(const ros::NodeHandle &node, const std::string &topic, int queue_size, bool latched=false)
static bool g_halt_requested
Definition: main.cpp:101
static bool g_halt_motors
Definition: main.cpp:100
RTLoopHistory(unsigned length, double default_value)
Definition: main.cpp:239
static int setupPidFile(const char *interface)
Definition: main.cpp:606
char * xml_
Definition: main.cpp:69
bool getParam(const std::string &key, std::string &s) const
char * program_
Definition: main.cpp:67
bool haltMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
Definition: main.cpp:558
static Time now()
void * controlLoop(void *)
Definition: main.cpp:275
ROSCPP_DECL void shutdown()
void mergeSummaryf(unsigned char lvl, const char *format,...)
double rt_loop_frequency
Definition: main.cpp:123
~RTLoopHistory()
Definition: main.cpp:248
static const char * PIDDIR
Definition: main.cpp:586
void add(const std::string &key, const T &val)
uint16_t length_
char * interface_
Definition: main.cpp:68
int main(int argc, char *argv[])
Definition: main.cpp:695
static double now()
Definition: main.cpp:204
double halt_rt_loop_frequency
Definition: main.cpp:122
static void cleanupPidFile(const char *interface)
Definition: main.cpp:684
accumulator_set< double, stats< tag::max, tag::mean > > jitter_acc
Definition: main.cpp:111
int recent_overruns
Definition: main.cpp:113
int last_overrun
Definition: main.cpp:114


pr2_ethercat
Author(s): Rob Wheeler
autogenerated on Tue Jun 1 2021 02:50:54