hysteresis_controller2.cpp
Go to the documentation of this file.
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 "joint_qualification_controllers/hysteresis_controller2.h"
00036 #include "pluginlib/class_list_macros.h"
00037 #include "urdf_model/joint.h"
00038 
00039 PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::HysteresisController2,
00040                        pr2_controller_interface::Controller)
00041 
00042 #define MAX_DATA_POINTS 120000
00043 
00044 using namespace std;
00045 using namespace joint_qualification_controllers;
00046 
00047 HysteresisController2::HysteresisController2() : 
00048   joint_(NULL),
00049   robot_(NULL),
00050   data_sent_(false),
00051   hyst_pub_(NULL)
00052 {
00053   test_data_.joint_name = "default joint";
00054 
00055   /* TODO: figure out if I need to update this or just remove it
00056      I _think_ I can just remove this; it's done in init() instead
00057   test_data_.time_up.resize(MAX_DATA_POINTS);
00058   test_data_.effort_up.resize(MAX_DATA_POINTS);
00059   test_data_.position_up.resize(MAX_DATA_POINTS);
00060   test_data_.velocity_up.resize(MAX_DATA_POINTS);
00061 
00062   test_data_.time_down.resize(MAX_DATA_POINTS);
00063   test_data_.effort_down.resize(MAX_DATA_POINTS);
00064   test_data_.position_down.resize(MAX_DATA_POINTS);
00065   test_data_.velocity_down.resize(MAX_DATA_POINTS);
00066   */
00067 
00068   test_data_.arg_name.resize(14);
00069   test_data_.arg_value.resize(14);
00070   test_data_.arg_name[0] = "Min. Expected Effort";
00071   test_data_.arg_name[1] = "Max. Expected Effort";
00072   test_data_.arg_name[2] = "Minimum Position";
00073   test_data_.arg_name[3] = "Maximum Position";
00074   test_data_.arg_name[4] = "Velocity";
00075   test_data_.arg_name[5] = "Timeout";
00076   test_data_.arg_name[6] = "Max. Allowed Effort";
00077   test_data_.arg_name[7] = "Tolerance";
00078   test_data_.arg_name[8] = "SD Max";
00079   test_data_.arg_name[9] = "Slope";
00080   test_data_.arg_name[10] = "P Gain";
00081   test_data_.arg_name[11] = "I Gain";
00082   test_data_.arg_name[12] = "D Gain";
00083   test_data_.arg_name[13] = "I-Clamp";
00084 
00085   state_         = STOPPED;
00086   starting_count_ = 0;
00087   velocity_      = 0;
00088   initial_time_  = ros::Time(0);
00089   max_effort_    = 0;
00090   complete       = false;
00091   up_count_      = 0;
00092   down_count_    = 0;
00093   repeat_count_  = 0;
00094   repeat_        = 0;
00095 }
00096 
00097 HysteresisController2::~HysteresisController2()
00098 {
00099   if (velocity_controller_) delete velocity_controller_;
00100 }
00101 
00102 bool HysteresisController2::init( pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00103 {
00104   assert(robot);
00105   robot_ = robot;
00106 
00107   std::string name;
00108   if (!n.getParam("velocity_controller/joint", name)){
00109     ROS_ERROR("Hysteresis Controller: No joint name found on parameter namespace: %s)",
00110               n.getNamespace().c_str());
00111     return false;
00112   }
00113   if (!(joint_ = robot->getJointState(name)))
00114   {
00115     ROS_ERROR("HysteresisController2 could not find joint named \"%s\"\n", name.c_str());
00116     return false;
00117   }
00118 
00119   if (!n.getParam("velocity", velocity_)){
00120     ROS_ERROR("Hysteresis Controller: No velocity found on parameter namespace: %s)",
00121               n.getNamespace().c_str());
00122     return false;
00123   }
00124   velocity_ = velocity_ > 0 ? velocity_ : -1.0 * velocity_;
00125 
00126   if (!n.getParam("max_effort", max_effort_)){
00127     ROS_ERROR("Hysteresis Controller: No max effort found on parameter namespace: %s)",
00128               n.getNamespace().c_str());
00129     return false;
00130   }
00131 
00132   double min_expected, max_expected, max_pos, min_pos;
00133 
00134     if (!n.getParam("min_expected", min_expected)){
00135     ROS_ERROR("Hysteresis Controller: No min expected effort found on parameter namespace: %s)",
00136               n.getNamespace().c_str());
00137     return false;
00138   }
00139 
00140   if (!n.getParam("max_expected", max_expected)){
00141     ROS_ERROR("Hysteresis Controller: No max expected effort found on parameter namespace: %s)",
00142               n.getNamespace().c_str());
00143     return false;
00144   }
00145 
00146   if (!n.getParam("max_position", max_pos)){
00147     ROS_ERROR("Hysteresis Controller: No max position found on parameter namespace: %s)",
00148               n.getNamespace().c_str());
00149     return false;
00150   }
00151 
00152   if (!n.getParam("min_position", min_pos)){
00153     ROS_ERROR("Hysteresis Controller: No min position found on parameter namespace: %s)",
00154               n.getNamespace().c_str());
00155     return false;
00156   }
00157 
00158   if (!n.getParam("timeout", timeout_)){
00159     ROS_ERROR("Hysteresis Controller: No timeout found on parameter namespace: %s)",
00160               n.getNamespace().c_str());
00161     return false;
00162   }
00163 
00164   if (!n.getParam("repeat_count", repeat_count_)){
00165     repeat_count_ = 1;
00166   }
00167 
00168   double tolerance, sd_max;
00169   if (!n.getParam("tolerance", tolerance)){
00170     ROS_WARN("Parameter 'tolerance' is not set on namespace: %s. Default is 0.20.", 
00171              n.getNamespace().c_str());
00172     // This is deprecated, so eventually "return false" will be here.
00173     tolerance = 0.20;
00174   }
00175 
00176   if (!n.getParam("sd_max", sd_max)) {
00177     ROS_WARN("Parameter 'sd_max' is not set on namespace: %s. Default is 0.20.", 
00178              n.getNamespace().c_str());
00179     // This is deprecated, so eventually "return false" will be here.
00180     sd_max = 0.20;
00181   }
00182 
00183   double slope;
00184   if (!n.getParam("slope", slope))
00185     slope = 0;
00186 
00187   initial_time_ = robot_->getTime();
00188   initial_position_ = joint_->position_;
00189 
00190   // Set values in test data output
00191   test_data_.joint_name = name;
00192   test_data_.arg_value[0] = min_expected;
00193   test_data_.arg_value[1] = max_expected;
00194   test_data_.arg_value[2] = min_pos;
00195   test_data_.arg_value[3] = max_pos;
00196   test_data_.arg_value[4] = velocity_;
00197   test_data_.arg_value[5] = timeout_;
00198   test_data_.arg_value[6] = max_effort_;
00199   test_data_.arg_value[7] = tolerance;
00200   test_data_.arg_value[8] = sd_max;
00201   test_data_.arg_value[9] = slope;
00202 
00203   velocity_controller_ = new controller::JointVelocityController();
00204   ros::NodeHandle n_vel(n, "velocity_controller");
00205   if (!velocity_controller_->init(robot, n_vel)) return false;
00206 
00207   // Get the gains, add them to test data
00208   double p, i, d, iClamp, imin;
00209   velocity_controller_->getGains(p, i, d, iClamp, imin);
00210 
00211   test_data_.arg_value[10] = p;
00212   test_data_.arg_value[11] = i;
00213   test_data_.arg_value[12] = d;
00214   test_data_.arg_value[13] = iClamp;
00215 
00216   // repeat count is the number of up+down movements. we have one run for each
00217   // direction
00218   test_data_.runs.resize(repeat_count_ * 2);
00219   move_count_.resize(repeat_count_ * 2);
00220   for( int i=0; i < 2*repeat_count_; ++i ) {
00221     test_data_.runs[i].time.resize(MAX_DATA_POINTS);
00222     test_data_.runs[i].effort.resize(MAX_DATA_POINTS);
00223     test_data_.runs[i].position.resize(MAX_DATA_POINTS);
00224     test_data_.runs[i].velocity.resize(MAX_DATA_POINTS);
00225     if( i % 2 ) {
00226       // odd-numbered runs are down
00227       test_data_.runs[i].dir = HysteresisRun::DOWN;
00228     } else {
00229       test_data_.runs[i].dir = HysteresisRun::UP;
00230     }
00231     move_count_[i] = 0;
00232   }
00233 
00234   hyst_pub_.reset(new realtime_tools::RealtimePublisher<joint_qualification_controllers::HysteresisData2>(n, "/test_data", 1, true));
00235 
00236   return true;
00237 }
00238 
00239 void HysteresisController2::starting()
00240 {
00241   velocity_controller_->starting();
00242 
00243   initial_time_ = robot_->getTime();
00244   initial_position_ = joint_->position_;
00245 }
00246 
00247 void HysteresisController2::update()
00248 {
00249   if (!joint_->calibrated_)
00250     return;
00251 
00252   ros::Time time = robot_->getTime();
00253   velocity_controller_->update();
00254 
00255   // Timeout check.
00256   if ((time - initial_time_).toSec() > timeout_ && state_ != ANALYZING && state_ != DONE) 
00257   {
00258     state_ = ANALYZING;
00259     test_data_.arg_value[5] = -1;
00260     velocity_controller_->setCommand(0.0);
00261   }
00262 
00263   switch (state_)
00264   {
00265   case STOPPED:
00266     velocity_controller_->setCommand(-1.0 * velocity_);
00267     starting_count_ = 0;
00268     state_ = MOVING_HOME;
00269     break;
00270   case MOVING_HOME:
00271     starting_count_++;
00272     if (turn() and starting_count_ > 100)
00273     {
00274       velocity_controller_->setCommand(velocity_);
00275       state_ = MOVING_UP;
00276       starting_count_ = 0;
00277     }
00278     break;
00279   case MOVING_UP:
00280     starting_count_++;
00281     if (up_count_ < MAX_DATA_POINTS)
00282     {
00283       test_data_.runs[repeat_*2].time[up_count_] = time.toSec();
00284       test_data_.runs[repeat_*2].effort[up_count_] = joint_->measured_effort_;
00285       test_data_.runs[repeat_*2].position[up_count_] = joint_->position_;
00286       test_data_.runs[repeat_*2].velocity[up_count_] = joint_->velocity_;
00287       up_count_++;
00288     }
00289     
00290     if ((turn() and starting_count_ > 100) or up_count_ >= MAX_DATA_POINTS)
00291     {
00292       move_count_[repeat_*2] = up_count_;
00293       up_count_ = 0;
00294       velocity_controller_->setCommand(-1.0 * velocity_);
00295       state_ = MOVING_DOWN;
00296       starting_count_ = 0;
00297     }
00298     break;
00299   case MOVING_DOWN:
00300     starting_count_++;
00301     if (down_count_ < MAX_DATA_POINTS)
00302     {
00303       test_data_.runs[repeat_*2 + 1].time[down_count_] = time.toSec();
00304       test_data_.runs[repeat_*2 + 1].effort[down_count_] = joint_->measured_effort_;
00305       test_data_.runs[repeat_*2 + 1].position[down_count_] = joint_->position_;
00306       test_data_.runs[repeat_*2 + 1].velocity[down_count_] = joint_->velocity_;
00307       down_count_++;
00308     }
00309     if ((turn() and starting_count_ > 100) or down_count_ >= MAX_DATA_POINTS)
00310     {
00311       move_count_[repeat_*2 + 1] = down_count_;
00312       down_count_ = 0;
00313       starting_count_ = 0;
00314       ++repeat_;
00315 
00316       // if we still have more repeats
00317       if(repeat_ < repeat_count_ ) {
00318         velocity_controller_->setCommand(velocity_);
00319         state_ = MOVING_UP;
00320       } else {
00321         // done. Analyze data
00322         velocity_controller_->setCommand(0.0);
00323         state_ = ANALYZING;
00324       }
00325     }
00326     break;
00327   case ANALYZING:
00328     velocity_controller_->setCommand(0.0);
00329     analysis();
00330     state_ = DONE;
00331     break;
00332   case DONE:
00333     velocity_controller_->setCommand(0.0);
00334     if (!data_sent_)
00335       data_sent_ = sendData();
00336     break;
00337   }
00338 
00339 }
00340 
00341 bool HysteresisController2::turn()
00342 {
00343   if (joint_->joint_->type!=urdf::Joint::CONTINUOUS)
00344   {
00345     return (fabs(joint_->velocity_) < 0.001 && fabs(joint_->commanded_effort_) > max_effort_);
00346   }
00347   else
00348   {
00349     if (fabs(joint_->position_-initial_position_) > 6.28)
00350     {
00351       initial_position_ = joint_->position_;
00352       return true;
00353     }
00354     return false;
00355   }
00356 }
00357 
00358 void HysteresisController2::analysis()
00359 {
00360   // Resize if no points
00361   for( int i=0; i < repeat_count_ * 2; ++i ) {
00362     int count = move_count_[i];
00363     if( count < 1 ) count = 1;
00364     test_data_.runs[i].time.resize(count);
00365     test_data_.runs[i].effort.resize(count);
00366     test_data_.runs[i].position.resize(count);
00367     test_data_.runs[i].velocity.resize(count);
00368   }
00369 
00370   return;
00371 }
00372 
00373 bool HysteresisController2::sendData()
00374 {
00375   if (hyst_pub_->trylock())
00376   {
00377     joint_qualification_controllers::HysteresisData2 *out = &hyst_pub_->msg_;
00378     out->joint_name = test_data_.joint_name;
00379 
00380     out->runs = test_data_.runs;
00381 
00382     out->arg_name = test_data_.arg_name;
00383     out->arg_value = test_data_.arg_value;
00384 
00385     hyst_pub_->unlockAndPublish();
00386     return true;
00387   }
00388   return false;
00389 }
00390 
00391 
00392 


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