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  * Modified 2016, by Shadow Robot Company Ltd.
8  * Modified 2017, by Tokyo Opensource Robotics Kyokai Association
9  * Modified 2019, by Kawasaki Heavy Industries, LTD.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the Willow Garage nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *********************************************************************/
38 
39 #include <getopt.h>
40 #include <execinfo.h>
41 #include <csignal>
42 #include <pthread.h>
43 #include <numeric>
44 
45 #include <boost/accumulators/accumulators.hpp>
46 #include <boost/accumulators/statistics/stats.hpp>
47 #include <boost/accumulators/statistics/max.hpp>
48 #include <boost/accumulators/statistics/mean.hpp>
51 #include <diagnostic_msgs/DiagnosticArray.h>
52 #include <string>
53 #include <vector>
54 
57 
58 using boost::accumulators::accumulator_set;
59 using boost::accumulators::stats;
60 using boost::accumulators::extract_result;
61 using boost::accumulators::tag::max;
62 using boost::accumulators::tag::mean;
63 using std::string;
64 using std::vector;
65 using std::accumulate;
67 
68 static struct
69 {
70  char *program_;
71  bool write_;
72  double period_;
73  std::string ip_;
75  std::string robot_;
76 }
77 g_options;
78 
79 void Usage( const string &msg = "" )
80 {
81  fprintf(stderr, "Usage: %s [options]\n", g_options.program_);
82  fprintf(stderr, " Available options\n");
83  fprintf(stderr, " -i, --ip IP address for Controller\n");
84  fprintf(stderr, " -l, --loopback Use loopback interface for Controller (i.e. simulation mode)\n");
85  fprintf(stderr, " -p, --period RT loop period in msec\n");
86  fprintf(stderr, " -v, --viewer Viewing robot through Rviz\n");
87  fprintf(stderr, " -r, --robot Robot name\n");
88  fprintf(stderr, " -h, --help Print this message and exit\n");
89  if ( msg != "" )
90  {
91  fprintf(stderr, "Error: %s\n", msg.c_str());
92  exit(-1);
93  }
94  else
95  {
96  exit(0);
97  }
98 }
99 
100 static int g_quit = 0;
102 static const int SEC_2_NSEC = 1e+9;
103 static const int SEC_2_USEC = 1e+6;
104 static const double PERIOD_SLEEP = 0.1; /* 100msec */
105 static const double PERIOD_DIFF_WEIGHT = 1e-2;
106 
107 static struct
108 {
109  accumulator_set<double, stats<max, mean> > read_acc;
110  accumulator_set<double, stats<max, mean> > write_acc;
111  accumulator_set<double, stats<max, mean> > loop_acc;
112  accumulator_set<double, stats<max, mean> > jitter_acc;
113  int overruns;
114  int recent_overruns; /* overruns during publishing */
115  int last_overrun; /* diagnostics count after last overruns occurred */
116  int last_severe_overrun; /* diagnostics severe count after last overruns occurred */
118  double overrun_read;
120 
121  /* These values are set when realtime loop does not meet performance expectations */
125 }
126 g_stats;
127 
129 {
130  if ( publisher.trylock() )
131  {
132  accumulator_set<double, stats<max, mean> > zero;
133  vector<diagnostic_msgs::DiagnosticStatus> statuses;
135 
136  static double max_read = 0, max_write = 0, max_loop = 0, max_jitter = 0;
137  double avg_read, avg_write, avg_loop, avg_jitter;
138 
139  avg_read = extract_result<mean>(g_stats.read_acc);
140  avg_write = extract_result<mean>(g_stats.write_acc);
141  avg_loop = extract_result<mean>(g_stats.loop_acc);
142  max_read = std::max(max_read, extract_result<max>(g_stats.read_acc));
143  max_write = std::max(max_write, extract_result<max>(g_stats.write_acc));
144  max_loop = std::max(max_loop, extract_result<max>(g_stats.loop_acc));
145  g_stats.read_acc = zero;
146  g_stats.write_acc = zero;
147  g_stats.loop_acc = zero;
148 
149  /* Publish average loop jitter */
150  avg_jitter = extract_result<mean>(g_stats.jitter_acc);
151  max_jitter = std::max(max_jitter, extract_result<max>(g_stats.jitter_acc));
152  g_stats.jitter_acc = zero;
153 
154  status.addf("Max READ roundtrip (us)", "%.2f", max_read * SEC_2_USEC);
155  status.addf("Avg READ roundtrip (us)", "%.2f", avg_read * SEC_2_USEC);
156  status.addf("Max WRITE roundtrip (us)", "%.2f", max_write * SEC_2_USEC);
157  status.addf("Avg WRITE roundtrip (us)", "%.2f", avg_write * SEC_2_USEC);
158  status.addf("Max Total Loop roundtrip (us)", "%.2f", max_loop * SEC_2_USEC);
159  status.addf("Avg Total Loop roundtrip (us)", "%.2f", avg_loop * SEC_2_USEC);
160  status.addf("Max Loop Jitter (us)", "%.2f", max_jitter * SEC_2_USEC);
161  status.addf("Avg Loop Jitter (us)", "%.2f", avg_jitter * SEC_2_USEC);
162  status.addf("Control Loop Overruns", "%d", g_stats.overruns);
163  status.addf("Recent Control Loop Overruns", "%d", g_stats.recent_overruns);
164  status.addf("Last Control Loop Overrun Cause", "READ: %.2fus, WRITE: %.2fus",
165  g_stats.overrun_read*SEC_2_USEC, g_stats.overrun_write * SEC_2_USEC);
166  status.addf("Last Overrun Loop Time (us)", "%.2f", g_stats.overrun_loop_sec * SEC_2_USEC);
167  status.addf("Realtime Loop Frequency", "%.4f", g_stats.rt_loop_frequency);
168 
169  status.name = "Realtime Control Loop";
170  if (g_stats.overruns > 0 && g_stats.last_overrun < 30)
171  {
172  if (g_stats.last_severe_overrun < 30)
173  status.level = 1;
174  else
175  status.level = 0;
176  status.message = "Realtime loop used too much time in the last 30 seconds.";
177  }
178  else
179  {
180  status.level = 0;
181  status.message = "OK";
182  }
183  g_stats.recent_overruns = 0;
184  ++g_stats.last_overrun;
185  ++g_stats.last_severe_overrun;
186 
187  if (g_stats.rt_loop_not_making_timing)
188  status.mergeSummaryf(status.ERROR, "realtime loop only ran at %.4f Hz", g_stats.halt_rt_loop_frequency);
189 
190  statuses.push_back(status);
191  publisher.msg_.status = statuses;
192  publisher.msg_.header.stamp = ros::Time::now();
193  publisher.unlockAndPublish();
194  }
195 }
196 
197 static inline double now()
198 {
199  struct timespec n;
200  clock_gettime( CLOCK_MONOTONIC, &n );
201  return static_cast<double>(n.tv_nsec) / SEC_2_NSEC + n.tv_sec;
202 }
203 
204 static void timespecInc( struct timespec& tick, const int& nsec )
205 {
206  tick.tv_nsec += nsec;
207  if ( tick.tv_nsec > 0 )
208  {
209  while (tick.tv_nsec >= SEC_2_NSEC)
210  {
211  tick.tv_nsec -= SEC_2_NSEC;
212  ++tick.tv_sec;
213  }
214  }
215  else
216  {
217  while (tick.tv_nsec < 0)
218  {
219  tick.tv_nsec += SEC_2_NSEC;
220  --tick.tv_sec;
221  }
222  }
223 }
224 
226 {
227 public:
228  RTLoopHistory(unsigned length, double default_value) :
229  index_(0),
230  length_(length),
231  history_(length, default_value)
232  {
233  }
234 
235  void sample(double value)
236  {
237  index_ = (index_ + 1) % length_;
238  history_[index_] = value;
239  }
240 
241  double average() const
242  {
243  return accumulate(history_.begin(), history_.end(), 0.0) / static_cast<double>(length_);
244  }
245 
246 protected:
247  unsigned index_;
248  unsigned length_;
249  vector<double> history_;
250 };
251 
252 inline bool activate( khi_robot_control::KhiRobotHardwareInterface& robot, struct timespec* tick )
253 {
254  bool ret = true;
255 
256  if ( g_options.write_ )
257  {
258  ret = robot.activate();
259  if ( ret == false )
260  {
261  ROS_ERROR( "Failed to activate KHI robot" );
262  }
263  }
264 
265  clock_gettime( CLOCK_REALTIME, tick );
266 
267  /* Snap to the nearest second */
268  tick->tv_nsec = (tick->tv_nsec / g_options.period_ + 1) * g_options.period_;
269  clock_nanosleep( CLOCK_REALTIME, TIMER_ABSTIME, tick, NULL );
270 
271  last_published = now();
273  last_loop_start = now();
274 
275  return ret;
276 }
277 
278 void quitRequested( int sig )
279 {
280  ROS_WARN( "received signal %d", sig );
281  g_quit = 1;
282 }
283 
284 void *controlLoop( void* )
285 {
286  ros::NodeHandle nh;
287  int state_trigger = khi_robot_control::NONE;
288 
289  /* Catch attempts to quit */
290  signal( SIGTERM, quitRequested );
291  signal( SIGINT, quitRequested );
292  signal( SIGHUP, quitRequested );
293 
294  /* Diagnostics */
295  RealtimePublisher<diagnostic_msgs::DiagnosticArray> publisher( nh, "/diagnostics", 2 );
296 
297  /* Realtime Loop Frequency */
298  const double rt_loop_monitor_period = 0.2; /* Calculate realtime loop frequency every 200msec */
299  const double period_in_secs = 1e+9 * g_options.period_;
300  const double given_frequency = 1 / period_in_secs;
301  double min_acceptable_rt_loop_frequency = 0.75 * given_frequency;
302  if ( nh.getParam("min_acceptable_rt_loop_frequency", min_acceptable_rt_loop_frequency ) )
303  {
304  ROS_WARN("min_acceptable_rt_loop_frequency changed to %f", min_acceptable_rt_loop_frequency);
305  }
306  unsigned rt_cycle_count = 0;
307  RTLoopHistory rt_loop_history( 3, 1000.0 ); /* Keep history of last 3 calculation intervals. */
308 
309  /* Realtime Scheduler */
310  struct sched_param thread_param;
311  int policy = SCHED_FIFO;
312  thread_param.sched_priority = sched_get_priority_max( policy );
313  if ( pthread_setschedparam( pthread_self(), policy, &thread_param ) == 0 )
314  {
315  ROS_INFO( "KHI robot control started. [REALTIME]" );
316  }
317  else
318  {
319  ROS_INFO( "KHI robot control started. [NOT REALTIME]" );
320  }
321 
322  /* Publish one-time before entering real-time to pre-allocate message vectors */
323  publishDiagnostics( publisher );
324 
325  /* Initialization */
326  struct timespec tick;
327  ros::Duration durp( g_options.period_ / 1e+9 );
329  double period_diff = 0;
330  if ( !robot.open( g_options.robot_, g_options.ip_, g_options.period_, g_options.simulation_ ) )
331  {
332  ROS_ERROR( "Failed to open KHI robot" );
333  publisher.stop();
334  robot.close();
335  delete &robot;
336  ros::shutdown();
337  return NULL;
338  }
339 
341 
342  if ( !activate( robot, &tick ) )
343  {
344  publisher.stop();
345  robot.deactivate();
346  robot.close();
347  delete &robot;
348  ros::shutdown();
349  return NULL;
350  }
351 
352  while ( !g_quit )
353  {
354  double this_loop_start = now();
355  g_stats.loop_acc( this_loop_start - last_loop_start );
356  last_loop_start = this_loop_start;
357 
358  double start = now();
359 
360  ros::Time this_moment( tick.tv_sec, tick.tv_nsec );
361  robot.read( this_moment, durp );
362 
363  double after_read = now();
364 
365  cm.update( this_moment, durp );
366  if ( g_options.write_ )
367  {
368  /* Robot State */
369  robot.updateState();
370  state_trigger = robot.getStateTrigger();
371  if ( state_trigger == khi_robot_control::HOLD )
372  {
373  robot.hold();
374  continue;
375  }
376  else if ( state_trigger == khi_robot_control::RESTART )
377  {
378  if ( activate( robot, &tick ) )
379  {
380  ros::Time activate_moment( tick.tv_sec, tick.tv_nsec );
381  robot.read( activate_moment, durp );
382  cm.update( activate_moment, durp, true );
383  }
384  continue;
385  }
386  else if ( state_trigger == khi_robot_control::QUIT )
387  {
388  g_quit = true;
389  continue;
390  }
391 
392  robot.write( this_moment, durp );
393  }
394 
395  /* Cycle Adjustment */
396  if ( robot.getPeriodDiff( period_diff ) )
397  {
398  timespecInc( tick, PERIOD_DIFF_WEIGHT * period_diff );
399  }
400 
401  double end = now();
402 
403  g_stats.read_acc( after_read - start );
404  g_stats.write_acc( end - after_read );
405 
406  if ( ( end - last_published ) > 1.0 )
407  {
408  publishDiagnostics( publisher );
409  last_published = end;
410  }
411 
412  /* Check Realtime Loop Frequency */
413  ++rt_cycle_count;
414  if ( ( start - last_rt_monitor_time ) > rt_loop_monitor_period )
415  {
416  /* Calculate new average rt loop frequency */
417  double rt_loop_frequency = static_cast<double>(rt_cycle_count) / rt_loop_monitor_period;
418 
419  /* Use last X samples of frequency when deciding whether or not to halt */
420  rt_loop_history.sample(rt_loop_frequency);
421  double avg_rt_loop_frequency = rt_loop_history.average();
422  if ( avg_rt_loop_frequency < min_acceptable_rt_loop_frequency )
423  {
424  if ( !g_stats.rt_loop_not_making_timing )
425  {
426  /* Only update this value if motors when this first occurs (used for diagnostics error message) */
427  g_stats.halt_rt_loop_frequency = avg_rt_loop_frequency;
428  }
429  g_stats.rt_loop_not_making_timing = true;
430  }
431  g_stats.rt_loop_frequency = avg_rt_loop_frequency;
432  rt_cycle_count = 0;
434  }
435 
436  /* Compute end of next g_options.period_ */
437  timespecInc( tick, g_options.period_ );
438 
439  /* Check Overrun */
440  struct timespec before;
441  clock_gettime( CLOCK_REALTIME, &before );
442  if ( ( before.tv_sec + static_cast<double>(before.tv_nsec) / SEC_2_NSEC) >
443  ( tick.tv_sec + static_cast<double>(tick.tv_nsec) / SEC_2_NSEC ) )
444  {
445  /* Total amount of time the loop took to run */
446  g_stats.overrun_loop_sec = ( before.tv_sec + static_cast<double>(before.tv_nsec) / SEC_2_NSEC ) -
447  ( tick.tv_sec + static_cast<double>(tick.tv_nsec) / SEC_2_NSEC );
448 
449  /* We overran, snap to next "g_options.period_" */
450  tick.tv_sec = before.tv_sec;
451  tick.tv_nsec = ( before.tv_nsec / g_options.period_ ) * g_options.period_;
452  timespecInc( tick, g_options.period_ );
453 
454  /* Initialize overruns */
455  if ( g_stats.overruns == 0 )
456  {
457  g_stats.last_overrun = 1000;
458  g_stats.last_severe_overrun = 1000;
459  }
460  /* Check for overruns */
461  if ( g_stats.recent_overruns > 10 )
462  {
463  g_stats.last_severe_overrun = 0;
464  }
465  g_stats.last_overrun = 0;
466 
467  ++g_stats.overruns;
468  ++g_stats.recent_overruns;
469  g_stats.overrun_read = after_read - start;
470  g_stats.overrun_write = end - after_read;
471  }
472 
473  /* Sleep until end of g_options.period_ */
474  clock_nanosleep( CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL );
475 
476  /* Check Jitter */
477  struct timespec after;
478  clock_gettime( CLOCK_REALTIME, &after );
479  double jitter = ( after.tv_sec - tick.tv_sec + static_cast<double>(after.tv_nsec - tick.tv_nsec) / SEC_2_NSEC );
480  g_stats.jitter_acc( jitter );
481  }
482  publisher.stop();
483  robot.deactivate();
484  robot.close();
485  delete &robot;
486  ROS_INFO( "KHI robot control ended." );
487  ros::shutdown();
488  return NULL;
489 }
490 
491 static pthread_t controlThread;
492 static pthread_attr_t controlThreadAttr;
493 
494 int main(int argc, char *argv[])
495 {
496  /* Initialize ROS and parse command-line arguments */
497  ros::init( argc, argv, "KhiRobotControl" );
498 
499  /* Options */
500  g_options.program_ = argv[0];
501  g_options.period_ = 4e+6; /* 4ms */
502  g_options.simulation_ = false;
503  g_options.write_ = true;
504 
505  while (true)
506  {
507  static struct option long_options[] =
508  {
509  {"help", no_argument, 0, 'h'},
510  {"interface", required_argument, 0, 'i'},
511  {"loopback", no_argument, 0, 'l'},
512  {"viewer", no_argument, 0, 'v'},
513  {"period", required_argument, 0, 'p'},
514  {"robot", required_argument, 0, 'r'},
515  };
516  int option_index = 0;
517  int c = getopt_long( argc, argv, "hi:lvp:r:", long_options, &option_index );
518  if (c == -1)
519  {
520  break;
521  }
522 
523  switch (c)
524  {
525  case 'h':
526  Usage();
527  break;
528  case 'i':
529  g_options.ip_ = std::string(optarg);
530  break;
531  case 'l':
532  g_options.simulation_ = true;
533  break;
534  case 'v':
535  ROS_INFO( "Viewer mode" );
536  g_options.write_ = false;
537  break;
538  case 'p':
539  /* convert period given in msec to nsec */
540  g_options.period_ = fabs(atof(optarg))*1e+6;
541  break;
542  case 'r':
543  g_options.robot_ = std::string(optarg);
544  break;
545  default:
546  break;
547  }
548  }
549 
550  if ( optind < argc )
551  {
552  Usage( "Extra arguments" );
553  }
554 
555  /* Start controlLoop thread */
556  int rv = pthread_create( &controlThread, &controlThreadAttr, controlLoop, 0 );
557  if ( rv != 0 )
558  {
559  ROS_FATAL( "Unable to create control thread: rv = %d", rv );
560  exit( EXIT_FAILURE );
561  }
562 
563  ros::AsyncSpinner spinner(boost::thread::hardware_concurrency());
564  spinner.start();
565  pthread_join(controlThread, reinterpret_cast<void **>(&rv));
567  return rv;
568 }
569 
rt_loop_frequency
double rt_loop_frequency
Definition: main.cpp:124
controller_manager::ControllerManager
khi_robot_control::KhiRobotHardwareInterface
Definition: khi_robot_hardware_interface.h:80
realtime_publisher.h
loop_acc
accumulator_set< double, stats< max, mean > > loop_acc
Definition: main.cpp:111
msg
msg
last_overrun
int last_overrun
Definition: main.cpp:115
now
static double now()
Definition: main.cpp:197
g_options
static struct @0 g_options
khi_robot_control::KhiRobotHardwareInterface::write
void write(const ros::Time &time, const ros::Duration &period) override
Definition: khi_robot_hardware_interface.cpp:176
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
jitter_acc
accumulator_set< double, stats< max, mean > > jitter_acc
Definition: main.cpp:112
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
khi_robot_control::KhiRobotHardwareInterface::getPeriodDiff
bool getPeriodDiff(double &diff)
Definition: khi_robot_hardware_interface.cpp:192
khi_robot_control::KhiRobotHardwareInterface::updateState
int updateState()
Definition: khi_robot_hardware_interface.cpp:182
last_published
static double last_published
Definition: main.cpp:101
g_stats
static struct @1 g_stats
ros::AsyncSpinner
write_acc
accumulator_set< double, stats< max, mean > > write_acc
Definition: main.cpp:110
RTLoopHistory::average
double average() const
Definition: main.cpp:241
ros::shutdown
ROSCPP_DECL void shutdown()
RTLoopHistory::sample
void sample(double value)
Definition: main.cpp:235
Usage
void Usage(const string &msg="")
Definition: main.cpp:79
PERIOD_DIFF_WEIGHT
static const double PERIOD_DIFF_WEIGHT
Definition: main.cpp:105
khi_robot_hardware_interface.h
khi_robot_control::KhiRobotHardwareInterface::close
void close()
Definition: khi_robot_hardware_interface.cpp:165
overrun_write
double overrun_write
Definition: main.cpp:119
diagnostic_updater::DiagnosticStatusWrapper::mergeSummaryf
void mergeSummaryf(unsigned char lvl, const char *format,...)
timespecInc
static void timespecInc(struct timespec &tick, const int &nsec)
Definition: main.cpp:204
publishDiagnostics
static void publishDiagnostics(RealtimePublisher< diagnostic_msgs::DiagnosticArray > &publisher)
Definition: main.cpp:128
khi_robot_control::KhiRobotHardwareInterface::getStateTrigger
int getStateTrigger()
Definition: khi_robot_hardware_interface.cpp:187
controller_manager.h
khi_robot_control::HOLD
@ HOLD
Definition: khi_robot_driver.h:142
khi_robot_control::KhiRobotHardwareInterface::read
void read(const ros::Time &time, const ros::Duration &period) override
Definition: khi_robot_hardware_interface.cpp:171
spinner
void spinner()
g_quit
static int g_quit
Definition: main.cpp:100
realtime_tools::RealtimePublisher
khi_robot_control::RESTART
@ RESTART
Definition: khi_robot_driver.h:143
khi_robot_control::QUIT
@ QUIT
Definition: khi_robot_driver.h:144
SEC_2_NSEC
static const int SEC_2_NSEC
Definition: main.cpp:102
controlThread
static pthread_t controlThread
Definition: main.cpp:491
khi_robot_control::KhiRobotHardwareInterface::deactivate
void deactivate()
Definition: khi_robot_hardware_interface.cpp:160
SEC_2_USEC
static const int SEC_2_USEC
Definition: main.cpp:103
rt_loop_not_making_timing
bool rt_loop_not_making_timing
Definition: main.cpp:122
realtime_tools::RealtimePublisher::unlockAndPublish
void unlockAndPublish()
write_
bool write_
Definition: main.cpp:71
simulation_
bool simulation_
Definition: main.cpp:74
khi_robot_control::KhiRobotHardwareInterface::activate
bool activate()
Definition: khi_robot_hardware_interface.cpp:149
activate
bool activate(khi_robot_control::KhiRobotHardwareInterface &robot, struct timespec *tick)
Definition: main.cpp:252
realtime_tools::RealtimePublisher::msg_
Msg msg_
realtime_tools::RealtimePublisher::stop
void stop()
DiagnosticStatusWrapper.h
realtime_tools::RealtimePublisher::trylock
bool trylock()
ROS_WARN
#define ROS_WARN(...)
RTLoopHistory
Definition: main.cpp:225
khi_robot_control::KhiRobotHardwareInterface::open
bool open(const std::string &robot_name, const std::string &ip_address, const double &period, const bool in_simulation=false)
Definition: khi_robot_hardware_interface.cpp:83
read_acc
accumulator_set< double, stats< max, mean > > read_acc
Definition: main.cpp:109
period_
double period_
Definition: main.cpp:72
ROS_FATAL
#define ROS_FATAL(...)
overruns
int overruns
Definition: main.cpp:113
RTLoopHistory::index_
unsigned index_
Definition: main.cpp:247
PERIOD_SLEEP
static const double PERIOD_SLEEP
Definition: main.cpp:104
start
ROSCPP_DECL void start()
last_rt_monitor_time
static double last_rt_monitor_time
Definition: main.cpp:101
RTLoopHistory::length_
unsigned length_
Definition: main.cpp:248
program_
char * program_
Definition: main.cpp:70
ros::Time
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
ip_
std::string ip_
Definition: main.cpp:73
ROS_ERROR
#define ROS_ERROR(...)
last_severe_overrun
int last_severe_overrun
Definition: main.cpp:116
default_value
def default_value(type_)
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
controlThreadAttr
static pthread_attr_t controlThreadAttr
Definition: main.cpp:492
khi_robot_control::NONE
@ NONE
Definition: khi_robot_driver.h:141
last_loop_start
static double last_loop_start
Definition: main.cpp:101
diagnostic_updater::DiagnosticStatusWrapper
RTLoopHistory::history_
vector< double > history_
Definition: main.cpp:249
overrun_read
double overrun_read
Definition: main.cpp:118
controlLoop
void * controlLoop(void *)
Definition: main.cpp:284
quitRequested
void quitRequested(int sig)
Definition: main.cpp:278
ROS_INFO
#define ROS_INFO(...)
robot_
std::string robot_
Definition: main.cpp:75
recent_overruns
int recent_overruns
Definition: main.cpp:114
ros::Duration
controller_manager::ControllerManager::update
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
khi_robot_control::KhiRobotHardwareInterface::hold
bool hold()
Definition: khi_robot_hardware_interface.cpp:155
RTLoopHistory::RTLoopHistory
RTLoopHistory(unsigned length, double default_value)
Definition: main.cpp:228
ros::NodeHandle
main
int main(int argc, char *argv[])
Definition: main.cpp:494
overrun_loop_sec
double overrun_loop_sec
Definition: main.cpp:117
ros::Time::now
static Time now()
halt_rt_loop_frequency
double halt_rt_loop_frequency
Definition: main.cpp:123


khi_robot_control
Author(s): nakamichi_d
autogenerated on Sat Oct 21 2023 02:54:50