#include <cstdio>
#include <cstdarg>
#include <getopt.h>
#include <execinfo.h>
#include <csignal>
#include <sys/mman.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <unistd.h>
#include <fcntl.h>
#include <pthread.h>
#include <numeric>
#include "ros_ethercat_model/ros_ethercat.hpp"
#include <controller_manager/controller_manager.h>
#include <std_msgs/Float64.h>
#include <diagnostic_updater/DiagnosticStatusWrapper.h>
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) |
string | generatePIDFilename (const char *interface) |
static int | lock_fd (int fd) |
int | main (int argc, char *argv[]) |
static double | now () |
static void | publishDiagnostics (RealtimePublisher< diagnostic_msgs::DiagnosticArray > &publisher) |
void | quitRequested (int sig) |
static int | setupPidFile (const char *interface) |
static void * | terminate_control (RealtimePublisher< diagnostic_msgs::DiagnosticArray > *publisher, RealtimePublisher< std_msgs::Float64 > *rtpublisher, const char *message, const char *data=NULL) |
static void | timespecInc (struct timespec &tick, int nsec) |
void | Usage (const string &msg="") |
Variables |
static pthread_t | controlThread |
static pthread_attr_t | controlThreadAttr |
struct { |
bool allow_unprogrammed_ |
char * interface_ |
double period |
char * program_ |
char * rosparam_ |
bool stats_ |
} | g_options |
static int | g_quit = 0 |
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 char * | PIDDIR = "/var/tmp/run/" |
static const int | SEC_2_NSEC = 1e+9 |
static const int | SEC_2_USEC = 1e6 |
Define Documentation
Function Documentation
static int lock_fd |
( |
int |
fd | ) |
[static] |
int main |
( |
int |
argc, |
|
|
char * |
argv[] |
|
) |
| |
static double now |
( |
| ) |
[inline, static] |
static void timespecInc |
( |
struct timespec & |
tick, |
|
|
int |
nsec |
|
) |
| [static] |
void Usage |
( |
const string & |
msg = "" | ) |
|
Variable Documentation
const char* PIDDIR = "/var/tmp/run/" [static] |