#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.
static void cleanupPidFile |
( |
const char * |
interface | ) |
|
|
static |
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 | ) |
|
|
static |
int main |
( |
int |
argc, |
|
|
char * |
argv[] |
|
) |
| |
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 |
static void timespecInc |
( |
struct timespec & |
tick, |
|
|
int |
nsec |
|
) |
| |
|
static |
void Usage |
( |
string |
msg = "" | ) |
|
accumulator_set<double, stats<tag::max, tag::mean> > cm_acc |
pthread_attr_t controlThreadAttr |
|
static |
accumulator_set<double, stats<tag::max, tag::mean> > ec_acc |
bool g_halt_motors = false |
|
static |
bool g_halt_requested = false |
|
static |
volatile bool g_publish_trace_requested = false |
|
static |
bool g_reset_motors = true |
|
static |
double halt_rt_loop_frequency |
accumulator_set<double, stats<tag::max, tag::mean> > jitter_acc |
accumulator_set<double, stats<tag::max, tag::mean> > loop_acc |
const std::string name = "pr2_ethercat" |
|
static |
const int NSEC_PER_SECOND = 1e+9 |
|
static |
const char* PIDDIR = "/var/tmp/run/" |
|
static |
bool rt_loop_not_making_timing |
const int USEC_PER_SECOND = 1e6 |
|
static |