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 "pr2_calibration_controllers/joint_calibration_controller.h"
00036 #include "ros/time.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039 PLUGINLIB_DECLARE_CLASS(pr2_calibration_controllers, JointCalibrationController,
00040 controller::JointCalibrationController, pr2_controller_interface::Controller)
00041
00042 using namespace std;
00043
00044 namespace controller {
00045
00046 JointCalibrationController::JointCalibrationController()
00047 : robot_(NULL), last_publish_time_(0),
00048 actuator_(NULL), joint_(NULL), transmission_(NULL)
00049 {
00050 }
00051
00052 JointCalibrationController::~JointCalibrationController()
00053 {
00054 }
00055
00056 bool JointCalibrationController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00057 {
00058 robot_ = robot;
00059 node_ = n;
00060
00061
00062 std::string joint_name;
00063 if (!node_.getParam("joint", joint_name))
00064 {
00065 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00066 return false;
00067 }
00068 if (!(joint_ = robot->getJointState(joint_name)))
00069 {
00070 ROS_ERROR("Could not find joint %s (namespace: %s)",
00071 joint_name.c_str(), node_.getNamespace().c_str());
00072 return false;
00073 }
00074 if (!joint_->joint_->calibration)
00075 {
00076 ROS_ERROR("Joint %s has no calibration reference position specified (namespace: %s)",
00077 joint_name.c_str(), node_.getNamespace().c_str());
00078 return false;
00079 }
00080
00081
00082 std::string actuator_name;
00083 if (!node_.getParam("actuator", actuator_name))
00084 {
00085 ROS_ERROR("No actuator given (namespace: %s)", node_.getNamespace().c_str());
00086 return false;
00087 }
00088 if (!(actuator_ = robot->model_->getActuator(actuator_name)))
00089 {
00090 ROS_ERROR("Could not find actuator %s (namespace: %s)",
00091 actuator_name.c_str(), node_.getNamespace().c_str());
00092 return false;
00093 }
00094 if (actuator_->state_.zero_offset_ != 0){
00095 ROS_INFO("Joint %s is already calibrated at offset %f", joint_name.c_str(), actuator_->state_.zero_offset_);
00096 state_ = CALIBRATED;
00097 joint_->calibrated_ = true;
00098 }
00099 else{
00100 ROS_INFO("Joint %s is not yet calibrated", joint_name.c_str());
00101 state_ = INITIALIZED;
00102 joint_->calibrated_ = false;
00103 }
00104
00105
00106 std::string transmission_name;
00107 if (!node_.getParam("transmission", transmission_name))
00108 {
00109 ROS_ERROR("No transmission given (namespace: %s)", node_.getNamespace().c_str());
00110 return false;
00111 }
00112 if (!(transmission_ = robot->model_->getTransmission(transmission_name)))
00113 {
00114 ROS_ERROR("Could not find transmission %s (namespace: %s)",
00115 transmission_name.c_str(), node_.getNamespace().c_str());
00116 return false;
00117 }
00118
00119 if (!node_.getParam("velocity", search_velocity_))
00120 {
00121 ROS_ERROR("Velocity value was not specified (namespace: %s)", node_.getNamespace().c_str());
00122 return false;
00123 }
00124
00125
00126 if (!joint_->joint_->calibration->falling && !joint_->joint_->calibration->rising){
00127 ROS_ERROR("No rising or falling edge is specified for calibration of joint %s. Note that the reference_position is not used any more", joint_name.c_str());
00128 return false;
00129 }
00130 if (joint_->joint_->calibration->falling && joint_->joint_->calibration->rising && joint_->joint_->type != urdf::Joint::CONTINUOUS){
00131 ROS_ERROR("Both rising and falling edge are specified for non-continuous joint %s. This is not supported.", joint_name.c_str());
00132 return false;
00133 }
00134 if (search_velocity_ < 0){
00135 search_velocity_ *= -1;
00136 ROS_ERROR("Negative search velocity is not supported for joint %s. Making the search velocity positive.", joint_name.c_str());
00137 }
00138
00139
00140 if (joint_->joint_->calibration->falling && joint_->joint_->calibration->rising){
00141 joint_->reference_position_ = *(joint_->joint_->calibration->rising);
00142 ROS_DEBUG("Using positive search velocity for joint %s", joint_name.c_str());
00143 }
00144 else if (joint_->joint_->calibration->falling){
00145 joint_->reference_position_ = *(joint_->joint_->calibration->falling);
00146 search_velocity_ *= -1.0;
00147 ROS_DEBUG("Using negative search velocity for joint %s", joint_name.c_str());
00148 }
00149 else if (joint_->joint_->calibration->rising){
00150 joint_->reference_position_ = *(joint_->joint_->calibration->rising);
00151 ROS_DEBUG("Using positive search velocity for joint %s", joint_name.c_str());
00152 }
00153
00154 fake_a.resize(1);
00155 fake_j.resize(1);
00156
00157
00158
00159
00160 if (!vc_.init(robot, node_))
00161 return false;
00162
00163
00164 is_calibrated_srv_ = node_.advertiseService("is_calibrated", &JointCalibrationController::isCalibrated, this);
00165
00166
00167 pub_calibrated_.reset(new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
00168
00169
00170 return true;
00171 }
00172
00173
00174 void JointCalibrationController::starting()
00175 {
00176 state_ = INITIALIZED;
00177 joint_->calibrated_ = false;
00178 actuator_->state_.zero_offset_ = 0.0;
00179 }
00180
00181
00182 bool JointCalibrationController::isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req,
00183 pr2_controllers_msgs::QueryCalibrationState::Response& resp)
00184 {
00185 ROS_DEBUG("Is calibrated service %d", state_ == CALIBRATED);
00186 resp.is_calibrated = (state_ == CALIBRATED);
00187 return true;
00188 }
00189
00190
00191 void JointCalibrationController::update()
00192 {
00193 assert(joint_);
00194 assert(actuator_);
00195
00196 switch(state_)
00197 {
00198 case INITIALIZED:
00199 vc_.setCommand(0.0);
00200 state_ = BEGINNING;
00201 break;
00202 case BEGINNING:
00203 if (actuator_->state_.calibration_reading_ & 1)
00204 state_ = MOVING_TO_LOW;
00205 else{
00206 state_ = MOVING_TO_HIGH;
00207 original_position_ = joint_->position_;
00208 }
00209 break;
00210 case MOVING_TO_LOW:
00211 vc_.setCommand(-search_velocity_);
00212 if (!(actuator_->state_.calibration_reading_ & 1))
00213 {
00214 if (--countdown_ <= 0){
00215 state_ = MOVING_TO_HIGH;
00216 original_position_ = joint_->position_;
00217 }
00218 }
00219 else
00220 countdown_ = 200;
00221 break;
00222 case MOVING_TO_HIGH: {
00223 vc_.setCommand(search_velocity_);
00224
00225 if (actuator_->state_.calibration_reading_ & 1)
00226 {
00227
00228 if ((search_velocity_ > 0.0 && (joint_->position_ - original_position_) < 0) ||
00229 (search_velocity_ < 0.0 && (joint_->position_ - original_position_) > 0))
00230 {
00231 state_ = BEGINNING;
00232 ROS_ERROR("Joint hit the falling edge instead of the rising edge. Calibrating again...");
00233 ros::Duration(1.0).sleep();
00234 break;
00235 }
00236
00237 pr2_hardware_interface::Actuator a;
00238 pr2_mechanism_model::JointState j;
00239 fake_a[0] = &a;
00240 fake_j[0] = &j;
00241
00242 fake_a[0]->state_.position_ = actuator_->state_.last_calibration_rising_edge_;
00243 transmission_->propagatePosition(fake_a, fake_j);
00244
00245
00246 actuator_->state_.zero_offset_ = actuator_->state_.last_calibration_rising_edge_;
00247
00248
00249 joint_->calibrated_ = true;
00250
00251 state_ = CALIBRATED;
00252 vc_.setCommand(0.0);
00253 }
00254 break;
00255 }
00256 case CALIBRATED:
00257 if (pub_calibrated_) {
00258 if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime()){
00259 assert(pub_calibrated_);
00260 if (pub_calibrated_->trylock()) {
00261 last_publish_time_ = robot_->getTime();
00262 pub_calibrated_->unlockAndPublish();
00263 }
00264 }
00265 }
00266 break;
00267 }
00268
00269 if (state_ != CALIBRATED)
00270 vc_.update();
00271 }
00272 }