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/simple_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, SimpleTransmissionCal, 
00047                         pr2_bringup_gazebo_demo::SimpleTransmissionCal, 
00048                         pr2_mechanism_model::Transmission)
00049 
00050 
00051 bool SimpleTransmissionCal::initXml(TiXmlElement *elt, pr2_mechanism_model::Robot *robot)
00052 {
00053   const char *name = elt->Attribute("name");
00054   name_ = name ? name : "";
00055 
00056   TiXmlElement *jel = elt->FirstChildElement("joint");
00057   const char *joint_name = jel ? jel->Attribute("name") : NULL;
00058   if (!joint_name)
00059   {
00060     ROS_ERROR("SimpleTransmissionCal did not specify joint name");
00061     return false;
00062   }
00063 
00064   const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00065   if (!joint)
00066   {
00067     ROS_ERROR("SimpleTransmissionCal could not find joint named \"%s\"", joint_name);
00068     return false;
00069   }
00070   joint_names_.push_back(joint_name);
00071 
00072   TiXmlElement *ael = elt->FirstChildElement("actuator");
00073   const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00074   Actuator *a;
00075   if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00076   {
00077     ROS_ERROR("SimpleTransmissionCal could not find actuator named \"%s\"", actuator_name);
00078     return false;
00079   }
00080   a->command_.enable_ = true;
00081   actuator_names_.push_back(actuator_name);
00082 
00083   mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00084 
00085   return true;
00086 }
00087 
00088 void SimpleTransmissionCal::propagatePosition(
00089    std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00090 {
00091   assert(as.size() == 1);
00092   assert(js.size() == 1);
00093   js[0]->position_ = as[0]->state_.position_ / mechanical_reduction_;
00094   js[0]->velocity_ = as[0]->state_.velocity_ / mechanical_reduction_;
00095   js[0]->measured_effort_ = as[0]->state_.last_measured_effort_ * mechanical_reduction_;
00096 }
00097 
00098 void SimpleTransmissionCal::propagatePositionBackwards(
00099   std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00100 {
00101   assert(as.size() == 1);
00102   assert(js.size() == 1);
00103   as[0]->state_.position_ = js[0]->position_ * mechanical_reduction_;
00104   as[0]->state_.velocity_ = js[0]->velocity_ * mechanical_reduction_;
00105   as[0]->state_.last_measured_effort_ = js[0]->measured_effort_ / mechanical_reduction_;
00106 
00107   
00108   this->joint_calibration_simulator_.simulateJointCalibration(js[0],as[0]);
00109 }
00110 
00111 void SimpleTransmissionCal::propagateEffort(
00112    std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00113 {
00114   assert(as.size() == 1);
00115   assert(js.size() == 1);
00116   as[0]->command_.effort_ = js[0]->commanded_effort_ / mechanical_reduction_;
00117 }
00118 
00119 void SimpleTransmissionCal::propagateEffortBackwards(
00120   std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00121 {
00122   assert(as.size() == 1);
00123   assert(js.size() == 1);
00124   js[0]->commanded_effort_ = as[0]->command_.effort_ * mechanical_reduction_;
00125 }
00126