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 
00036 
00037 #include <math.h>
00038 #include <pluginlib/class_list_macros.h>
00039 #include "pr2_mechanism_model/robot.h"
00040 #include "pr2_bringup_gazebo_demo/wrist_transmission.h"
00041 #include "angles/angles.h"
00042 
00043 using namespace pr2_bringup_gazebo_demo;
00044 using namespace pr2_hardware_interface;
00045 
00046 PLUGINLIB_DECLARE_CLASS(pr2_bringup_gazebo_demo, WristTransmissionCal,
00047                         pr2_bringup_gazebo_demo::WristTransmissionCal,
00048                         pr2_mechanism_model::Transmission)
00049 
00050 
00051 bool WristTransmissionCal::initXml(TiXmlElement *elt, pr2_mechanism_model::Robot *robot)
00052 {
00053   const char *name = elt->Attribute("name");
00054   name_ = name ? name : "";
00055 
00056 
00057   TiXmlElement *ael = elt->FirstChildElement("rightActuator");
00058   const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00059   Actuator *a;
00060   if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00061   {
00062     ROS_WARN("WristTransmissionCal could not find actuator named \"%s\"", actuator_name);
00063     return false;
00064   }
00065   a->command_.enable_ = true;
00066   actuator_names_.push_back(actuator_name);
00067   const char *act_red = ael->Attribute("mechanicalReduction");
00068   if (!act_red)
00069     {
00070       ROS_WARN("WristTransmissionCal's actuator \"%s\" was not given a reduction.", actuator_name);
00071       return false;
00072     }
00073   actuator_reduction_.push_back(atof(act_red));
00074 
00075   ael = elt->FirstChildElement("leftActuator");
00076   actuator_name = ael ? ael->Attribute("name") : NULL;
00077   if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00078   {
00079     ROS_WARN("WristTransmissionCal could not find actuator named \"%s\"", actuator_name);
00080     return false;
00081   }
00082   a->command_.enable_ = true;
00083   actuator_names_.push_back(actuator_name);
00084   act_red = ael->Attribute("mechanicalReduction");
00085   if (!act_red)
00086     {
00087       ROS_WARN("WristTransmissionCal's actuator \"%s\" was not given a reduction.", actuator_name);
00088       return false;
00089     }
00090   actuator_reduction_.push_back(atof(act_red));
00091 
00092 
00093   TiXmlElement *j = elt->FirstChildElement("flexJoint");
00094   const char *joint_name = j->Attribute("name");
00095   if (!joint_name)
00096   {
00097     ROS_ERROR("WristTransmissionCal did not specify joint name");
00098     return false;
00099   }
00100   const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00101 
00102   if (!joint)
00103   {
00104     ROS_ERROR("WristTransmissionCal could not find joint named \"%s\"", joint_name);
00105     return false;
00106   }
00107   joint_names_.push_back(joint_name);
00108   const char *joint_red = j->Attribute("mechanicalReduction");
00109   if (!joint_red)
00110   {
00111     ROS_WARN("WristTransmissionCal's joint \"%s\" was not given a reduction.", joint_name);
00112     return false;
00113   }
00114   joint_reduction_.push_back(atof(joint_red));
00115 
00116   j = elt->FirstChildElement("rollJoint");
00117   joint_name = j->Attribute("name");
00118   if (!joint_name)
00119   {
00120     ROS_ERROR("WristTransmissionCal did not specify joint name");
00121     return false;
00122   }
00123   const boost::shared_ptr<const urdf::Joint> joint2 = robot->robot_model_.getJoint(joint_name);
00124 
00125   if (!joint2)
00126   {
00127     ROS_ERROR("WristTransmissionCal could not find joint named \"%s\"", joint_name);
00128     return false;
00129   }
00130   joint_names_.push_back(joint_name);
00131   joint_red = j->Attribute("mechanicalReduction");
00132   if (!joint_red)
00133   {
00134     ROS_WARN("WristTransmissionCal's joint \"%s\" was not given a reduction.", joint_name);
00135     return false;
00136   }
00137   joint_reduction_.push_back(atof(joint_red));
00138 
00139 
00140   return true;
00141 }
00142 
00143 void WristTransmissionCal::propagatePosition(
00144   std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00145 {
00146   assert(as.size() == 2);
00147   assert(js.size() == 2);
00148 
00149   js[0]->position_ = (as[0]->state_.position_ / actuator_reduction_[0] - as[1]->state_.position_ / actuator_reduction_[1])/(2*joint_reduction_[0]);
00150   js[0]->velocity_ = (as[0]->state_.velocity_ / actuator_reduction_[0] - as[1]->state_.velocity_ / actuator_reduction_[1])/(2*joint_reduction_[0]);
00151   js[0]->measured_effort_ = joint_reduction_[0]*(as[0]->state_.last_measured_effort_ * actuator_reduction_[0] - as[1]->state_.last_measured_effort_ * actuator_reduction_[1]);
00152 
00153   js[1]->position_ = (-as[0]->state_.position_ / actuator_reduction_[0] - as[1]->state_.position_ / actuator_reduction_[1])/(2*joint_reduction_[1]);
00154   js[1]->velocity_ = (-as[0]->state_.velocity_ / actuator_reduction_[0] - as[1]->state_.velocity_ / actuator_reduction_[1])/(2*joint_reduction_[1]);
00155   js[1]->measured_effort_ = joint_reduction_[1]*(-as[0]->state_.last_measured_effort_ * actuator_reduction_[0] - as[1]->state_.last_measured_effort_ * actuator_reduction_[1]);
00156 }
00157 
00158 void WristTransmissionCal::propagatePositionBackwards(
00159   std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00160 {
00161   assert(as.size() == 2);
00162   assert(js.size() == 2);
00163 
00164   as[0]->state_.position_ = ((js[0]->position_*joint_reduction_[0] - js[1]->position_*joint_reduction_[1]) * actuator_reduction_[0]);
00165   as[0]->state_.velocity_ = ((js[0]->velocity_*joint_reduction_[0] - js[1]->velocity_*joint_reduction_[1]) * actuator_reduction_[0]);
00166   as[0]->state_.last_measured_effort_ = (js[0]->measured_effort_/joint_reduction_[0] - js[1]->measured_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[0]);
00167 
00168   as[1]->state_.position_ = ((-js[0]->position_*joint_reduction_[0] - js[1]->position_*joint_reduction_[1]) * actuator_reduction_[1]);
00169   as[1]->state_.velocity_ = ((-js[0]->velocity_*joint_reduction_[0] - js[1]->velocity_*joint_reduction_[1]) * actuator_reduction_[1]);
00170   as[1]->state_.last_measured_effort_ = (-js[0]->measured_effort_/joint_reduction_[0] - js[1]->measured_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[1]);
00171 
00172   
00173   
00174   this->joint_calibration_simulator_[0].simulateJointCalibration(js[0],as[1]);
00175   this->joint_calibration_simulator_[1].simulateJointCalibration(js[1],as[0]);
00176 }
00177 
00178 void WristTransmissionCal::propagateEffort(
00179   std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00180 {
00181   assert(as.size() == 2);
00182   assert(js.size() == 2);
00183 
00184   as[0]->command_.effort_ = (js[0]->commanded_effort_/joint_reduction_[0] - js[1]->commanded_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[0]);
00185   as[1]->command_.effort_ = (-js[0]->commanded_effort_/joint_reduction_[0] - js[1]->commanded_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[1]);
00186 }
00187 
00188 void WristTransmissionCal::propagateEffortBackwards(
00189   std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00190 {
00191   assert(as.size() == 2);
00192   assert(js.size() == 2);
00193 
00194   js[0]->commanded_effort_ = joint_reduction_[0]*(as[0]->command_.effort_ * actuator_reduction_[0] - as[1]->command_.effort_ * actuator_reduction_[1]);
00195   js[1]->commanded_effort_ = joint_reduction_[1]*(-as[0]->command_.effort_ * actuator_reduction_[0] - as[1]->command_.effort_ * actuator_reduction_[1]);
00196 }
00197 
00198 
00199 void WristTransmissionCal::setReductions(std::vector<double>& ar, std::vector<double>& jr)
00200 {
00201   actuator_reduction_ = ar;
00202   joint_reduction_ = jr;
00203 }
00204