#include <stdio.h>
#include <getopt.h>
#include <execinfo.h>
#include <signal.h>
#include <sys/mman.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <unistd.h>
#include <fcntl.h>
#include <pthread.h>
#include <diagnostic_updater/DiagnosticStatusWrapper.h>
#include <pr2_controller_manager/controller_manager.h>
#include <ethercat_hardware/ethercat_hardware.h>
#include <ros/ros.h>
#include <std_srvs/Empty.h>
#include <realtime_tools/realtime_publisher.h>
#include <std_msgs/Float64.h>
#include <boost/accumulators/accumulators.hpp>
#include <boost/accumulators/statistics/stats.hpp>
#include <boost/accumulators/statistics/max.hpp>
#include <boost/accumulators/statistics/mean.hpp>
Go to the source code of this file.
| 
Classes | 
| class | RTLoopHistory | 
| 
Defines | 
| #define | CLOCK_PRIO   0 | 
| #define | CONTROL_PRIO   0 | 
| 
Functions | 
| static void | cleanupPidFile (const char *interface) | 
| void * | controlLoop (void *) | 
| void * | diagnosticLoop (void *args) | 
| std::string | generatePIDFilename (const char *interface) | 
| bool | haltMotorsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) | 
| static int | lock_fd (int fd) | 
| int | main (int argc, char *argv[]) | 
| static double | now () | 
| static void | publishDiagnostics (realtime_tools::RealtimePublisher< diagnostic_msgs::DiagnosticArray > &publisher) | 
| bool | publishTraceService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) | 
| void | quitRequested (int sig) | 
| bool | resetMotorsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) | 
| static int | setupPidFile (const char *interface) | 
| static void | timespecInc (struct timespec &tick, int nsec) | 
| void | Usage (string msg="") | 
| 
Variables | 
| static pthread_t | controlThread | 
| static pthread_attr_t | controlThreadAttr | 
| static bool | g_halt_motors = false | 
| static bool | g_halt_requested = false | 
| struct { | 
| bool   allow_unprogrammed_ | 
| char *   interface_ | 
| char *   program_ | 
| char *   rosparam_ | 
| bool   stats_ | 
| char *   xml_ | 
| } | g_options | 
| static volatile bool | g_publish_trace_requested = false | 
| static int | g_quit = 0 | 
| static bool | g_reset_motors = true | 
| std::string | g_robot_desc | 
| struct { | 
| accumulator_set< double, stats < tag::max, tag::mean > >   cm_acc
 | 
| accumulator_set< double, stats < tag::max, tag::mean > >   ec_acc
 | 
| double   halt_rt_loop_frequency | 
| accumulator_set< double, stats < tag::max, tag::mean > >   jitter_acc
 | 
| int   last_overrun | 
| int   last_severe_overrun | 
| accumulator_set< double, stats < tag::max, tag::mean > >   loop_acc
 | 
| double   overrun_cm | 
| double   overrun_ec | 
| double   overrun_loop_sec | 
| int   overruns | 
| int   recent_overruns | 
| double   rt_loop_frequency | 
| bool   rt_loop_not_making_timing | 
| } | g_stats | 
| static const std::string | name = "pr2_ethercat" | 
| static const int | NSEC_PER_SECOND = 1e+9 | 
| static const char * | PIDDIR = "/var/tmp/run/" | 
| static const int | USEC_PER_SECOND = 1e6 | 
Define Documentation
Function Documentation
      
        
          | bool haltMotorsService | ( | std_srvs::Empty::Request & | req, | 
        
          |  |  | std_srvs::Empty::Response & | resp | 
        
          |  | ) |  |  | 
      
 
 
      
        
          | static int lock_fd | ( | int | fd | ) |  [static] | 
      
 
 
      
        
          | int main | ( | int | argc, | 
        
          |  |  | char * | argv[] | 
        
          |  | ) |  |  | 
      
 
 
      
        
          | static double now | ( |  | ) |  [inline, static] | 
      
 
 
      
        
          | bool resetMotorsService | ( | std_srvs::Empty::Request & | req, | 
        
          |  |  | std_srvs::Empty::Response & | resp | 
        
          |  | ) |  |  | 
      
 
 
      
        
          | static void timespecInc | ( | struct timespec & | tick, | 
        
          |  |  | int | nsec | 
        
          |  | ) |  |  [static] | 
      
 
 
      
        
          | void Usage | ( | string | msg = "" | ) |  | 
      
 
 
Variable Documentation
      
        
          | const std::string name = "pr2_ethercat"  [static] | 
      
 
 
      
        
          | const char* PIDDIR = "/var/tmp/run/"  [static] |