$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #include <stdio.h> 00036 #include <getopt.h> 00037 #include <execinfo.h> 00038 #include <signal.h> 00039 #include <sys/mman.h> 00040 #include <sys/types.h> 00041 #include <sys/stat.h> 00042 #include <unistd.h> 00043 #include <fcntl.h> 00044 #include <pthread.h> 00045 00046 #include <diagnostic_updater/DiagnosticStatusWrapper.h> 00047 #include <pr2_controller_manager/controller_manager.h> 00048 #include <ethercat_hardware/ethercat_hardware.h> 00049 00050 #include <ros/ros.h> 00051 #include <std_srvs/Empty.h> 00052 00053 #include <realtime_tools/realtime_publisher.h> 00054 #include <std_msgs/Float64.h> 00055 00056 #include <boost/accumulators/accumulators.hpp> 00057 #include <boost/accumulators/statistics/stats.hpp> 00058 #include <boost/accumulators/statistics/max.hpp> 00059 #include <boost/accumulators/statistics/mean.hpp> 00060 using namespace boost::accumulators; 00061 00062 static const std::string name = "pr2_etherCAT"; 00063 00064 00065 static struct 00066 { 00067 char *program_; 00068 char *interface_; 00069 char *xml_; 00070 bool allow_unprogrammed_; 00071 bool stats_; 00072 } g_options; 00073 00074 std::string g_robot_desc; 00075 00076 void Usage(string msg = "") 00077 { 00078 fprintf(stderr, "Usage: %s [options]\n", g_options.program_); 00079 fprintf(stderr, " Available options\n"); 00080 fprintf(stderr, " -i, --interface <interface> Connect to EtherCAT devices on this interface\n"); 00081 fprintf(stderr, " -s, --stats Publish statistics on the RT loop jitter on \"pr2_etherCAT/realtime\" in seconds\n"); 00082 fprintf(stderr, " -x, --xml <file|param> Load the robot description from this file or parameter name\n"); 00083 fprintf(stderr, " -u, --allow_unprogrammed Allow control loop to run with unprogrammed devices\n"); 00084 fprintf(stderr, " -h, --help Print this message and exit\n"); 00085 if (msg != "") 00086 { 00087 fprintf(stderr, "Error: %s\n", msg.c_str()); 00088 exit(-1); 00089 } 00090 else 00091 { 00092 exit(0); 00093 } 00094 } 00095 00096 static int g_quit = 0; 00097 static bool g_reset_motors = true; 00098 static bool g_halt_motors = false; 00099 static bool g_halt_requested = false; 00100 static volatile bool g_publish_trace_requested = false; 00101 static const int NSEC_PER_SECOND = 1e+9; 00102 static const int USEC_PER_SECOND = 1e6; 00103 00104 static struct 00105 { 00106 accumulator_set<double, stats<tag::max, tag::mean> > ec_acc; 00107 accumulator_set<double, stats<tag::max, tag::mean> > cm_acc; 00108 accumulator_set<double, stats<tag::max, tag::mean> > loop_acc; 00109 accumulator_set<double, stats<tag::max, tag::mean> > jitter_acc; 00110 int overruns; 00111 int recent_overruns; 00112 int last_overrun; 00113 int last_severe_overrun; 00114 double overrun_loop_sec; 00115 double overrun_ec; 00116 double overrun_cm; 00117 00118 // These values are set when realtime loop does not meet performace expections 00119 bool rt_loop_not_making_timing; 00120 double halt_rt_loop_frequency; 00121 double rt_loop_frequency; 00122 } g_stats; 00123 00124 static void publishDiagnostics(realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticArray> &publisher) 00125 { 00126 if (publisher.trylock()) 00127 { 00128 accumulator_set<double, stats<tag::max, tag::mean> > zero; 00129 vector<diagnostic_msgs::DiagnosticStatus> statuses; 00130 diagnostic_updater::DiagnosticStatusWrapper status; 00131 00132 static double max_ec = 0, max_cm = 0, max_loop = 0, max_jitter = 0; 00133 double avg_ec, avg_cm, avg_loop, avg_jitter; 00134 00135 avg_ec = extract_result<tag::mean>(g_stats.ec_acc); 00136 avg_cm = extract_result<tag::mean>(g_stats.cm_acc); 00137 avg_loop = extract_result<tag::mean>(g_stats.loop_acc); 00138 max_ec = std::max(max_ec, extract_result<tag::max>(g_stats.ec_acc)); 00139 max_cm = std::max(max_cm, extract_result<tag::max>(g_stats.cm_acc)); 00140 max_loop = std::max(max_loop, extract_result<tag::max>(g_stats.loop_acc)); 00141 g_stats.ec_acc = zero; 00142 g_stats.cm_acc = zero; 00143 g_stats.loop_acc = zero; 00144 00145 // Publish average loop jitter 00146 avg_jitter = extract_result<tag::mean>(g_stats.jitter_acc); 00147 max_jitter = std::max(max_jitter, extract_result<tag::max>(g_stats.jitter_acc)); 00148 g_stats.jitter_acc = zero; 00149 00150 static bool first = true; 00151 if (first) 00152 { 00153 first = false; 00154 status.add("Robot Description", g_robot_desc); 00155 } 00156 00157 status.addf("Max EtherCAT roundtrip (us)", "%.2f", max_ec*USEC_PER_SECOND); 00158 status.addf("Avg EtherCAT roundtrip (us)", "%.2f", avg_ec*USEC_PER_SECOND); 00159 status.addf("Max Controller Manager roundtrip (us)", "%.2f", max_cm*USEC_PER_SECOND); 00160 status.addf("Avg Controller Manager roundtrip (us)", "%.2f", avg_cm*USEC_PER_SECOND); 00161 status.addf("Max Total Loop roundtrip (us)", "%.2f", max_loop*USEC_PER_SECOND); 00162 status.addf("Avg Total Loop roundtrip (us)", "%.2f", avg_loop*USEC_PER_SECOND); 00163 status.addf("Max Loop Jitter (us)", "%.2f", max_jitter * USEC_PER_SECOND); 00164 status.addf("Avg Loop Jitter (us)", "%.2f", avg_jitter * USEC_PER_SECOND); 00165 status.addf("Control Loop Overruns", "%d", g_stats.overruns); 00166 status.addf("Recent Control Loop Overruns", "%d", g_stats.recent_overruns); 00167 status.addf("Last Control Loop Overrun Cause", "ec: %.2fus, cm: %.2fus", 00168 g_stats.overrun_ec*USEC_PER_SECOND, g_stats.overrun_cm*USEC_PER_SECOND); 00169 status.addf("Last Overrun Loop Time (us)", "%.2f", g_stats.overrun_loop_sec * USEC_PER_SECOND); 00170 status.addf("Realtime Loop Frequency", "%.4f", g_stats.rt_loop_frequency); 00171 00172 status.name = "Realtime Control Loop"; 00173 if (g_stats.overruns > 0 && g_stats.last_overrun < 30) 00174 { 00175 if (g_stats.last_severe_overrun < 30) 00176 status.level = 1; 00177 else 00178 status.level = 0; 00179 status.message = "Realtime loop used too much time in the last 30 seconds."; 00180 } 00181 else 00182 { 00183 status.level = 0; 00184 status.message = "OK"; 00185 } 00186 g_stats.recent_overruns = 0; 00187 g_stats.last_overrun++; 00188 g_stats.last_severe_overrun++; 00189 00190 if (g_stats.rt_loop_not_making_timing) 00191 { 00192 status.mergeSummaryf(status.ERROR, "Halting, realtime loop only ran at %.4f Hz", g_stats.halt_rt_loop_frequency); 00193 } 00194 00195 statuses.push_back(status); 00196 publisher.msg_.status = statuses; 00197 publisher.msg_.header.stamp = ros::Time::now(); 00198 publisher.unlockAndPublish(); 00199 } 00200 } 00201 00202 static inline double now() 00203 { 00204 struct timespec n; 00205 clock_gettime(CLOCK_MONOTONIC, &n); 00206 return double(n.tv_nsec) / NSEC_PER_SECOND + n.tv_sec; 00207 } 00208 00209 00210 void *diagnosticLoop(void *args) 00211 { 00212 EthercatHardware *ec((EthercatHardware *) args); 00213 struct timespec tick; 00214 clock_gettime(CLOCK_MONOTONIC, &tick); 00215 while (!g_quit) { 00216 ec->collectDiagnostics(); 00217 tick.tv_sec += 1; 00218 clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &tick, NULL); 00219 } 00220 return NULL; 00221 } 00222 00223 static void timespecInc(struct timespec &tick, int nsec) 00224 { 00225 tick.tv_nsec += nsec; 00226 while (tick.tv_nsec >= NSEC_PER_SECOND) 00227 { 00228 tick.tv_nsec -= NSEC_PER_SECOND; 00229 tick.tv_sec++; 00230 } 00231 } 00232 00233 00234 class RTLoopHistory 00235 { 00236 public: 00237 RTLoopHistory(unsigned length, double default_value) : 00238 index_(0), 00239 length_(length), 00240 history_(new double[length]) 00241 { 00242 for (unsigned i=0; i<length_; ++i) 00243 history_[i] = default_value; 00244 } 00245 00246 ~RTLoopHistory() 00247 { 00248 delete[] history_; 00249 history_ = NULL; 00250 } 00251 00252 void sample(double value) 00253 { 00254 index_ = (index_+1) % length_; 00255 history_[index_] = value; 00256 } 00257 00258 double average() const 00259 { 00260 double sum(0.0); 00261 for (unsigned i=0; i<length_; ++i) 00262 sum+=history_[i]; 00263 return sum / double(length_); 00264 } 00265 00266 protected: 00267 unsigned index_; 00268 unsigned length_; 00269 double *history_; 00270 }; 00271 00272 00273 void *controlLoop(void *) 00274 { 00275 int rv = 0; 00276 double last_published, last_loop_start; 00277 int period; 00278 int policy; 00279 TiXmlElement *root; 00280 TiXmlElement *root_element; 00281 00282 ros::NodeHandle node(name); 00283 00284 realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticArray> publisher(node, "/diagnostics", 2); 00285 realtime_tools::RealtimePublisher<std_msgs::Float64> *rtpublisher = 0; 00286 00287 // Realtime loop should be running at least 750Hz 00288 // Calculate realtime loop frequency every 200mseec 00289 // Halt motors if average frequency over last 600msec is less than 750Hz 00290 double min_acceptable_rt_loop_frequency; 00291 if (!node.getParam("min_acceptable_rt_loop_frequency", min_acceptable_rt_loop_frequency)) 00292 { 00293 min_acceptable_rt_loop_frequency = 750.0; 00294 } 00295 else 00296 { 00297 ROS_WARN("min_acceptable_rt_loop_frequency changed to %f", min_acceptable_rt_loop_frequency); 00298 } 00299 unsigned rt_cycle_count = 0; 00300 double last_rt_monitor_time; 00301 double rt_loop_monitor_period = 0.6 / 3; 00302 // Keep history of last 3 calculation intervals. 00303 RTLoopHistory rt_loop_history(3, 1000.0); 00304 00305 if (g_options.stats_){ 00306 rtpublisher = new realtime_tools::RealtimePublisher<std_msgs::Float64>(node, "realtime", 2); 00307 } 00308 00309 // Initialize the hardware interface 00310 EthercatHardware ec(name); 00311 ec.init(g_options.interface_, g_options.allow_unprogrammed_); 00312 00313 // Create controller manager 00314 pr2_controller_manager::ControllerManager cm(ec.hw_); 00315 00316 // Load robot description 00317 TiXmlDocument xml; 00318 struct stat st; 00319 if (0 == stat(g_options.xml_, &st)) 00320 { 00321 xml.LoadFile(g_options.xml_); 00322 } 00323 else 00324 { 00325 ROS_INFO("Xml file not found, reading from parameter server"); 00326 ros::NodeHandle top_level_node; 00327 if (top_level_node.getParam(g_options.xml_, g_robot_desc)) 00328 xml.Parse(g_robot_desc.c_str()); 00329 else 00330 { 00331 ROS_FATAL("Could not load the xml from parameter server: %s", g_options.xml_); 00332 rv = -1; 00333 goto end; 00334 } 00335 } 00336 root_element = xml.RootElement(); 00337 root = xml.FirstChildElement("robot"); 00338 if (!root || !root_element) 00339 { 00340 ROS_FATAL("Could not parse the xml from %s", g_options.xml_); 00341 rv = -1; 00342 goto end; 00343 } 00344 00345 // Initialize the controller manager from robot description 00346 if (!cm.initXml(root)) 00347 { 00348 ROS_FATAL("Could not initialize the controller manager"); 00349 rv = -1; 00350 goto end; 00351 } 00352 00353 // Publish one-time before entering real-time to pre-allocate message vectors 00354 publishDiagnostics(publisher); 00355 00356 //Start Non-realtime diagonostic thread 00357 static pthread_t diagnosticThread; 00358 if ((rv = pthread_create(&diagnosticThread, NULL, diagnosticLoop, &ec)) != 0) 00359 { 00360 ROS_FATAL("Unable to create control thread: rv = %d", rv); 00361 goto end; 00362 } 00363 00364 // Set to realtime scheduler for this thread 00365 struct sched_param thread_param; 00366 policy = SCHED_FIFO; 00367 thread_param.sched_priority = sched_get_priority_max(policy); 00368 pthread_setschedparam(pthread_self(), policy, &thread_param); 00369 00370 struct timespec tick; 00371 clock_gettime(CLOCK_REALTIME, &tick); 00372 period = 1e+6; // 1 ms in nanoseconds 00373 00374 // Snap to the nearest second 00375 tick.tv_sec = tick.tv_sec; 00376 tick.tv_nsec = (tick.tv_nsec / period + 1) * period; 00377 clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL); 00378 00379 last_published = now(); 00380 last_rt_monitor_time = now(); 00381 last_loop_start = now(); 00382 while (!g_quit) 00383 { 00384 // Track how long the actual loop takes 00385 double this_loop_start = now(); 00386 g_stats.loop_acc(this_loop_start - last_loop_start); 00387 last_loop_start = this_loop_start; 00388 00389 double start = now(); 00390 if (g_reset_motors) 00391 { 00392 ec.update(true, g_halt_motors); 00393 g_reset_motors = false; 00394 // Also, clear error flags when motor reset is requested 00395 g_stats.rt_loop_not_making_timing = false; 00396 } 00397 else 00398 { 00399 ec.update(false, g_halt_motors); 00400 } 00401 if (g_publish_trace_requested) 00402 { 00403 g_publish_trace_requested = false; 00404 ec.publishTrace(-1,"",0,0); 00405 } 00406 g_halt_motors = false; 00407 double after_ec = now(); 00408 cm.update(); 00409 double end = now(); 00410 00411 g_stats.ec_acc(after_ec - start); 00412 g_stats.cm_acc(end - after_ec); 00413 00414 if ((end - last_published) > 1.0) 00415 { 00416 publishDiagnostics(publisher); 00417 last_published = end; 00418 } 00419 00420 // Realtime loop should run about 1000Hz. 00421 // Missing timing on a control cycles usually causes a controller glitch and actuators to jerk. 00422 // When realtime loop misses a lot of cycles controllers will perform poorly and may cause robot to shake. 00423 // Halt motors if realtime loop does not run enough cycles over a given period. 00424 ++rt_cycle_count; 00425 if ((start - last_rt_monitor_time) > rt_loop_monitor_period) 00426 { 00427 // Calculate new average rt loop frequency 00428 double rt_loop_frequency = double(rt_cycle_count) / rt_loop_monitor_period; 00429 00430 // Use last X samples of frequency when deciding whether or not to halt 00431 rt_loop_history.sample(rt_loop_frequency); 00432 double avg_rt_loop_frequency = rt_loop_history.average(); 00433 if (avg_rt_loop_frequency < min_acceptable_rt_loop_frequency) 00434 { 00435 g_halt_motors = true; 00436 if (!g_stats.rt_loop_not_making_timing) 00437 { 00438 // Only update this value if motors when this first occurs (used for diagnostics error message) 00439 g_stats.halt_rt_loop_frequency = avg_rt_loop_frequency; 00440 } 00441 g_stats.rt_loop_not_making_timing = true; 00442 } 00443 g_stats.rt_loop_frequency = avg_rt_loop_frequency; 00444 rt_cycle_count = 0; 00445 last_rt_monitor_time = start; 00446 } 00447 00448 // Compute end of next period 00449 timespecInc(tick, period); 00450 00451 struct timespec before; 00452 clock_gettime(CLOCK_REALTIME, &before); 00453 if ((before.tv_sec + double(before.tv_nsec)/NSEC_PER_SECOND) > (tick.tv_sec + double(tick.tv_nsec)/NSEC_PER_SECOND)) 00454 { 00455 // Total amount of time the loop took to run 00456 g_stats.overrun_loop_sec = (before.tv_sec + double(before.tv_nsec)/NSEC_PER_SECOND) - 00457 (tick.tv_sec + double(tick.tv_nsec)/NSEC_PER_SECOND); 00458 00459 // We overran, snap to next "period" 00460 tick.tv_sec = before.tv_sec; 00461 tick.tv_nsec = (before.tv_nsec / period) * period; 00462 timespecInc(tick, period); 00463 00464 // initialize overruns 00465 if (g_stats.overruns == 0){ 00466 g_stats.last_overrun = 1000; 00467 g_stats.last_severe_overrun = 1000; 00468 } 00469 // check for overruns 00470 if (g_stats.recent_overruns > 10) 00471 g_stats.last_severe_overrun = 0; 00472 g_stats.last_overrun = 0; 00473 00474 g_stats.overruns++; 00475 g_stats.recent_overruns++; 00476 g_stats.overrun_ec = after_ec - start; 00477 g_stats.overrun_cm = end - after_ec; 00478 } 00479 00480 // Sleep until end of period 00481 clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL); 00482 00483 // Calculate RT loop jitter 00484 struct timespec after; 00485 clock_gettime(CLOCK_REALTIME, &after); 00486 double jitter = (after.tv_sec - tick.tv_sec + double(after.tv_nsec-tick.tv_nsec)/NSEC_PER_SECOND); 00487 00488 g_stats.jitter_acc(jitter); 00489 00490 // Publish realtime loops statistics, if requested 00491 if (rtpublisher) 00492 { 00493 if (rtpublisher->trylock()) 00494 { 00495 rtpublisher->msg_.data = jitter; 00496 rtpublisher->unlockAndPublish(); 00497 } 00498 } 00499 00500 // Halt the motors, if requested by a service call 00501 if (g_halt_requested) 00502 { 00503 g_halt_motors = true; 00504 g_halt_requested = false; 00505 } 00506 } 00507 00508 /* Shutdown all of the motors on exit */ 00509 for (pr2_hardware_interface::ActuatorMap::const_iterator it = ec.hw_->actuators_.begin(); it != ec.hw_->actuators_.end(); ++it) 00510 { 00511 it->second->command_.enable_ = false; 00512 it->second->command_.effort_ = 0; 00513 } 00514 ec.update(false, true); 00515 00516 //pthread_join(diagnosticThread, 0); 00517 00518 end: 00519 publisher.stop(); 00520 delete rtpublisher; 00521 00522 ros::shutdown(); 00523 00524 return (void *)rv; 00525 } 00526 00527 void quitRequested(int sig) 00528 { 00529 g_quit = 1; 00530 } 00531 00532 bool resetMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) 00533 { 00534 g_reset_motors = true; 00535 return true; 00536 } 00537 00538 bool haltMotorsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) 00539 { 00540 g_halt_requested = true; 00541 return true; 00542 } 00543 00544 bool publishTraceService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) 00545 { 00546 g_publish_trace_requested = true; 00547 return true; 00548 } 00549 00550 static int 00551 lock_fd(int fd) 00552 { 00553 struct flock lock; 00554 int rv; 00555 00556 lock.l_type = F_WRLCK; 00557 lock.l_whence = SEEK_SET; 00558 lock.l_start = 0; 00559 lock.l_len = 0; 00560 00561 rv = fcntl(fd, F_SETLK, &lock); 00562 return rv; 00563 } 00564 00565 #define PIDDIR "/var/tmp/run/" 00566 #define PIDFILE "pr2_etherCAT.pid" 00567 static int setupPidFile(void) 00568 { 00569 int rv = -1; 00570 pid_t pid; 00571 int fd; 00572 FILE *fp = NULL; 00573 00574 umask(0); 00575 mkdir(PIDDIR, 0777); 00576 fd = open(PIDDIR PIDFILE, O_RDWR | O_CREAT | O_EXCL, S_IWUSR | S_IRUSR | S_IWGRP | S_IRGRP | S_IWOTH | S_IROTH); 00577 if (fd == -1) 00578 { 00579 if (errno != EEXIST) 00580 { 00581 ROS_FATAL("Unable to create pid file '%s': %s", PIDDIR PIDFILE, strerror(errno)); 00582 goto end; 00583 } 00584 00585 if ((fd = open(PIDDIR PIDFILE, O_RDWR)) < 0) 00586 { 00587 ROS_FATAL("Unable to open pid file '%s': %s", PIDDIR PIDFILE, strerror(errno)); 00588 goto end; 00589 } 00590 00591 if ((fp = fdopen(fd, "rw")) == NULL) 00592 { 00593 ROS_FATAL("Can't read from '%s': %s", PIDDIR PIDFILE, strerror(errno)); 00594 goto end; 00595 } 00596 pid = -1; 00597 if ((fscanf(fp, "%d", &pid) != 1) || (pid == getpid()) || (lock_fd(fileno(fp)) == 0)) 00598 { 00599 int rc; 00600 00601 if ((rc = unlink(PIDDIR PIDFILE)) == -1) 00602 { 00603 ROS_FATAL("Can't remove stale pid file '%s': %s", PIDDIR PIDFILE, strerror(errno)); 00604 goto end; 00605 } 00606 } else { 00607 ROS_FATAL("Another instance of pr2_etherCAT is already running with pid: %d", pid); 00608 goto end; 00609 } 00610 } 00611 00612 unlink(PIDDIR PIDFILE); 00613 fd = open(PIDDIR PIDFILE, O_RDWR | O_CREAT | O_EXCL, S_IWUSR | S_IRUSR | S_IWGRP | S_IRGRP | S_IWOTH | S_IROTH); 00614 00615 if (fd == -1) 00616 { 00617 ROS_FATAL("Unable to open pid file '%s': %s", PIDDIR PIDFILE, strerror(errno)); 00618 goto end; 00619 } 00620 00621 if (lock_fd(fd) == -1) 00622 { 00623 ROS_FATAL("Unable to lock pid file '%s': %s", PIDDIR PIDFILE, strerror(errno)); 00624 goto end; 00625 } 00626 00627 if ((fp = fdopen(fd, "w")) == NULL) 00628 { 00629 ROS_FATAL("fdopen failed: %s", strerror(errno)); 00630 goto end; 00631 } 00632 00633 fprintf(fp, "%d\n", getpid()); 00634 00635 /* We do NOT close fd, since we want to keep the lock. */ 00636 fflush(fp); 00637 fcntl(fd, F_SETFD, (long) 1); 00638 rv = 0; 00639 end: 00640 return rv; 00641 } 00642 00643 static void cleanupPidFile(void) 00644 { 00645 unlink(PIDDIR PIDFILE); 00646 } 00647 00648 #define CLOCK_PRIO 0 00649 #define CONTROL_PRIO 0 00650 00651 static pthread_t controlThread; 00652 static pthread_attr_t controlThreadAttr; 00653 int main(int argc, char *argv[]) 00654 { 00655 // Keep the kernel from swapping us out 00656 if (mlockall(MCL_CURRENT | MCL_FUTURE) < 0) { 00657 perror("mlockall"); 00658 return -1; 00659 } 00660 00661 // Setup single instance 00662 if (setupPidFile() < 0) return -1; 00663 00664 // Initialize ROS and parse command-line arguments 00665 ros::init(argc, argv, "realtime_loop"); 00666 00667 // Parse options 00668 g_options.program_ = argv[0]; 00669 while (1) 00670 { 00671 static struct option long_options[] = { 00672 {"help", no_argument, 0, 'h'}, 00673 {"stats", no_argument, 0, 's'}, 00674 {"allow_unprogrammed", no_argument, 0, 'u'}, 00675 {"interface", required_argument, 0, 'i'}, 00676 {"xml", required_argument, 0, 'x'}, 00677 }; 00678 int option_index = 0; 00679 int c = getopt_long(argc, argv, "hi:usx:", long_options, &option_index); 00680 if (c == -1) break; 00681 switch (c) 00682 { 00683 case 'h': 00684 Usage(); 00685 break; 00686 case 'u': 00687 g_options.allow_unprogrammed_ = 1; 00688 break; 00689 case 'i': 00690 g_options.interface_ = optarg; 00691 break; 00692 case 'x': 00693 g_options.xml_ = optarg; 00694 break; 00695 case 's': 00696 g_options.stats_ = 1; 00697 break; 00698 } 00699 } 00700 if (optind < argc) 00701 { 00702 Usage("Extra arguments"); 00703 } 00704 00705 if (!g_options.interface_) 00706 Usage("You must specify a network interface"); 00707 if (!g_options.xml_) 00708 Usage("You must specify a robot description XML file"); 00709 00710 ros::NodeHandle node(name); 00711 00712 // Catch attempts to quit 00713 signal(SIGTERM, quitRequested); 00714 signal(SIGINT, quitRequested); 00715 signal(SIGHUP, quitRequested); 00716 00717 ros::ServiceServer reset = node.advertiseService("reset_motors", resetMotorsService); 00718 ros::ServiceServer halt = node.advertiseService("halt_motors", haltMotorsService); 00719 ros::ServiceServer publishTrace = node.advertiseService("publish_trace", publishTraceService); 00720 00721 //Start thread 00722 int rv; 00723 if ((rv = pthread_create(&controlThread, &controlThreadAttr, controlLoop, 0)) != 0) 00724 { 00725 ROS_FATAL("Unable to create control thread: rv = %d", rv); 00726 exit(EXIT_FAILURE); 00727 } 00728 00729 ros::spin(); 00730 pthread_join(controlThread, (void **)&rv); 00731 00732 // Cleanup pid file 00733 cleanupPidFile(); 00734 00735 return rv; 00736 }