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: Wim Meeussen */ 00036 00037 #ifndef URDF_INTERFACE_JOINT_H 00038 #define URDF_INTERFACE_JOINT_H 00039 00040 #include <string> 00041 #include <vector> 00042 #include <tinyxml.h> 00043 #include <boost/shared_ptr.hpp> 00044 00045 #include "pose.h" 00046 00047 namespace urdf{ 00048 00049 class Link; 00050 00051 class JointDynamics 00052 { 00053 public: 00054 JointDynamics() { this->clear(); }; 00055 double damping; 00056 double friction; 00057 00058 void clear() 00059 { 00060 damping = 0; 00061 friction = 0; 00062 }; 00063 bool initXml(TiXmlElement* config); 00064 }; 00065 00066 class JointLimits 00067 { 00068 public: 00069 JointLimits() { this->clear(); }; 00070 double lower; 00071 double upper; 00072 double effort; 00073 double velocity; 00074 00075 void clear() 00076 { 00077 lower = 0; 00078 upper = 0; 00079 effort = 0; 00080 velocity = 0; 00081 }; 00082 bool initXml(TiXmlElement* config); 00083 }; 00084 00086 class JointSafety 00087 { 00088 public: 00090 JointSafety() { this->clear(); }; 00091 00123 double soft_upper_limit; 00124 double soft_lower_limit; 00125 double k_position; 00126 double k_velocity; 00127 00128 void clear() 00129 { 00130 soft_upper_limit = 0; 00131 soft_lower_limit = 0; 00132 k_position = 0; 00133 k_velocity = 0; 00134 }; 00135 bool initXml(TiXmlElement* config); 00136 }; 00137 00138 00139 class JointCalibration 00140 { 00141 public: 00142 JointCalibration() { this->clear(); }; 00143 double reference_position; 00144 boost::shared_ptr<double> rising, falling; 00145 00146 void clear() 00147 { 00148 reference_position = 0; 00149 }; 00150 bool initXml(TiXmlElement* config); 00151 }; 00152 00153 class JointMimic 00154 { 00155 public: 00156 JointMimic() { this->clear(); }; 00157 double offset; 00158 double multiplier; 00159 std::string joint_name; 00160 00161 void clear() 00162 { 00163 offset = 0.0; 00164 multiplier = 0.0; 00165 joint_name.clear(); 00166 }; 00167 bool initXml(TiXmlElement* config); 00168 }; 00169 00170 00171 class Joint 00172 { 00173 public: 00174 00175 Joint() { this->clear(); }; 00176 00177 std::string name; 00178 enum 00179 { 00180 UNKNOWN, REVOLUTE, CONTINUOUS, PRISMATIC, FLOATING, PLANAR, FIXED 00181 } type; 00182 00191 Vector3 axis; 00192 00195 std::string child_link_name; 00196 00199 std::string parent_link_name; 00201 Pose parent_to_joint_origin_transform; 00202 00204 boost::shared_ptr<JointDynamics> dynamics; 00205 00207 boost::shared_ptr<JointLimits> limits; 00208 00210 boost::shared_ptr<JointSafety> safety; 00211 00213 boost::shared_ptr<JointCalibration> calibration; 00214 00216 boost::shared_ptr<JointMimic> mimic; 00217 00218 bool initXml(TiXmlElement* xml); 00219 void clear() 00220 { 00221 this->axis.clear(); 00222 this->child_link_name.clear(); 00223 this->parent_link_name.clear(); 00224 this->parent_to_joint_origin_transform.clear(); 00225 this->dynamics.reset(); 00226 this->limits.reset(); 00227 this->safety.reset(); 00228 this->calibration.reset(); 00229 this->type = UNKNOWN; 00230 }; 00231 }; 00232 00233 } 00234 00235 #endif