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