joint_0_transmission.cpp
Go to the documentation of this file.
00001 
00029 #include "sr_mechanism_model/joint_0_transmission.hpp"
00030 
00031 #include <math.h>
00032 #include <pluginlib/class_list_macros.h>
00033 #include "pr2_mechanism_model/robot.h"
00034 #include "pr2_mechanism_model/simple_transmission.h"
00035 
00036 #include <sr_hardware_interface/sr_actuator.hpp>
00037 
00038 using namespace pr2_hardware_interface;
00039 
00040 PLUGINLIB_EXPORT_CLASS(sr_mechanism_model::J0Transmission, pr2_mechanism_model::Transmission)
00041 
00042 namespace sr_mechanism_model
00043 {
00044   bool J0Transmission::initXml(TiXmlElement *elt, pr2_mechanism_model::Robot *robot)
00045   {
00046     const char *name = elt->Attribute("name");
00047     name_ = name ? name : "";
00048 
00049     TiXmlElement *jel = elt->FirstChildElement("joint1");
00050     init_joint(jel, robot);
00051     TiXmlElement *jel2 = elt->FirstChildElement("joint2");
00052     init_joint(jel2, robot);
00053 
00054     TiXmlElement *ael = elt->FirstChildElement("actuator");
00055     const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00056     Actuator *a;
00057     if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00058     {
00059       ROS_ERROR("J0Transmission could not find actuator named \"%s\"", actuator_name);
00060       return false;
00061     }
00062     a->command_.enable_ = true;
00063     actuator_names_.push_back(actuator_name);
00064 
00065     mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00066 
00067     return true;
00068   }
00069 
00070   bool J0Transmission::initXml(TiXmlElement *elt)
00071   {
00072     const char *name = elt->Attribute("name");
00073     name_ = name ? name : "";
00074 
00075     TiXmlElement *jel = elt->FirstChildElement("joint1");
00076     init_joint(jel, NULL);
00077     TiXmlElement *jel2 = elt->FirstChildElement("joint2");
00078     init_joint(jel2, NULL);
00079 
00080 
00081     TiXmlElement *ael = elt->FirstChildElement("actuator");
00082     const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00083     if (!actuator_name)
00084     {
00085       ROS_ERROR("J0Transmission could not find actuator named \"%s\"", actuator_name);
00086       return false;
00087     }
00088     actuator_names_.push_back(actuator_name);
00089 
00090     mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00091 
00092     return true;
00093   }
00094 
00095   bool J0Transmission::init_joint(TiXmlElement *jel, pr2_mechanism_model::Robot *robot)
00096   {
00097     const char *joint_name = jel ? jel->Attribute("name") : NULL;
00098     if (!joint_name)
00099     {
00100       ROS_ERROR("J0Transmission did not specify joint name");
00101       return false;
00102     }
00103 
00104     if( robot != NULL )
00105     {
00106       const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00107       if (!joint)
00108       {
00109         ROS_ERROR("J0Transmission could not find joint named \"%s\"", joint_name);
00110         return false;
00111       }
00112     }
00113     joint_names_.push_back(joint_name);
00114 
00115     return true;
00116   }
00117 
00118   void J0Transmission::propagatePosition(
00119     std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00120   {
00121     ROS_DEBUG(" propagate position for j0");
00122 
00123     assert(as.size() == 1);
00124     assert(js.size() == 2);
00125 
00126     //the size is either 0 (when the joint hasn't been updated yet), either 2
00127     // (joint 0 is composed of the 2 calibrated values: joint 1 and joint 2)
00128     int size = static_cast<sr_actuator::SrActuator*>(as[0])->state_.calibrated_sensor_values_.size();
00129     if( size != 0)
00130     {
00131       if( size == 2 )
00132       {
00133         ROS_DEBUG_STREAM( "READING pos " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_
00134                           << " J1 " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.calibrated_sensor_values_[0]
00135                           << " J2 " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.calibrated_sensor_values_[1] );
00136 
00137         js[0]->position_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.calibrated_sensor_values_[0];
00138         js[1]->position_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.calibrated_sensor_values_[1];
00139 
00140         js[0]->velocity_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ / 2.0;
00141         js[1]->velocity_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ / 2.0;
00142 
00143         js[0]->measured_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_;
00144         js[1]->measured_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_;
00145       }
00146     }
00147     else
00148     {
00149       ROS_DEBUG_STREAM( "READING pos from Gazebo " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_
00150                         << " J1 " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ / 2.0
00151                         << " J2 " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ / 2.0 );
00152 
00153       //TODO: use a real formula for the coupling??
00154       //GAZEBO
00155       js[0]->position_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ / 2.0;
00156       js[1]->position_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ / 2.0;
00157 
00158       js[0]->velocity_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ / 2.0;
00159       js[1]->velocity_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ / 2.0;
00160 
00161       js[0]->measured_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_ / 2.0;
00162       js[1]->measured_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_ / 2.0;
00163     }
00164 
00165     ROS_DEBUG("end propagate position for j0");
00166   }
00167 
00168   void J0Transmission::propagatePositionBackwards(
00169     std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00170   {
00171     ROS_DEBUG("propagate pos backward for j0");
00172 
00173     assert(as.size() == 1);
00174     assert(js.size() == 2);
00175 
00176     ROS_DEBUG_STREAM("  pos = " << js[0]->position_ << " + " << js[1]->position_ << " = " << static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_);
00177     static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ = js[0]->position_ + js[1]->position_;
00178     static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ = js[0]->velocity_ + js[1]->velocity_;
00179     static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_ = js[0]->measured_effort_ + js[1]->measured_effort_;
00180 
00181     // Update the timing (making sure it's initialized).
00182     if (! simulated_actuator_timestamp_initialized_)
00183     {
00184       // Set the time stamp to zero (it is measured relative to the start time).
00185       static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_ = ros::Duration(0);
00186 
00187       // Try to set the start time.  Only then do we claim initialized.
00188       if (ros::isStarted())
00189       {
00190         simulated_actuator_start_time_ = ros::Time::now();
00191         simulated_actuator_timestamp_initialized_ = true;
00192       }
00193     }
00194     else
00195     {
00196       // Measure the time stamp relative to the start time.
00197       static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00198     }
00199     // Set the historical (double) timestamp accordingly.
00200     static_cast<sr_actuator::SrActuator*>(as[0])->state_.timestamp_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_.toSec();
00201 
00202     // simulate calibration sensors by filling out actuator states
00203     this->joint_calibration_simulator_.simulateJointCalibration(js[0],static_cast<sr_actuator::SrActuator*>(as[0]));
00204 
00205     ROS_DEBUG(" end propagate pos backward for j0");
00206   }
00207 
00208   void J0Transmission::propagateEffort(
00209     std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00210   {
00211     ROS_DEBUG(" propagate effort for j0");
00212 
00213     assert(as.size() == 1);
00214     assert(js.size() == 2);
00215     static_cast<sr_actuator::SrActuator*>(as[0])->command_.enable_ = true;
00216     static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_ = (js[0]->commanded_effort_ + js[1]->commanded_effort_);
00217 
00218     ROS_DEBUG("end propagate effort for j0");
00219   }
00220 
00221   void J0Transmission::propagateEffortBackwards(
00222     std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00223   {
00224     ROS_DEBUG("propagate effort backward for j0");
00225 
00226     assert(as.size() == 1);
00227     assert(js.size() == 2);
00228     js[0]->commanded_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_;
00229     js[1]->commanded_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_;
00230 
00231     ROS_DEBUG("end propagate effort backward for j0");
00232   }
00233 
00234 } //end namespace sr_mechanism_model
00235 
00236 /* For the emacs weenies in the crowd.
00237 Local Variables:
00238    c-basic-offset: 2
00239 End:
00240 */


sr_mechanism_model
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:16