$search
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 <pr2_mechanism_model/pr2_belt_transmission.h> 00036 #include <math.h> 00037 #include <pluginlib/class_list_macros.h> 00038 00039 PLUGINLIB_DECLARE_CLASS(pr2_mechanism_model, PR2BeltCompensatorTransmission, 00040 pr2_mechanism_model::PR2BeltCompensatorTransmission, 00041 pr2_mechanism_model::Transmission) 00042 00043 namespace pr2_mechanism_model { 00044 00045 bool PR2BeltCompensatorTransmission::initXml(TiXmlElement *elt, Robot *robot) 00046 { 00047 const char *name = elt->Attribute("name"); 00048 name_ = name ? name : ""; 00049 00050 TiXmlElement *jel = elt->FirstChildElement("joint"); 00051 const char *joint_name = jel ? jel->Attribute("name") : NULL; 00052 if (!joint_name) 00053 { 00054 ROS_ERROR("PR2BeltCompensatorTransmission did not specify joint name"); 00055 return false; 00056 } 00057 00058 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name); 00059 if (!joint) 00060 { 00061 ROS_ERROR("PR2BeltCompensatorTransmission could not find joint named \"%s\"", joint_name); 00062 return false; 00063 } 00064 joint_names_.push_back(joint_name); 00065 00066 TiXmlElement *ael = elt->FirstChildElement("actuator"); 00067 const char *actuator_name = ael ? ael->Attribute("name") : NULL; 00068 pr2_hardware_interface::Actuator *a; 00069 if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL ) 00070 { 00071 ROS_ERROR("PR2BeltCompensatorTransmission could not find actuator named \"%s\"", actuator_name); 00072 return false; 00073 } 00074 a->command_.enable_ = true; 00075 actuator_names_.push_back(actuator_name); 00076 00077 mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText()); 00078 00079 TiXmlElement *c = elt->FirstChildElement("compensator"); 00080 if (!c) 00081 { 00082 ROS_ERROR("No compensator element given for transmission %s", name_.c_str()); 00083 return false; 00084 } 00085 00086 double k_belt; 00087 const char *k_belt_str = c->Attribute("k_belt"); 00088 if (!k_belt_str) { 00089 ROS_ERROR("No k_belt given for transmission %s", name_.c_str()); 00090 return false; 00091 } 00092 k_belt = atof(k_belt_str); 00093 00094 double mass_motor; 00095 const char *mass_motor_str = c->Attribute("mass_motor"); 00096 if (!mass_motor_str) { 00097 ROS_ERROR("No mass_motor given for transmission %s", name_.c_str()); 00098 return false; 00099 } 00100 mass_motor = atof(mass_motor_str); 00101 00102 trans_compl_ = (k_belt > 0.0 ? 1.0 / k_belt : 0.0); 00103 trans_tau_ = sqrt(mass_motor * trans_compl_); 00104 00105 const char *kd_motor_str = c->Attribute("kd_motor"); 00106 if (!kd_motor_str) { 00107 ROS_ERROR("No kd_motor given for transmission %s", name_.c_str()); 00108 return false; 00109 } 00110 Kd_motor_ = atof(kd_motor_str); 00111 00112 const char *lambda_motor_str = c->Attribute("lambda_motor"); 00113 if (!lambda_motor_str) { 00114 ROS_ERROR("No lambda_motor given for transmission %s", name_.c_str()); 00115 return false; 00116 } 00117 lambda_motor_ = atof(lambda_motor_str); 00118 00119 const char *lambda_joint_str = c->Attribute("lambda_joint"); 00120 if (!lambda_joint_str) { 00121 ROS_ERROR("No lambda_joint given for transmission %s", name_.c_str()); 00122 return false; 00123 } 00124 lambda_joint_ = atof(lambda_joint_str); 00125 00126 const char *lambda_combined_str = c->Attribute("lambda_combined"); 00127 if (!lambda_combined_str) { 00128 ROS_ERROR("No lambda_combined given for transmission %s", name_.c_str()); 00129 return false; 00130 } 00131 lambda_combo_ = atof(lambda_combined_str); 00132 00133 // Initializes the filters 00134 last_motor_pos_ = last_motor_vel_ = 0; 00135 last_jnt1_pos_ = last_jnt1_vel_ = last_jnt1_acc_ = 0; 00136 last_defl_pos_ = last_defl_vel_ = last_defl_acc_ = 0; 00137 last_joint_pos_ = last_joint_vel_ = 0; 00138 delta_motor_vel_ = 0; 00139 last_motor_damping_force_ = 0; 00140 00141 last_timestamp_ = ros::Duration(0); 00142 00143 // Initialize the backward transmission state variables. 00144 last_timestamp_backwards_ = last_timestamp_; 00145 halfdt_backwards_ = 0.0; 00146 motor_force_backwards_ = 0.0; 00147 last_motor_pos_backwards_ = 0.0; 00148 last_motor_vel_backwards_ = 0.0; 00149 last_motor_acc_backwards_ = 0.0; 00150 last_joint_pos_backwards_ = 0.0; 00151 last_joint_vel_backwards_ = 0.0; 00152 00153 return true; 00154 } 00155 00156 bool PR2BeltCompensatorTransmission::initXml(TiXmlElement *elt) 00157 { 00158 const char *name = elt->Attribute("name"); 00159 name_ = name ? name : ""; 00160 00161 TiXmlElement *jel = elt->FirstChildElement("joint"); 00162 const char *joint_name = jel ? jel->Attribute("name") : NULL; 00163 if (!joint_name) 00164 { 00165 ROS_ERROR("PR2BeltCompensatorTransmission did not specify joint name"); 00166 return false; 00167 } 00168 00169 joint_names_.push_back(joint_name); 00170 00171 TiXmlElement *ael = elt->FirstChildElement("actuator"); 00172 const char *actuator_name = ael ? ael->Attribute("name") : NULL; 00173 actuator_names_.push_back(actuator_name); 00174 00175 mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText()); 00176 00177 TiXmlElement *c = elt->FirstChildElement("compensator"); 00178 if (!c) 00179 { 00180 ROS_ERROR("No compensator element given for transmission %s", name_.c_str()); 00181 return false; 00182 } 00183 00184 double k_belt; 00185 const char *k_belt_str = c->Attribute("k_belt"); 00186 if (!k_belt_str) { 00187 ROS_ERROR("No k_belt given for transmission %s", name_.c_str()); 00188 return false; 00189 } 00190 k_belt = atof(k_belt_str); 00191 00192 double mass_motor; 00193 const char *mass_motor_str = c->Attribute("mass_motor"); 00194 if (!mass_motor_str) { 00195 ROS_ERROR("No mass_motor given for transmission %s", name_.c_str()); 00196 return false; 00197 } 00198 mass_motor = atof(mass_motor_str); 00199 00200 trans_compl_ = (k_belt > 0.0 ? 1.0 / k_belt : 0.0); 00201 trans_tau_ = sqrt(mass_motor * trans_compl_); 00202 00203 const char *kd_motor_str = c->Attribute("kd_motor"); 00204 if (!kd_motor_str) { 00205 ROS_ERROR("No kd_motor given for transmission %s", name_.c_str()); 00206 return false; 00207 } 00208 Kd_motor_ = atof(kd_motor_str); 00209 00210 const char *lambda_motor_str = c->Attribute("lambda_motor"); 00211 if (!lambda_motor_str) { 00212 ROS_ERROR("No lambda_motor given for transmission %s", name_.c_str()); 00213 return false; 00214 } 00215 lambda_motor_ = atof(lambda_motor_str); 00216 00217 const char *lambda_joint_str = c->Attribute("lambda_joint"); 00218 if (!lambda_joint_str) { 00219 ROS_ERROR("No lambda_joint given for transmission %s", name_.c_str()); 00220 return false; 00221 } 00222 lambda_joint_ = atof(lambda_joint_str); 00223 00224 const char *lambda_combined_str = c->Attribute("lambda_combined"); 00225 if (!lambda_combined_str) { 00226 ROS_ERROR("No lambda_combined given for transmission %s", name_.c_str()); 00227 return false; 00228 } 00229 lambda_combo_ = atof(lambda_combined_str); 00230 00231 // Initializes the filters 00232 last_motor_pos_ = last_motor_vel_ = 0; 00233 last_jnt1_pos_ = last_jnt1_vel_ = last_jnt1_acc_ = 0; 00234 last_defl_pos_ = last_defl_vel_ = last_defl_acc_ = 0; 00235 last_joint_pos_ = last_joint_vel_ = 0; 00236 delta_motor_vel_ = 0; 00237 last_motor_damping_force_ = 0; 00238 00239 last_timestamp_ = ros::Duration(0); 00240 00241 // Initialize the backward transmission state variables. 00242 last_timestamp_backwards_ = last_timestamp_; 00243 halfdt_backwards_ = 0.0; 00244 motor_force_backwards_ = 0.0; 00245 last_motor_pos_backwards_ = 0.0; 00246 last_motor_vel_backwards_ = 0.0; 00247 last_motor_acc_backwards_ = 0.0; 00248 last_joint_pos_backwards_ = 0.0; 00249 last_joint_vel_backwards_ = 0.0; 00250 00251 return true; 00252 } 00253 00254 void PR2BeltCompensatorTransmission::propagatePosition( 00255 std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<JointState*>& js) 00256 { 00257 assert(as.size() == 1); 00258 assert(js.size() == 1); 00259 ros::Duration timestamp = as[0]->state_.sample_timestamp_; 00260 dt = (timestamp - last_timestamp_).toSec(); 00261 last_timestamp_ = timestamp; 00262 00263 // These are not the actual "motor" positions. They are the 00264 // theoretical joint positions if there were no belt involved. 00265 00266 // Get the motor position, velocity, measured force. Note we do not 00267 // filter the motor velocity, because we want the least lag for the 00268 // motor damping feedback. We will filter the joint velocity. 00269 double motor_pos = as[0]->state_.position_ / mechanical_reduction_; 00270 double motor_vel = ( dt>0.0 ? (motor_pos - last_motor_pos_)/dt : 0.0 ); 00271 00272 double motor_measured_force = as[0]->state_.last_measured_effort_ * mechanical_reduction_; 00273 00274 00275 // Estimate the actual joint position and velocity. We use two 00276 // distinct methods (each with their own pros/cons and combine). 00277 00278 // Method 1: Twice filter the motor position at the resonance mode 00279 // of the joint against the transmission and locked motor. This 00280 // duplicates the mechanical filtering occuring in the 00281 // transmission. Obviously, this is an approximation. In 00282 // particular the resonance frequency is unknown (we have to assume 00283 // that lambda_joint_ over-estimates it). Also, this doesn't 00284 // account for steady-state forces, i.e. transmission stretch. So 00285 // the method is better at higher frequencies. For numerical 00286 // stability, upper bound the bandwidth by 2/dt. 00287 double jnt1_pos, jnt1_vel, jnt1_acc; 00288 double lam = (dt*lambda_joint_ < 2.0 ? lambda_joint_ : 2.0/dt); 00289 00290 jnt1_vel = last_jnt1_vel_ + 0.5*dt*( last_jnt1_acc_); 00291 jnt1_pos = last_jnt1_pos_ + 0.5*dt*(jnt1_vel + last_jnt1_vel_); 00292 00293 jnt1_acc = (lam*lam * (motor_pos-jnt1_pos) - 2.0*lam * jnt1_vel) 00294 / (1.0 + 0.5*dt*2.0*lam + 0.25*dt*dt*lam*lam); 00295 00296 jnt1_vel = last_jnt1_vel_ + 0.5*dt*(jnt1_acc + last_jnt1_acc_); 00297 jnt1_pos = last_jnt1_pos_ + 0.5*dt*(jnt1_vel + last_jnt1_vel_); 00298 00299 // Method 2: Estimate the transmission deflection explicitly. This 00300 // uses only the transmission stiffness (compliance) and motor mass. 00301 // The later is combined with the compliance to give a transmission 00302 // time constant (tau). This method assumes the motor mass is much 00303 // smaller than the joint mass and the resonance of the motor 00304 // against the transmission is damped. It does NOT need to know the 00305 // joint/link mass (i.e. is independent of joint configurations) and 00306 // adds the appropriate DC transmission stretch. However, it 00307 // assumes zero motor friction to ground and no Coulomb fiction. 00308 // Also, it uses the encoder directly at high frequency, remaining 00309 // noisy. For numerical stability, if the time constant is zero, 00310 // implement a 0th order system. Else lower bound the time constant 00311 // by dt/2. 00312 double defl_pos, defl_vel, defl_acc; 00313 if (trans_tau_ == 0) 00314 { 00315 defl_acc = 0.0; 00316 defl_vel = 0.0; 00317 defl_pos = trans_compl_ * motor_measured_force; 00318 } 00319 else 00320 { 00321 double tau = (dt < 2.0*trans_tau_ ? trans_tau_ : dt/2.0); 00322 00323 defl_vel = last_defl_vel_ + 0.5*dt*( last_defl_acc_); 00324 defl_pos = last_defl_pos_ + 0.5*dt*(defl_vel + last_defl_vel_); 00325 00326 defl_acc = (trans_compl_ * motor_measured_force 00327 - defl_pos - 2.0*tau * defl_vel) 00328 / (tau*tau + 2.0*tau*0.5*dt + 0.25*dt*dt); 00329 00330 defl_vel = last_defl_vel_ + 0.5*dt*(defl_acc + last_defl_acc_); 00331 defl_pos = last_defl_pos_ + 0.5*dt*(defl_vel + last_defl_vel_); 00332 } 00333 00334 double jnt2_pos = motor_pos - defl_pos; 00335 00336 // Combine the two joint position estimates and calculate the 00337 // velocity: High pass method 1, low pass method 2. In the end, the 00338 // encoder and measured force are both filtered at least once before 00339 // reaching the joint estimate. I.e. the velocity is smooth. For 00340 // numerical stability, upper bound the combination bandwidth. If 00341 // the bandwidth is zero, take just method 1. 00342 double joint_pos, joint_vel; 00343 if (lambda_combo_ == 0.0) 00344 { 00345 joint_pos = jnt1_pos; 00346 joint_vel = jnt1_vel; 00347 } 00348 else 00349 { 00350 lam = (dt*lambda_combo_ < 2.0 ? lambda_combo_ : 2.0/dt); 00351 00352 joint_pos = last_joint_pos_ + 0.5*dt*(last_joint_vel_); 00353 joint_vel = (jnt1_vel + lam * (jnt2_pos - joint_pos)) 00354 / (1.0 + 0.5*dt*lam); 00355 joint_pos = last_joint_pos_ + 0.5*dt*(joint_vel + last_joint_vel_); 00356 } 00357 00358 00359 // Push the joint info out. 00360 js[0]->position_ = joint_pos + js[0]->reference_position_; 00361 js[0]->velocity_ = joint_vel; 00362 js[0]->measured_effort_ = as[0]->state_.last_measured_effort_ * mechanical_reduction_; 00363 00364 00365 // Stores values used by propogateEffort 00366 delta_motor_vel_ = motor_vel - last_motor_vel_; 00367 00368 // Saves the current values for use in the next servo cycle. These 00369 // are used to filter the signals 00370 last_motor_pos_ = motor_pos; 00371 last_motor_vel_ = motor_vel; 00372 00373 last_jnt1_pos_ = jnt1_pos; 00374 last_jnt1_vel_ = jnt1_vel; 00375 last_jnt1_acc_ = jnt1_acc; 00376 00377 last_defl_pos_ = defl_pos; 00378 last_defl_vel_ = defl_vel; 00379 last_defl_acc_ = defl_acc; 00380 00381 last_joint_pos_ = joint_pos; 00382 last_joint_vel_ = joint_vel; 00383 } 00384 00385 void PR2BeltCompensatorTransmission::propagateEffort( 00386 std::vector<JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as) 00387 { 00388 assert(as.size() == 1); 00389 assert(js.size() == 1); 00390 00391 00392 // Calculate the damping force for the motor vibrations against the 00393 // transmission. As we don't have a true vibration measurement, 00394 // dampen the motor simply at high frequency. For numerical 00395 // stability, upper bound the cutoff bandwidth. If the bandwidth is 00396 // zero, use damping over all frequencies, i.e. regular damping. 00397 double motor_damping_force; 00398 if (lambda_motor_ == 0.0) 00399 { 00400 motor_damping_force = - Kd_motor_ * last_motor_vel_; 00401 } 00402 else 00403 { 00404 double lam = (dt*lambda_motor_ < 2.0 ? lambda_motor_ : 2.0/dt); 00405 00406 motor_damping_force = ((1.0-0.5*dt*lam) * last_motor_damping_force_ 00407 - Kd_motor_ * delta_motor_vel_) 00408 / (1.0+0.5*dt*lam); 00409 } 00410 00411 // Add to the joint force. 00412 double motor_force = js[0]->commanded_effort_ + motor_damping_force; 00413 00414 // Send out! 00415 as[0]->command_.effort_ = motor_force / mechanical_reduction_; 00416 00417 last_motor_damping_force_ = motor_damping_force; 00418 } 00419 00420 00421 00422 // The backward transmission is a entirely separate entity for the 00423 // forward transmission. Both contain state information, that is NOT 00424 // shared. In particular, the backward transmission implements a 00425 // 4th-order model of the motor mass, belt stiffness, and joint mass, 00426 // which is what the forward transmission expects. It should be used 00427 // ONLY in Gazebo, i.e. when simulating the robot. As such, we assume 00428 // here that a cycle starts with a given actuator effort, 00429 // propagateEffortBackwards() is called first (setting the time step) to 00430 // set the joint effort, Gazebo then calculates a new joint position, 00431 // and propagatePositionBackwards() is called last to provide the new 00432 // actuator position. 00433 void PR2BeltCompensatorTransmission::propagateEffortBackwards( 00434 std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<JointState*>& js) 00435 { 00436 // Check the arguments. This acts only on a single actuator/joint. 00437 assert(as.size() == 1); 00438 assert(js.size() == 1); 00439 00440 // We are simulating a motor-mass / belt-spring-damper / joint-mass 00441 // system. Note all calculations are done if joint-space units, so 00442 // that the motor position/velocity/acceleration/force are scaled 00443 // appropriately by the mechanical reduction. Also note, the joint 00444 // mass is actually simulated in Gazebo, so for the purposes of this 00445 // belt simulation, we assume an infinite joint mass and hence zero 00446 // joint acceleration. Finally, we assume the belt-spring/motor-mass 00447 // dynamics are critically damped and set the damping accordingly. 00448 double motor_pos, motor_vel, motor_acc; 00449 double joint_pos, joint_vel; 00450 double motor_force; 00451 double spring_force; 00452 double halfdt; 00453 00454 // Calculate the time step. Should be the same as the forward 00455 // transmission, but we don't want/need to assume that. Furthermore, 00456 // given this is used only to simulate a transmission, the time-steps 00457 // should be perfectly constant and known in advance. But to keep 00458 // this clean we recalculate. The question remains who defines the 00459 // time step. Like the forward transmission, we can only use the time 00460 // step in the actuator state, though this makes little sense here... 00461 ros::Duration timestamp = as[0]->state_.sample_timestamp_; 00462 halfdt = 0.5*(timestamp - last_timestamp_backwards_).toSec(); 00463 last_timestamp_backwards_ = timestamp; 00464 00465 // Get the actuator force acting on the motor mass, multipled by the 00466 // mechanical reduction to be in joint-space units. Note we are 00467 // assuming the command is perfectly executed, i.e. will completely 00468 // act on the motor. 00469 motor_force = as[0]->command_.effort_ * mechanical_reduction_; 00470 00471 // If the transmission compliance is zero (infinitely stiff) or the 00472 // motor mass is zero (infinitely light), then the transmission time 00473 // constant is also zero (infinitely fast) and the entire transmission 00474 // collapses to a regular rigid connection. 00475 if ((trans_compl_ == 0.0) || (trans_tau_ == 0.0)) 00476 { 00477 // Immediately propagate the motor force to the spring, ignoring 00478 // the (infinitely fast) model dynamics. 00479 spring_force = motor_force; 00480 } 00481 else 00482 { 00483 // Update the model. Note for numerical stability, the 00484 // transmission dynamics need to be slower than the integration 00485 // time step. Specifically we need to lower bound the tranmission 00486 // time constant by dt/2. 00487 double tau = (halfdt < trans_tau_ ? trans_tau_ : halfdt); 00488 00489 // Calculate the new motor position/velocity assuming a new motor 00490 // acceleration of zero (simply integrate the last information). 00491 motor_vel = last_motor_vel_backwards_ + halfdt*(last_motor_acc_backwards_ + 0 ); 00492 motor_pos = last_motor_pos_backwards_ + halfdt*(last_motor_vel_backwards_ + motor_vel); 00493 00494 // Calculate the new joint position/velocity assuming a new joint 00495 // acceleration of zero, equivalent to an extremely large joint 00496 // mass (relatively to the motor). This is also "fixed" in the 00497 // second half of the backward transmission after the simulator 00498 // has provided a new joint position/velocity. 00499 joint_vel = last_joint_vel_backwards_; 00500 joint_pos = last_joint_pos_backwards_ + halfdt*(last_joint_vel_backwards_ + joint_vel); 00501 00502 // Calculate the spring force between the two masses. 00503 spring_force = (2.0*tau*(motor_vel - joint_vel) + (motor_pos - joint_pos)) / trans_compl_; 00504 00505 // This gives us the new motor acceleration (still assuming no 00506 // joint acceleration). 00507 motor_acc = (motor_force - spring_force) * trans_compl_ / (tau*tau + 2.0*tau*halfdt + halfdt*halfdt); 00508 00509 // Recalculate the motor position/velocity, using this new acceleration. 00510 motor_vel = last_motor_vel_backwards_ + halfdt*(last_motor_acc_backwards_ + motor_acc); 00511 motor_pos = last_motor_pos_backwards_ + halfdt*(last_motor_vel_backwards_ + motor_vel); 00512 00513 // Recalculate the spring force. 00514 spring_force = (2.0*tau*(motor_vel - joint_vel) + (motor_pos - joint_pos)) / trans_compl_; 00515 } 00516 00517 // The spring force becomes the force seen by the joint. 00518 js[0]->commanded_effort_ = spring_force; 00519 00520 // Save the information that is to be used in the second half, i.e. in 00521 // propagatePositionBackwards(). This includes the motor force 00522 // (driving this cycle) and the time step (calculated here). 00523 halfdt_backwards_ = halfdt; 00524 motor_force_backwards_ = motor_force; 00525 } 00526 00527 00528 void PR2BeltCompensatorTransmission::propagatePositionBackwards( 00529 std::vector<JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as) 00530 { 00531 // Check the arguments. This acts only on a single actuator/joint. 00532 assert(as.size() == 1); 00533 assert(js.size() == 1); 00534 00535 // Again (as in the first half of the backward transmission) simulate 00536 // the motor-mass / belt-spring-damper / joint-mass system. And 00537 // again, all variables are in joint-space units. Only this time use 00538 // the joint position/velocity provided by the simulator. 00539 double motor_pos, motor_vel, motor_acc; 00540 double joint_pos, joint_vel; 00541 double motor_force; 00542 double spring_force; 00543 double halfdt; 00544 00545 // Get the time step and motor force from the first half of the 00546 // backward transmission. 00547 halfdt = halfdt_backwards_; 00548 motor_force = motor_force_backwards_; 00549 00550 // Get the new joint position and velocity, as calculated by the 00551 // simulator. 00552 joint_pos = js[0]->position_ - js[0]->reference_position_; 00553 joint_vel = js[0]->velocity_; 00554 00555 // As in the first half, if the transmission compliance or time 00556 // constant are zero, the transmission collapses to a regular rigid 00557 // transmission. 00558 if ((trans_compl_ == 0.0) || (trans_tau_ == 0.0)) 00559 { 00560 // Immediately propagate the joint position/velocity to the motor, 00561 // ignoring the (infinitely fast) model dynamics. 00562 motor_acc = 0.0; 00563 motor_vel = joint_vel; 00564 motor_pos = joint_pos; 00565 } 00566 else 00567 { 00568 // Update the model. Note for numerical stability, we again lower 00569 // bound the tranmission time constant by dt/2. 00570 double tau = (halfdt < trans_tau_ ? trans_tau_ : halfdt); 00571 00572 // Calculate the new motor position/velocity assuming a new motor 00573 // acceleration of zero. 00574 motor_vel = last_motor_vel_backwards_ + halfdt*(last_motor_acc_backwards_ + 0 ); 00575 motor_pos = last_motor_pos_backwards_ + halfdt*(last_motor_vel_backwards_ + motor_vel); 00576 00577 // Calculate the spring force between the two masses. 00578 spring_force = (2.0*tau*(motor_vel - joint_vel) + (motor_pos - joint_pos)) / trans_compl_; 00579 00580 // This gives us the new motor acceleration. 00581 motor_acc = (motor_force - spring_force) * trans_compl_ / (tau*tau + 2.0*tau*halfdt + halfdt*halfdt); 00582 00583 // Recalculate the motor position/velocity, using this new acceleration. 00584 motor_vel = last_motor_vel_backwards_ + halfdt*(last_motor_acc_backwards_ + motor_acc); 00585 motor_pos = last_motor_pos_backwards_ + halfdt*(last_motor_vel_backwards_ + motor_vel); 00586 } 00587 00588 // Save the current state for the next cycle. 00589 last_motor_pos_backwards_ = motor_pos; 00590 last_motor_vel_backwards_ = motor_vel; 00591 last_motor_acc_backwards_ = motor_acc; 00592 00593 last_joint_pos_backwards_ = joint_pos; 00594 last_joint_vel_backwards_ = joint_vel; 00595 00596 // Push the motor position/velocity to the actuator, accounting for 00597 // the mechanical reduction. 00598 as[0]->state_.position_ = motor_pos * mechanical_reduction_; 00599 as[0]->state_.velocity_ = motor_vel * mechanical_reduction_; 00600 00601 // Also push the motor force to the actuator. Note we already assumed 00602 // that the commanded actuator effort was accurately executed/applied, 00603 // so the measured actuator effort is just the motor force. 00604 as[0]->state_.last_measured_effort_ = motor_force / mechanical_reduction_; 00605 00606 00607 // By storing the new actuator data, we are advancing to the next 00608 // servo cycle. Always make sure the timing has been initialized. 00609 if (! simulated_actuator_timestamp_initialized_) 00610 { 00611 // Set the time stamp to zero (it is measured relative to the start time). 00612 as[0]->state_.sample_timestamp_ = ros::Duration(0); 00613 00614 // Try to set the start time. Only then do we claim initialized. 00615 if (ros::isStarted()) 00616 { 00617 simulated_actuator_start_time_ = ros::Time::now(); 00618 simulated_actuator_timestamp_initialized_ = true; 00619 } 00620 } 00621 else 00622 { 00623 // Measure the time stamp relative to the start time. 00624 as[0]->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_; 00625 } 00626 // Set the historical (double) timestamp accordingly. 00627 as[0]->state_.timestamp_ = as[0]->state_.sample_timestamp_.toSec(); 00628 00629 00630 // Simulate calibration sensors by filling out actuator states 00631 this->joint_calibration_simulator_.simulateJointCalibration(js[0],as[0]); 00632 } 00633 00634 } // namespace