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