00001 /* 00002 * robot_state.hpp 00003 * 00004 * Created on: 7 Jan 2014 00005 * Author: Manos Nikolaidis 00006 * 00007 * Software License Agreement (BSD License) 00008 * 00009 * Copyright (c) 2014, Shadow Robot Company Ltd. 00010 * All rights reserved. 00011 * 00012 * Redistribution and use in source and binary forms, with or without 00013 * modification, are permitted provided that the following conditions 00014 * are met: 00015 * 00016 * * Redistributions of source code must retain the above copyright 00017 * notice, this list of conditions and the following disclaimer. 00018 * * Redistributions in binary form must reproduce the above 00019 * copyright notice, this list of conditions and the following 00020 * disclaimer in the documentation and/or other materials provided 00021 * with the distribution. 00022 * * Neither the name of the Willow Garage nor the names of its 00023 * contributors may be used to endorse or promote products derived 00024 * from this software without specific prior written permission. 00025 * 00026 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00027 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00028 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00029 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00030 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00031 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00032 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00033 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00034 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00035 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00036 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 * POSSIBILITY OF SUCH DAMAGE. 00038 *********************************************************************/ 00039 00040 #ifndef ROS_ETHERCAT_MODEL_ROBOTSTATE_HPP 00041 #define ROS_ETHERCAT_MODEL_ROBOTSTATE_HPP 00042 00043 #include <urdf/model.h> 00044 #include <pluginlib/class_loader.h> 00045 #include <boost/ptr_container/ptr_unordered_map.hpp> 00046 #include <boost/ptr_container/ptr_vector.hpp> 00047 #include <hardware_interface/hardware_interface.h> 00048 #include "ros_ethercat_model/joint.hpp" 00049 #include "ros_ethercat_model/transmission.hpp" 00050 #include "ros_ethercat_model/hardware_interface.hpp" 00051 00052 namespace ros_ethercat_model 00053 { 00054 00061 class RobotState : public hardware_interface::HardwareInterface 00062 { 00063 public: 00064 RobotState(TiXmlElement *root) 00065 : transmission_loader_("ros_ethercat_model", "ros_ethercat_model::Transmission") 00066 { 00067 if (root) 00068 initXml(root); 00069 } 00070 void initXml(TiXmlElement *root) 00071 { 00072 try 00073 { 00074 if (!robot_model_.initXml(root)) 00075 throw std::runtime_error("Failed to load robot_model_"); 00076 00077 for (std::map<std::string, boost::shared_ptr<urdf::Joint> >::const_iterator it = robot_model_.joints_.begin(); 00078 it != robot_model_.joints_.end(); 00079 ++it) 00080 { 00081 // we are only loading joints that can be controlled 00082 if (it->second->type == urdf::Joint::PRISMATIC || it->second->type == urdf::Joint::REVOLUTE) 00083 joint_states_[it->first].joint_ = it->second; 00084 } 00085 00086 for (TiXmlElement *xit = root->FirstChildElement("transmission"); 00087 xit; 00088 xit = xit->NextSiblingElement("transmission")) 00089 { 00090 std::string type = xit->Attribute("type"); 00091 00092 Transmission *t = transmission_loader_.createUnmanagedInstance(type); 00093 if (!t || !t->initXml(xit, this)) 00094 throw std::runtime_error(std::string("Failed to initialize transmission type: ") + type); 00095 transmissions_.push_back(t); 00096 } 00097 } 00098 catch (const std::runtime_error &ex) 00099 { 00100 ROS_FATAL_STREAM("ros_ethercat_model failed to parse the URDF xml into a robot model\n" << ex.what()); 00101 } 00102 } 00103 00105 void propagateActuatorPositionToJointPosition() 00106 { 00107 for (size_t i = 0; i < transmissions_.size(); ++i) 00108 transmissions_[i].propagatePosition(); 00109 } 00110 00112 void propagateJointEffortToActuatorEffort() 00113 { 00114 for (size_t i = 0; i < transmissions_.size(); ++i) 00115 transmissions_[i].propagateEffort(); 00116 } 00117 00119 Actuator* getActuator(const std::string &name) 00120 { 00121 for (size_t i = 0; i < transmissions_.size(); ++i) 00122 if (transmissions_[i].actuator_->name_ == name) 00123 return transmissions_[i].actuator_; 00124 return NULL; 00125 } 00126 00128 CustomHW* getCustomHW(const std::string &name) 00129 { 00130 return custom_hws_.count(name) ? &custom_hws_[name] : NULL; 00131 } 00132 00134 JointState* getJointState(const std::string &name) 00135 { 00136 return joint_states_.count(name) ? &joint_states_[name] : NULL; 00137 } 00138 00140 ros::Time getTime() 00141 { 00142 return current_time_; 00143 } 00144 00146 ros::Time current_time_; 00147 00149 boost::ptr_unordered_map<std::string, JointState> joint_states_; 00150 00152 boost::ptr_unordered_map<std::string, CustomHW> custom_hws_; 00153 00155 urdf::Model robot_model_; 00156 00158 boost::ptr_vector<Transmission> transmissions_; 00159 00161 pluginlib::ClassLoader<Transmission> transmission_loader_; 00162 }; 00163 } 00164 #endif