Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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_EXPORT_CLASS(joint_qualification_controllers::JointLimitCalibrationController,
00043 pr2_controller_interface::Controller)
00044
00045 JointLimitCalibrationController::JointLimitCalibrationController()
00046 : robot_(NULL), last_publish_time_(0), state_(INITIALIZED),
00047 count_(0), stop_count_(0), search_velocity_(0),
00048 actuator_(NULL), joint_(NULL), transmission_(NULL)
00049 {
00050 }
00051
00052 JointLimitCalibrationController::~JointLimitCalibrationController()
00053 {
00054 }
00055
00056 bool JointLimitCalibrationController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00057 {
00058 assert(robot);
00059 node_ = n;
00060 robot_ = robot;
00061
00062
00063 std::string joint_name;
00064 if (!node_.getParam("joint", joint_name))
00065 {
00066 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00067 return false;
00068 }
00069 if (!(joint_ = robot->getJointState(joint_name)))
00070 {
00071 ROS_ERROR("Could not find joint %s (namespace: %s)",
00072 joint_name.c_str(), node_.getNamespace().c_str());
00073 return false;
00074 }
00075
00076
00077 std::string actuator_name;
00078 if (!node_.getParam("actuator", actuator_name))
00079 {
00080 ROS_ERROR("No actuator given (namespace: %s)", node_.getNamespace().c_str());
00081 return false;
00082 }
00083 if (!(actuator_ = robot->model_->getActuator(actuator_name)))
00084 {
00085 ROS_ERROR("Could not find actuator %s (namespace: %s)",
00086 actuator_name.c_str(), node_.getNamespace().c_str());
00087 return false;
00088 }
00089
00090
00091 std::string transmission_name;
00092 if (!node_.getParam("transmission", transmission_name))
00093 {
00094 ROS_ERROR("No transmission given (namespace: %s)", node_.getNamespace().c_str());
00095 return false;
00096 }
00097 if (!(transmission_ = robot->model_->getTransmission(transmission_name).get()))
00098 {
00099 ROS_ERROR("Could not find transmission %s (namespace: %s)",
00100 transmission_name.c_str(), node_.getNamespace().c_str());
00101 return false;
00102 }
00103
00104 if (!node_.getParam("velocity", search_velocity_))
00105 {
00106 ROS_ERROR("Velocity value was not specified (namespace: %s)", node_.getNamespace().c_str());
00107 return false;
00108 }
00109
00110
00111 if (!vc_.init(robot, node_))
00112 return false;
00113
00114
00115 pub_calibrated_.reset(
00116 new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00117
00118 return true;
00119 }
00120
00121 void JointLimitCalibrationController::update()
00122 {
00123 assert(joint_);
00124 assert(actuator_);
00125
00126 switch (state_)
00127 {
00128 case INITIALIZED:
00129 state_ = BEGINNING;
00130 return;
00131 case BEGINNING:
00132 count_ = 0;
00133 joint_->calibrated_ = false;
00134 actuator_->state_.zero_offset_ = 0.0;
00135 vc_.setCommand(search_velocity_);
00136 state_ = STARTING;
00137 break;
00138 case STARTING:
00139
00140 if (++count_ > 500)
00141 {
00142 count_ = 0;
00143 state_ = STOPPING;
00144 }
00145 break;
00146 case STOPPING:
00147 if (fabs(joint_->velocity_) < 0.001)
00148 stop_count_++;
00149 else
00150 stop_count_ = 0;
00151
00152 if (stop_count_ > 250)
00153 {
00154
00155 pr2_hardware_interface::Actuator a;
00156 pr2_mechanism_model::JointState j;
00157 std::vector<pr2_hardware_interface::Actuator*> fake_a;
00158 std::vector<pr2_mechanism_model::JointState*> fake_j;
00159 fake_a.push_back(&a);
00160 fake_j.push_back(&j);
00161
00162 fake_a[0]->state_.position_ = actuator_->state_.position_;
00163
00164 transmission_->propagatePosition(fake_a, fake_j);
00165
00166
00167 double ref_position = 0;
00168 if (search_velocity_ < 0)
00169 ref_position = joint_->joint_->limits->lower;
00170 else
00171 ref_position = joint_->joint_->limits->upper;
00172
00173
00174 fake_j[0]->position_ = fake_j[0]->position_ - ref_position;
00175
00176 transmission_->propagatePositionBackwards(fake_j, fake_a);
00177
00178 actuator_->state_.zero_offset_ = fake_a[0]->state_.position_;
00179 state_ = CALIBRATED;
00180 joint_->calibrated_ = true;
00181 vc_.setCommand(0);
00182 }
00183 break;
00184 case CALIBRATED:
00185 if (pub_calibrated_)
00186 {
00187 if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime())
00188 {
00189 if (pub_calibrated_->trylock())
00190 {
00191 last_publish_time_ = robot_->getTime();
00192 pub_calibrated_->unlockAndPublish();
00193 }
00194 }
00195 }
00196 break;
00197 }
00198
00199 if (state_ != CALIBRATED)
00200 vc_.update();
00201 }
00202