40 #include <sys/types.h> 51 #include <std_srvs/Empty.h> 54 #include <std_msgs/Float64.h> 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> 62 static const std::string
name =
"pr2_ethercat";
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");
89 fprintf(
stderr,
"Error: %s\n",
msg.c_str());
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;
130 accumulator_set<double, stats<tag::max, tag::mean> >
zero;
131 vector<diagnostic_msgs::DiagnosticStatus> statuses;
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;
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));
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));
152 static bool first =
true;
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);
174 status.name =
"Realtime Control Loop";
177 if (
g_stats.last_severe_overrun < 30)
181 status.message =
"Realtime loop used too much time in the last 30 seconds.";
186 status.message =
"OK";
192 if (
g_stats.rt_loop_not_making_timing)
194 status.
mergeSummaryf(status.ERROR,
"Halting, realtime loop only ran at %.4f Hz",
g_stats.halt_rt_loop_frequency);
197 statuses.push_back(status);
198 publisher.
msg_.status = statuses;
204 static inline double now()
207 clock_gettime(CLOCK_MONOTONIC, &n);
215 struct timespec tick;
216 clock_gettime(CLOCK_MONOTONIC, &tick);
220 clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &tick, NULL);
227 tick.tv_nsec += nsec;
242 history_(new double[length])
244 for (
unsigned i=0; i<
length_; ++i)
245 history_[i] = default_value;
257 history_[index_] = value;
263 for (
unsigned i=0; i<
length_; ++i)
265 return sum / double(length_);
278 double last_published, last_loop_start;
282 TiXmlElement *root_element;
292 double min_acceptable_rt_loop_frequency;
293 if (!node.
getParam(
"min_acceptable_rt_loop_frequency", min_acceptable_rt_loop_frequency))
295 min_acceptable_rt_loop_frequency = 750.0;
299 ROS_WARN(
"min_acceptable_rt_loop_frequency changed to %f", min_acceptable_rt_loop_frequency);
301 unsigned rt_cycle_count = 0;
302 double last_rt_monitor_time;
303 double rt_loop_monitor_period = 0.6 / 3;
341 ROS_INFO(
"Xml file not found, reading from parameter server");
346 ROS_WARN(
"Using -x to load robot description from parameter server is depricated. Use -r instead.");
356 root_element = xml.RootElement();
357 root = xml.FirstChildElement(
"robot");
358 if (!root || !root_element)
368 ROS_FATAL(
"Could not initialize the controller manager");
377 static pthread_t diagnosticThread;
378 if ((rv = pthread_create(&diagnosticThread, NULL,
diagnosticLoop, &ec)) != 0)
380 ROS_FATAL(
"Unable to create control thread: rv = %d", rv);
385 struct sched_param thread_param;
387 thread_param.sched_priority = sched_get_priority_max(policy);
388 pthread_setschedparam(pthread_self(), policy, &thread_param);
390 struct timespec tick;
391 clock_gettime(CLOCK_REALTIME, &tick);
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);
399 last_published =
now();
400 last_rt_monitor_time =
now();
401 last_loop_start =
now();
405 double this_loop_start =
now();
406 g_stats.loop_acc(this_loop_start - last_loop_start);
407 last_loop_start = this_loop_start;
415 g_stats.rt_loop_not_making_timing =
false;
424 ec.publishTrace(-1,
"",0,0);
427 double after_ec =
now();
431 g_stats.ec_acc(after_ec - start);
432 g_stats.cm_acc(end - after_ec);
434 if ((end - last_published) > 1.0)
437 last_published = end;
445 if ((start - last_rt_monitor_time) > rt_loop_monitor_period)
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)
456 if (!
g_stats.rt_loop_not_making_timing)
459 g_stats.halt_rt_loop_frequency = avg_rt_loop_frequency;
461 g_stats.rt_loop_not_making_timing =
true;
463 g_stats.rt_loop_frequency = avg_rt_loop_frequency;
465 last_rt_monitor_time =
start;
471 struct timespec before;
472 clock_gettime(CLOCK_REALTIME, &before);
480 tick.tv_sec = before.tv_sec;
481 tick.tv_nsec = (before.tv_nsec / period) * period;
487 g_stats.last_severe_overrun = 1000;
490 if (
g_stats.recent_overruns > 10)
491 g_stats.last_severe_overrun = 0;
497 g_stats.overrun_cm = end - after_ec;
501 clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL);
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);
515 rtpublisher->
msg_.data = jitter;
529 for (pr2_hardware_interface::ActuatorMap::const_iterator it = ec.hw_->actuators_.begin(); it != ec.hw_->actuators_.end(); ++it)
531 it->second->command_.enable_ =
false;
532 it->second->command_.effort_ = 0;
534 ec.update(
false,
true);
544 return (
void *) (intptr_t) rv;
576 lock.l_type = F_WRLCK;
577 lock.l_whence = SEEK_SET;
581 rv = fcntl(fd, F_SETLK, &lock);
586 static const char*
PIDDIR =
"/var/tmp/run/";
590 std::string filename;
591 if (interface != NULL)
596 filename = std::string(
PIDDIR) +
"EtherCAT_" + std::string(interface) +
".pid";
600 filename = std::string(
PIDDIR) + std::string(
"pr2_etherCAT.pid");
617 fd = open(filename.c_str(), O_RDWR | O_CREAT | O_EXCL, S_IWUSR | S_IRUSR | S_IWGRP | S_IRGRP | S_IWOTH | S_IROTH);
622 ROS_FATAL(
"Unable to create pid file '%s': %s", filename.c_str(), strerror(errno));
626 if ((fd = open(filename.c_str(), O_RDWR)) < 0)
628 ROS_FATAL(
"Unable to open pid file '%s': %s", filename.c_str(), strerror(errno));
632 if ((fp = fdopen(fd,
"rw")) == NULL)
634 ROS_FATAL(
"Can't read from '%s': %s", filename.c_str(), strerror(errno));
638 if ((fscanf(fp,
"%d", &pid) != 1) || (pid == getpid()) || (
lock_fd(fileno(fp)) == 0))
642 if ((rc = unlink(filename.c_str())) == -1)
644 ROS_FATAL(
"Can't remove stale pid file '%s': %s", filename.c_str(), strerror(errno));
648 ROS_FATAL(
"Another instance of pr2_ethercat is already running with pid: %d", pid);
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);
658 ROS_FATAL(
"Unable to open pid file '%s': %s", filename.c_str(), strerror(errno));
664 ROS_FATAL(
"Unable to lock pid file '%s': %s", filename.c_str(), strerror(errno));
668 if ((fp = fdopen(fd,
"w")) == NULL)
670 ROS_FATAL(
"fdopen failed: %s", strerror(errno));
674 fprintf(fp,
"%d\n", getpid());
678 fcntl(fd, F_SETFD, (
long) 1);
687 unlink(filename.c_str());
691 #define CONTROL_PRIO 0 695 int main(
int argc,
char *argv[])
698 if (mlockall(MCL_CURRENT | MCL_FUTURE) < 0) {
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'},
720 int option_index = 0;
721 int c = getopt_long(argc, argv,
"hi:usx:r:", long_options, &option_index);
747 Usage(
"Extra arguments");
751 Usage(
"You must specify a network interface");
754 Usage(
"You must specify either an XML file or rosparam for robot description");
758 Usage(
"You must not specify both a rosparm and XML file for robot description");
787 ROS_FATAL(
"Unable to create control thread: rv = %d", rv);
bool publishTraceService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
bool resetMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
void quitRequested(int sig)
std::string generatePIDFilename(const char *interface)
accumulator_set< double, stats< tag::max, tag::mean > > loop_acc
static bool g_reset_motors
accumulator_set< double, stats< tag::max, tag::mean > > cm_acc
void Usage(string msg="")
static const int USEC_PER_SECOND
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static pthread_t controlThread
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void addf(const std::string &key, const char *format,...)
bool rt_loop_not_making_timing
static volatile bool g_publish_trace_requested
void sample(double value)
static int lock_fd(int fd)
static void timespecInc(struct timespec &tick, int nsec)
void collectDiagnostics()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
accumulator_set< double, stats< tag::max, tag::mean > > ec_acc
static pthread_attr_t controlThreadAttr
static const int NSEC_PER_SECOND
bool initXml(TiXmlElement *config)
void * diagnosticLoop(void *args)
static void publishDiagnostics(realtime_tools::RealtimePublisher< diagnostic_msgs::DiagnosticArray > &publisher)
static struct @0 g_options
static const std::string name
static bool g_halt_requested
static bool g_halt_motors
RTLoopHistory(unsigned length, double default_value)
static int setupPidFile(const char *interface)
bool getParam(const std::string &key, std::string &s) const
bool haltMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
void * controlLoop(void *)
ROSCPP_DECL void shutdown()
void mergeSummaryf(unsigned char lvl, const char *format,...)
static const char * PIDDIR
void add(const std::string &key, const T &val)
int main(int argc, char *argv[])
double halt_rt_loop_frequency
static void cleanupPidFile(const char *interface)
accumulator_set< double, stats< tag::max, tag::mean > > jitter_acc