joint_limit_calibration_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 #include "joint_qualification_controllers/joint_limit_calibration_controller.h"
00036 #include "ros/time.h"
00037 #include "pluginlib/class_list_macros.h"
00038 
00039 using namespace std;
00040 using namespace joint_qualification_controllers;
00041 
00042 PLUGINLIB_DECLARE_CLASS(joint_qualification_controllers, JointLimitCalibrationController, 
00043                         joint_qualification_controllers::JointLimitCalibrationController, 
00044                         pr2_controller_interface::Controller)
00045 
00046 JointLimitCalibrationController::JointLimitCalibrationController()
00047 : robot_(NULL), last_publish_time_(0), state_(INITIALIZED), 
00048   count_(0), stop_count_(0), search_velocity_(0), 
00049   actuator_(NULL), joint_(NULL), transmission_(NULL)
00050 {
00051 }
00052 
00053 JointLimitCalibrationController::~JointLimitCalibrationController()
00054 {
00055 }
00056 
00057 bool JointLimitCalibrationController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00058 {
00059   assert(robot);
00060   node_ = n;
00061   robot_ = robot;
00062 
00063   // Joint
00064   std::string joint_name;
00065   if (!node_.getParam("joint", joint_name))
00066   {
00067     ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00068     return false;
00069   }
00070   if (!(joint_ = robot->getJointState(joint_name)))
00071   {
00072     ROS_ERROR("Could not find joint %s (namespace: %s)",
00073               joint_name.c_str(), node_.getNamespace().c_str());
00074     return false;
00075   }
00076 
00077   // Actuator
00078   std::string actuator_name;
00079   if (!node_.getParam("actuator", actuator_name))
00080   {
00081     ROS_ERROR("No actuator given (namespace: %s)", node_.getNamespace().c_str());
00082     return false;
00083   }
00084   if (!(actuator_ = robot->model_->getActuator(actuator_name)))
00085   {
00086     ROS_ERROR("Could not find actuator %s (namespace: %s)",
00087               actuator_name.c_str(), node_.getNamespace().c_str());
00088     return false;
00089   }
00090 
00091   // Transmission
00092   std::string transmission_name;
00093   if (!node_.getParam("transmission", transmission_name))
00094   {
00095     ROS_ERROR("No transmission given (namespace: %s)", node_.getNamespace().c_str());
00096     return false;
00097   }
00098   if (!(transmission_ = robot->model_->getTransmission(transmission_name).get()))
00099   {
00100     ROS_ERROR("Could not find transmission %s (namespace: %s)",
00101               transmission_name.c_str(), node_.getNamespace().c_str());
00102     return false;
00103   }
00104 
00105   if (!node_.getParam("velocity", search_velocity_))
00106   {
00107     ROS_ERROR("Velocity value was not specified (namespace: %s)", node_.getNamespace().c_str());
00108     return false;
00109   }
00110 
00111   // Contained velocity controller
00112   if (!vc_.init(robot, node_))
00113     return false;
00114 
00115   // "Calibrated" topic
00116   pub_calibrated_.reset(
00117     new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00118 
00119   return true;
00120 }
00121 
00122 void JointLimitCalibrationController::update()
00123 {
00124   assert(joint_);
00125   assert(actuator_);
00126 
00127   switch (state_)
00128   {
00129   case INITIALIZED:
00130     state_ = BEGINNING;
00131     return;
00132   case BEGINNING:
00133     count_ = 0;
00134     joint_->calibrated_ = false;
00135     actuator_->state_.zero_offset_ = 0.0;
00136     vc_.setCommand(search_velocity_);
00137     state_ = STARTING;
00138     break;
00139   case STARTING:
00140     // Makes sure we start moving for a bit before checking if we've stopped.
00141     if (++count_ > 500)
00142     {
00143       count_ = 0;
00144       state_ = STOPPING;
00145     }
00146     break;
00147   case STOPPING:
00148     if (fabs(joint_->velocity_) < 0.001)
00149       stop_count_++;
00150     else
00151       stop_count_ = 0;
00152 
00153     if (stop_count_ > 250)
00154     {
00155       // Need to set zero offset correctly
00156       pr2_hardware_interface::Actuator a;
00157       pr2_mechanism_model::JointState j;
00158       std::vector<pr2_hardware_interface::Actuator*> fake_a;
00159       std::vector<pr2_mechanism_model::JointState*> fake_j;
00160       fake_a.push_back(&a);
00161       fake_j.push_back(&j);
00162 
00163       fake_a[0]->state_.position_ = actuator_->state_.position_;
00164 
00165       transmission_->propagatePosition(fake_a, fake_j);
00166 
00167       // What is the actuator position at the joint's max or min?
00168       double ref_position = 0;
00169       if (search_velocity_ < 0)
00170         ref_position = joint_->joint_->limits->lower;
00171       else
00172         ref_position = joint_->joint_->limits->upper;
00173 
00174 
00175       fake_j[0]->position_ = fake_j[0]->position_ - ref_position;
00176 
00177       transmission_->propagatePositionBackwards(fake_j, fake_a);
00178 
00179       actuator_->state_.zero_offset_ = fake_a[0]->state_.position_;
00180       state_ = CALIBRATED;
00181       joint_->calibrated_ = true;
00182       vc_.setCommand(0);
00183     }
00184     break;
00185   case CALIBRATED:
00186     if (pub_calibrated_)
00187     {
00188       if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime())
00189       {
00190         if (pub_calibrated_->trylock())
00191         {
00192           last_publish_time_ = robot_->getTime();
00193           pub_calibrated_->unlockAndPublish();
00194         }
00195       }
00196     }
00197     break;
00198   }
00199 
00200   if (state_ != CALIBRATED)
00201     vc_.update();
00202 }
00203 


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Mon Sep 14 2015 14:38:58