counterbalance_test_controller.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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 /* Author: Kevin Watts */
00036 
00037 
00038 #include <joint_qualification_controllers/counterbalance_test_controller.h>
00039 #include "pluginlib/class_list_macros.h"
00040 
00041 PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CounterbalanceTestController,
00042                        pr2_controller_interface::Controller)
00043 
00044 using namespace std;
00045 using namespace joint_qualification_controllers;
00046 
00047 CounterbalanceTestController::CounterbalanceTestController() :
00048   lift_dither_(NULL),
00049   flex_dither_(NULL),
00050   lift_controller_(NULL),
00051   flex_controller_(NULL),
00052   robot_(NULL),
00053   initial_time_(0.0),
00054   start_time_(0.0),
00055   cb_data_pub_(NULL)
00056 {
00057   timeout_ = 180;
00058   lift_index_ = 0;
00059   flex_index_ = 0;
00060   data_sent_ = false;
00061 
00062   cb_test_data_.arg_name.resize(25);
00063   cb_test_data_.arg_value.resize(25);
00064   cb_test_data_.arg_name[0] = "Settle Time";
00065   cb_test_data_.arg_name[1] = "Dither Points";
00066   cb_test_data_.arg_name[2] = "Timeout";
00067   cb_test_data_.arg_name[3] = "Lift Min";
00068   cb_test_data_.arg_name[4] = "Lift Max";
00069   cb_test_data_.arg_name[5] = "Lift Delta";
00070   cb_test_data_.arg_name[6] = "Flex Min";
00071   cb_test_data_.arg_name[7] = "Flex Max";
00072   cb_test_data_.arg_name[8] = "Flex Delta";
00073 
00074   // P/F params
00075   cb_test_data_.arg_name[9] = "Lift MSE";
00076   cb_test_data_.arg_name[10] = "Lift Avg Abs";
00077   cb_test_data_.arg_name[11] = "Lift Avg Effort";
00078   cb_test_data_.arg_name[12] = "Flex MSE";
00079   cb_test_data_.arg_name[13] = "Flex Avg Abs";
00080   cb_test_data_.arg_name[14] = "Flex Avg Effort";
00081 
00082   // PID's
00083   cb_test_data_.arg_name[15] = "Lift P";
00084   cb_test_data_.arg_name[16] = "Lift I";
00085   cb_test_data_.arg_name[17] = "Lift D";
00086   cb_test_data_.arg_name[18] = "Lift I Clamp";
00087 
00088   cb_test_data_.arg_name[19] = "Flex P";
00089   cb_test_data_.arg_name[20] = "Flex I";
00090   cb_test_data_.arg_name[21] = "Flex D";
00091   cb_test_data_.arg_name[22] = "Flex I Clamp";
00092 
00093   cb_test_data_.arg_name[23] = "Screw Tolerance";
00094   cb_test_data_.arg_name[24] = "Bar Tolerance";
00095 
00096   cb_test_data_.timeout_hit = false;
00097   cb_test_data_.lift_joint = "None";
00098   cb_test_data_.lift_joint = "";
00099   cb_test_data_.lift_amplitude = 0;
00100   cb_test_data_.flex_amplitude = 0;
00101 
00103 
00104   state_ = STARTING;
00105 
00106 }
00107 
00108 CounterbalanceTestController::~CounterbalanceTestController()
00109 {
00110   if (lift_controller_) delete lift_controller_;
00111   if (flex_controller_) delete flex_controller_;
00112   if (flex_dither_) delete flex_dither_;
00113   if (lift_dither_) delete lift_dither_;
00114 }
00115 
00116 bool CounterbalanceTestController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00117 {
00118   ROS_ASSERT(robot);
00119   robot_ = robot;
00120 
00121   // Lift joint
00122   string lift_joint;
00123   if (!n.getParam("lift/joint", lift_joint)){
00124     ROS_ERROR("CounterbalanceTestController: No lift joint name found on parameter namespace: %s)",
00125               n.getNamespace().c_str());
00126     return false;
00127   }
00128   if (!(lift_state_ = robot->getJointState(lift_joint)))
00129   {
00130     ROS_ERROR("CounterbalanceTestController could not find lift joint named \"%s\"\n", lift_joint.c_str());
00131     return false;
00132   }
00133   cb_test_data_.lift_joint = lift_joint;
00134 
00135   lift_controller_ = new controller::JointPositionController();
00136   ros::NodeHandle n_lift(n, "lift");
00137   if (!lift_controller_->init(robot, n_lift)) return false;
00138 
00139   int num_flexs = 1;
00140   double flex_min = 0;
00141   double flex_max = 0;
00142   double flex_delta = 0;
00143   double flex_mse = 0;
00144   double flex_avg_abs = 0;
00145   double flex_avg_eff = 0;
00146 
00147   cb_test_data_.flex_test = false;
00148 
00149   // Flex joint
00150   string flex_joint;
00151   if (n.getParam("flex/joint", flex_joint))
00152   {
00153     cb_test_data_.flex_test = true;
00154 
00155     if (!(flex_state_ = robot->getJointState(flex_joint)))
00156     {
00157       ROS_ERROR("CounterbalanceTestController could not find flex joint named \"%s\"\n", flex_joint.c_str());
00158       return false;
00159     }
00160     cb_test_data_.flex_joint = flex_joint;
00161 
00162     // Flex range
00163     if (!n.getParam("flex/min", flex_min))
00164     {
00165       ROS_ERROR("CounterbalanceTestController: No min flex position found on parameter namespace: %s)",
00166                 n.getNamespace().c_str());
00167       return false;
00168     }
00169     if (!n.getParam("flex/max", flex_max))
00170     {
00171       ROS_ERROR("CounterbalanceTestController: No max flex position found on parameter namespace: %s)",
00172                 n.getNamespace().c_str());
00173       return false;
00174     }
00175     if (!n.getParam("flex/delta", flex_delta))
00176     {
00177     ROS_ERROR("CounterbalanceTestController: No flex delta found on parameter namespace: %s)",
00178               n.getNamespace().c_str());
00179     return false;
00180     }
00181 
00182     if (flex_max < flex_min)
00183     {
00184       ROS_ERROR("CounterbalanceTestController: Flex max position must be >= flex min position");
00185       return false;
00186     }
00187     if (flex_delta < 0)
00188     {
00189       ROS_ERROR("CounterbalanceTestController: \"flex_delta\" parameter must be >=0");
00190       return false;
00191     }
00192 
00193     num_flexs = (int)(((flex_max - flex_min) / flex_delta) + 1);
00194 
00195     // MSE, Avg. Abs. Effort
00196     if (!n.getParam("flex/mse", flex_mse))
00197     {
00198       ROS_ERROR("CounterbalanceTestController: No flex/mse (mean square effort) found on parameter namespace: %s)",
00199                 n.getNamespace().c_str());
00200       return false;
00201     }
00202     
00203     if (!n.getParam("flex/avg_abs", flex_avg_abs))
00204     {
00205       ROS_ERROR("CounterbalanceTestController: No flex/avg_abs (average absolute effort) found on parameter namespace: %s)",
00206                 n.getNamespace().c_str());
00207       return false;
00208     }
00209 
00210     if (!n.getParam("flex/avg_eff", flex_avg_eff))
00211     {
00212       ROS_ERROR("CounterbalanceTestController: No flex/avg_eff (average absolute effort) found on parameter namespace: %s)",
00213                 n.getNamespace().c_str());
00214       return false;
00215     }
00216 
00217     double flex_amplitude;
00218     if (!n.getParam("flex/dither", flex_amplitude))
00219     {
00220       ROS_ERROR("CounterbalanceTestController: No flex amplitude found on parameter namespace: %s)",
00221                 n.getNamespace().c_str());
00222       return false;
00223     }
00224     flex_dither_ = new control_toolbox::Dither; 
00225     if (!flex_dither_->init(flex_amplitude, 100)) return false;
00226 
00227     cb_test_data_.flex_amplitude = flex_amplitude;
00228 
00229     flex_controller_ = new controller::JointPositionController();
00230     ros::NodeHandle n_flex(n, "flex");
00231     if (!flex_controller_->init(robot, n_flex)) return false;
00232 
00233     ROS_INFO("Initializing CounterbalanceTestController as a lift and flex test. Namespace: %s", 
00234              n.getNamespace().c_str());
00235   }
00236   else
00237   {
00238     ROS_INFO("Initializing CounterbalanceTestController as a shoulder lift test only. Namespace: %s",
00239              n.getNamespace().c_str());
00240   }
00241 
00242   double lift_amplitude;
00243   if (!n.getParam("lift/dither", lift_amplitude))
00244   {
00245     ROS_ERROR("CounterbalanceTestController: No lift amplitude found on parameter namespace: %s)",
00246               n.getNamespace().c_str());
00247     return false;
00248   }
00249   lift_dither_ = new control_toolbox::Dither; 
00250   if (!lift_dither_->init(lift_amplitude, 100)) return false;
00251 
00252   cb_test_data_.lift_amplitude = lift_amplitude;
00253 
00254   // Lift range
00255   double lift_min, lift_max, lift_delta;
00256   if (!n.getParam("lift/min", lift_min))
00257   {
00258     ROS_ERROR("CounterbalanceTestController: No min lift position found on parameter namespace: %s)",
00259               n.getNamespace().c_str());
00260     return false;
00261   }
00262   if (!n.getParam("lift/max", lift_max))
00263   {
00264     ROS_ERROR("CounterbalanceTestController: No max lift position found on parameter namespace: %s)",
00265               n.getNamespace().c_str());
00266     return false;
00267   }
00268   if (lift_max < lift_min)
00269   {
00270     ROS_ERROR("CounterbalanceTestController was given a shoulder lift maximum with values less than its minimum. Max: %f, Min %f", lift_max, lift_min);
00271     return false;
00272   }
00273 
00274   if (!n.getParam("lift/delta", lift_delta))
00275   {
00276     ROS_ERROR("CounterbalanceTestController: No lift delta found on parameter namespace: %s)",
00277               n.getNamespace().c_str());
00278     return false;
00279   }
00280   if (lift_delta < 0)
00281   {
00282     ROS_ERROR("CounterbalanceTestController was given a shoulder lift position delta <0. Delta given: %f", lift_delta);
00283     return false;
00284   }
00285 
00286   // Setting controller defaults
00287   if (!n.getParam("settle_time", settle_time_))
00288   {
00289     ROS_ERROR("CounterbalanceTestController: No settle time found on parameter namespace: %s)",
00290               n.getNamespace().c_str());
00291     return false;
00292   }
00293 
00294   if (!n.getParam("dither_points", dither_points_))
00295   {
00296     ROS_ERROR("CounterbalanceTestController: No dither points param found on parameter namespace: %s)",
00297               n.getNamespace().c_str());
00298     return false;
00299   }
00300 
00301   if (!n.getParam("timeout", timeout_))
00302   {
00303     ROS_ERROR("CounterbalanceTestController: No timeout found on parameter namespace: %s)",
00304               n.getNamespace().c_str());
00305     return false;
00306   }
00307 
00308   double lift_mse, lift_avg_abs, lift_avg_eff;
00309   if (!n.getParam("lift/mse", lift_mse))
00310   {
00311     ROS_ERROR("CounterbalanceTestController: No lift/mse (mean square effort) found on parameter namespace: %s)",
00312               n.getNamespace().c_str());
00313     return false;
00314   }
00315 
00316   if (!n.getParam("lift/avg_abs", lift_avg_abs))
00317   {
00318     ROS_ERROR("CounterbalanceTestController: No lift/avg_abs (average absolute effort) found on parameter namespace: %s)",
00319               n.getNamespace().c_str());
00320     return false;
00321   }
00322 
00323   if (!n.getParam("lift/avg_eff", lift_avg_eff))
00324   {
00325     ROS_ERROR("CounterbalanceTestController: No lift/avg_eff (average absolute effort) found on parameter namespace: %s)",
00326               n.getNamespace().c_str());
00327     return false;
00328   }
00329 
00330   // Set up array of lift, flex commands
00331   int num_lifts = 1;
00332   if (lift_delta > 0)
00333     num_lifts = (int)((lift_max - lift_min)/lift_delta + 1);
00334   ROS_ASSERT(num_lifts > 0);
00335 
00336   cb_test_data_.lift_data.resize(num_lifts);
00337   for (int i = 0; i < num_lifts; ++i)
00338   {
00339     cb_test_data_.lift_data[i].lift_position = (double)lift_min + lift_delta * i;
00340     cb_test_data_.lift_data[i].flex_data.resize(num_flexs);
00341     for (int j = 0; j < num_flexs; ++j)
00342     {
00343       cb_test_data_.lift_data[i].flex_data[j].flex_position = (double)flex_min + flex_delta * ((double)j);
00344 
00345       cb_test_data_.lift_data[i].flex_data[j].lift_hold.time.resize(dither_points_);
00346       cb_test_data_.lift_data[i].flex_data[j].lift_hold.position.resize(dither_points_);
00347       cb_test_data_.lift_data[i].flex_data[j].lift_hold.velocity.resize(dither_points_);
00348       cb_test_data_.lift_data[i].flex_data[j].lift_hold.effort.resize(dither_points_);
00349 
00350       cb_test_data_.lift_data[i].flex_data[j].flex_hold.time.resize(dither_points_);
00351       cb_test_data_.lift_data[i].flex_data[j].flex_hold.position.resize(dither_points_);
00352       cb_test_data_.lift_data[i].flex_data[j].flex_hold.velocity.resize(dither_points_);
00353       cb_test_data_.lift_data[i].flex_data[j].flex_hold.effort.resize(dither_points_);
00354     }
00355   }
00356 
00357   cb_test_data_.arg_value[0] = settle_time_;
00358   cb_test_data_.arg_value[1] = dither_points_;
00359   cb_test_data_.arg_value[2] = timeout_;
00360   cb_test_data_.arg_value[3] = lift_min;
00361   cb_test_data_.arg_value[4] = lift_max;
00362   cb_test_data_.arg_value[5] = lift_delta;
00363   cb_test_data_.arg_value[6] = flex_min;
00364   cb_test_data_.arg_value[7] = flex_max;
00365   cb_test_data_.arg_value[8] = flex_delta;
00366 
00367   // Mean square efforts, avg abs efforts
00368   cb_test_data_.arg_value[9] = lift_mse;
00369   cb_test_data_.arg_value[10] = lift_avg_abs;
00370   cb_test_data_.arg_value[11] = lift_avg_eff;
00371 
00372   if (cb_test_data_.flex_test)
00373   {
00374     cb_test_data_.arg_value[12] = flex_mse;
00375     cb_test_data_.arg_value[13] = flex_avg_abs;
00376     cb_test_data_.arg_value[14] = flex_avg_eff;
00377   }
00378   else
00379   {
00380     cb_test_data_.arg_value[12] = 0;
00381     cb_test_data_.arg_value[13] = 0;
00382     cb_test_data_.arg_value[14] = 0;
00383   }
00384 
00385   double p, i, d, i_clamp, dummy;
00386   lift_controller_->getGains(p, i, d, i_clamp, dummy);
00387   cb_test_data_.arg_value[15] = p;
00388   cb_test_data_.arg_value[16] = i;
00389   cb_test_data_.arg_value[17] = d;
00390   cb_test_data_.arg_value[18] = i_clamp;
00391 
00392   if (cb_test_data_.flex_test)
00393   {
00394     flex_controller_->getGains(p, i, d, i_clamp, dummy);
00395     cb_test_data_.arg_value[19] = p;
00396     cb_test_data_.arg_value[20] = i;
00397     cb_test_data_.arg_value[21] = d;
00398     cb_test_data_.arg_value[22] = i_clamp;
00399   }
00400   else
00401   {
00402     cb_test_data_.arg_value[19] = 0;
00403     cb_test_data_.arg_value[20] = 0;
00404     cb_test_data_.arg_value[21] = 0;
00405     cb_test_data_.arg_value[22] = 0;
00406   }
00407 
00408   // Record screw, bar tolerances
00409   double screw_tol, bar_tol;
00410   if (!n.getParam("screw_tol", screw_tol))
00411   {
00412     ROS_INFO("CounterbalanceTestController was not given parameter 'screw_tol' on namespace %s. Using default 2.0",
00413               n.getNamespace().c_str());
00414     screw_tol = 2.0;
00415   }  
00416 
00417   if (!n.getParam("bar_tol", bar_tol))
00418   {
00419     ROS_INFO("CounterbalanceTestController was not given parameter 'bar_tol' on namespace %s. Using default 0.8",
00420               n.getNamespace().c_str());
00421     bar_tol = 0.8;
00422   }  
00423   cb_test_data_.arg_value[23] = screw_tol;
00424   cb_test_data_.arg_value[24] = bar_tol;
00425 
00426 
00427   cb_data_pub_.reset(new realtime_tools::RealtimePublisher<
00428                      joint_qualification_controllers::CounterbalanceTestData>(n, "/cb_test_data", 1, true));
00429 
00430   //ROS_INFO("Initialized CB controller successfully!");
00431 
00432   return true;
00433 }
00434 
00435 void CounterbalanceTestController::starting()
00436 {
00437   initial_time_ = robot_->getTime();
00438 }
00439 
00440 void CounterbalanceTestController::update()
00441 {
00442   // wait until the joints are calibrated to start
00443   if (!lift_state_->calibrated_)
00444     return;
00445   if (cb_test_data_.flex_test and !flex_state_->calibrated_)
00446     return;
00447 
00448   ros::Time time = robot_->getTime();
00449 
00450   if ((time - initial_time_).toSec() > timeout_ && state_ != DONE)
00451   {
00452     ROS_WARN("CounterbalanceTestController timed out during test. Timeout: %f.", timeout_);
00453     state_ = DONE;
00454     cb_test_data_.timeout_hit = true;
00455   }
00456 
00457   lift_controller_->update();
00458   if (cb_test_data_.flex_test) 
00459     flex_controller_->update();
00460 
00461   switch (state_)
00462   {
00463   case STARTING:
00464     {
00465       double lift_cmd = cb_test_data_.lift_data[lift_index_].lift_position;
00466       double flex_cmd = cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_position;
00467 
00468       // Set controllers
00469       lift_controller_->setCommand(lift_cmd);
00470       if (cb_test_data_.flex_test) flex_controller_->setCommand(flex_cmd);
00471 
00472       dither_count_ = 0;
00473       start_time_ = time;
00474 
00475       state_ = SETTLING;
00476 
00477       //ROS_INFO("Moving to position lift %f, flex %f", lift_cmd, flex_cmd);
00478       break;
00479     }
00480   case SETTLING:
00481     {
00482       if ((time - start_time_).toSec() > settle_time_)
00483       {
00484         state_ = DITHERING;
00485         start_time_ = time;
00486       }
00487 
00488       break;
00489     }
00490   case DITHERING:
00491     {
00492       // Add dither
00493       lift_state_->commanded_effort_ += lift_dither_->update();
00494       if (cb_test_data_.flex_test) flex_state_->commanded_effort_ += flex_dither_->update();
00495 
00496       // Lift
00497       cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.time[dither_count_] = (time - start_time_).toSec();
00498       cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.position[dither_count_] = lift_state_->position_;
00499       cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.velocity[dither_count_] = lift_state_->velocity_;
00500       cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.effort[dither_count_] = lift_state_->measured_effort_;
00501       
00502       // Flex
00503       cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.time[dither_count_] = (time - start_time_).toSec();
00504       if (cb_test_data_.flex_test)
00505       {
00506         cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.position[dither_count_] = flex_state_->position_;
00507         cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.velocity[dither_count_] = flex_state_->velocity_;
00508         cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.effort[dither_count_] = flex_state_->measured_effort_;
00509       }
00510       else
00511       {
00512         cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.position[dither_count_] = 0;
00513         cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.velocity[dither_count_] = 0;
00514         cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.effort[dither_count_] = 0;
00515       }
00516 
00517       ++dither_count_;
00518       
00519       if (dither_count_ >= dither_points_)
00520       {
00521         state_ = NEXT;
00522       }
00523       break;
00524     }
00525   case NEXT:
00526     {
00527       // Increment flex, lift indices
00528       ++flex_index_;
00529       if (flex_index_ >= cb_test_data_.lift_data[0].flex_data.size())
00530       {
00531         flex_index_ = 0;
00532         lift_index_++;
00533       }
00534       if (lift_index_ >= cb_test_data_.lift_data.size())
00535       {
00536         state_ = DONE;
00537         break;
00538       }
00539 
00540       state_ = STARTING;
00541       break;
00542     }
00543   case DONE:
00544     {
00545       if (!data_sent_)
00546         data_sent_ = sendData();
00547 
00548       break;
00549     }
00550   }
00551 }
00552 
00553 bool CounterbalanceTestController::sendData()
00554 {
00555   if (cb_data_pub_->trylock())
00556   {
00557     // Copy data and send
00558     joint_qualification_controllers::CounterbalanceTestData *out = &cb_data_pub_->msg_;
00559 
00560     out->lift_joint     = cb_test_data_.lift_joint;
00561     out->flex_joint     = cb_test_data_.flex_joint;
00562     out->lift_amplitude = cb_test_data_.lift_amplitude;
00563     out->flex_amplitude = cb_test_data_.flex_amplitude;
00564     out->timeout_hit    = cb_test_data_.timeout_hit;
00565     out->flex_test      = cb_test_data_.flex_test;
00566     out->arg_name       = cb_test_data_.arg_name;
00567     out->arg_value      = cb_test_data_.arg_value;
00568 
00569     out->lift_data      = cb_test_data_.lift_data;
00570     cb_data_pub_->unlockAndPublish();
00571     return true;
00572   }
00573   return false;
00574 }
00575 


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Sat Apr 27 2019 03:10:47