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


open_controllers_interface
Author(s): Ryohei Ueda , Kei Okada
autogenerated on Thu Aug 27 2015 14:13:45