simple_transmission.cpp
Go to the documentation of this file.
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  * Author: Stuart Glaser
00036  *
00037  * modified by Ugo Cupcic
00038  */
00039 
00040 #include <math.h>
00041 #include <pluginlib/class_list_macros.h>
00042 #include "pr2_mechanism_model/robot.h"
00043 #include "sr_mechanism_model/simple_transmission.h"
00044 
00045 #include <sr_hardware_interface/sr_actuator.hpp>
00046 
00047 using namespace pr2_hardware_interface;
00048 
00049 PLUGINLIB_EXPORT_CLASS(sr_mechanism_model::SimpleTransmission, pr2_mechanism_model::Transmission)
00050 
00051 namespace sr_mechanism_model
00052 {
00053   bool SimpleTransmission::initXml(TiXmlElement *elt, pr2_mechanism_model::Robot *robot)
00054   {
00055     const char *name = elt->Attribute("name");
00056     name_ = name ? name : "";
00057 
00058     TiXmlElement *jel = elt->FirstChildElement("joint");
00059     const char *joint_name = jel ? jel->Attribute("name") : NULL;
00060     if (!joint_name)
00061     {
00062       ROS_ERROR("SimpleTransmission did not specify joint name");
00063       return false;
00064     }
00065 
00066     const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00067     if (!joint)
00068     {
00069       ROS_ERROR("SimpleTransmission could not find joint named \"%s\"", joint_name);
00070       return false;
00071     }
00072     joint_names_.push_back(joint_name);
00073 
00074     TiXmlElement *ael = elt->FirstChildElement("actuator");
00075     const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00076     pr2_hardware_interface::Actuator *a;
00077     if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00078     {
00079       ROS_ERROR("SimpleTransmission 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 
00085     mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00086 
00087     return true;
00088   }
00089 
00090   bool SimpleTransmission::initXml(TiXmlElement *elt)
00091   {
00092     const char *name = elt->Attribute("name");
00093     name_ = name ? name : "";
00094 
00095     TiXmlElement *jel = elt->FirstChildElement("joint");
00096     const char *joint_name = jel ? jel->Attribute("name") : NULL;
00097     if (!joint_name)
00098     {
00099       ROS_ERROR("SimpleTransmission did not specify joint name");
00100       return false;
00101     }
00102     joint_names_.push_back(joint_name);
00103 
00104     TiXmlElement *ael = elt->FirstChildElement("actuator");
00105     const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00106     if (!actuator_name)
00107     {
00108       ROS_ERROR("SimpleTransmission could not find actuator named \"%s\"", actuator_name);
00109       return false;
00110     }
00111     actuator_names_.push_back(actuator_name);
00112 
00113     mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00114 
00115     return true;
00116   }
00117 
00118   void SimpleTransmission::propagatePosition(
00119     std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00120   {
00121     ROS_DEBUG(" propagate position");
00122 
00123     assert(as.size() == 1);
00124     assert(js.size() == 1);
00125     js[0]->position_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_;
00126     js[0]->velocity_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_;
00127     js[0]->measured_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_;
00128 
00129     ROS_DEBUG("end propagate position");
00130   }
00131 
00132   void SimpleTransmission::propagatePositionBackwards(
00133     std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00134   {
00135     ROS_DEBUG(" propagate position bw");
00136 
00137     assert(as.size() == 1);
00138     assert(js.size() == 1);
00139     static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ = js[0]->position_;
00140     static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ = js[0]->velocity_;
00141     static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_ = js[0]->measured_effort_;
00142 
00143     // Update the timing (making sure it's initialized).
00144     if (! simulated_actuator_timestamp_initialized_)
00145     {
00146       // Set the time stamp to zero (it is measured relative to the start time).
00147       static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_ = ros::Duration(0);
00148 
00149       // Try to set the start time.  Only then do we claim initialized.
00150       if (ros::isStarted())
00151       {
00152         simulated_actuator_start_time_ = ros::Time::now();
00153         simulated_actuator_timestamp_initialized_ = true;
00154       }
00155     }
00156     else
00157     {
00158       // Measure the time stamp relative to the start time.
00159       static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00160     }
00161     // Set the historical (double) timestamp accordingly.
00162     static_cast<sr_actuator::SrActuator*>(as[0])->state_.timestamp_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_.toSec();
00163 
00164     // simulate calibration sensors by filling out actuator states
00165     this->joint_calibration_simulator_.simulateJointCalibration(js[0],static_cast<sr_actuator::SrActuator*>(as[0]));
00166 
00167     ROS_DEBUG(" end propagate position bw");
00168   }
00169 
00170   void SimpleTransmission::propagateEffort(
00171     std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00172   {
00173     ROS_DEBUG(" propagate effort");
00174 
00175     assert(as.size() == 1);
00176     assert(js.size() == 1);
00177     static_cast<sr_actuator::SrActuator*>(as[0])->command_.enable_ = true;
00178     static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_ = js[0]->commanded_effort_;
00179 
00180     ROS_DEBUG("end propagate effort");
00181   }
00182 
00183   void SimpleTransmission::propagateEffortBackwards(
00184     std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00185   {
00186     ROS_DEBUG(" propagate effort bw");
00187 
00188     assert(as.size() == 1);
00189     assert(js.size() == 1);
00190     js[0]->commanded_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_;
00191 
00192     ROS_DEBUG("end propagate effort bw");
00193   }
00194 
00195 } //end namespace
00196 
00197 /* For the emacs weenies in the crowd.
00198 Local Variables:
00199    c-basic-offset: 2
00200 End:
00201 */


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