pose.h
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: Wim Meeussen */
00036 
00037 #ifndef URDF_INTERFACE_POSE_H
00038 #define URDF_INTERFACE_POSE_H
00039 
00040 #include <string>
00041 #include <vector>
00042 #include <math.h>
00043 #include <boost/algorithm/string.hpp>
00044 #include <boost/lexical_cast.hpp>
00045 
00046 #include <tinyxml.h> // FIXME: remove parser from here
00047 #include <ros/console.h>
00048 
00049 namespace urdf{
00050 
00051 class Vector3
00052 {
00053 public:
00054   Vector3(double _x,double _y, double _z) {this->x=_x;this->y=_y;this->z=_z;};
00055   Vector3() {this->clear();};
00056   double x;
00057   double y;
00058   double z;
00059 
00060   void clear() {this->x=this->y=this->z=0.0;};
00061   bool init(const std::string &vector_str)
00062   {
00063     this->clear();
00064     std::vector<std::string> pieces;
00065     std::vector<double> xyz;
00066     boost::split( pieces, vector_str, boost::is_any_of(" "));
00067     for (unsigned int i = 0; i < pieces.size(); ++i){
00068       if (pieces[i] != ""){
00069         try
00070         {
00071           xyz.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
00072         }
00073         catch (boost::bad_lexical_cast &e)
00074         {
00075           ROS_ERROR("Vector3 xyz element (%s) is not a valid float",pieces[i].c_str());
00076           return false;
00077         }
00078       }
00079     }
00080 
00081     if (xyz.size() != 3) {
00082         ROS_ERROR("Vector contains %i elements instead of 3 elements", (int)xyz.size()); 
00083       return false;
00084     }
00085 
00086     this->x = xyz[0];
00087     this->y = xyz[1];
00088     this->z = xyz[2];
00089 
00090     return true;
00091   };
00092   Vector3 operator+(Vector3 vec)
00093   {
00094     return Vector3(this->x+vec.x,this->y+vec.y,this->z+vec.z);
00095   };
00096 };
00097 
00098 class Rotation
00099 {
00100 public:
00101   Rotation(double _x,double _y, double _z, double _w) {this->x=_x;this->y=_y;this->z=_z;this->w=_w;};
00102   Rotation() {this->clear();};
00103   void getQuaternion(double &quat_x,double &quat_y,double &quat_z, double &quat_w) const
00104   {
00105     quat_x = this->x;
00106     quat_y = this->y;
00107     quat_z = this->z;
00108     quat_w = this->w;
00109   };
00110   void getRPY(double &roll,double &pitch,double &yaw) const
00111   {
00112     double sqw;
00113     double sqx;
00114     double sqy;
00115     double sqz;
00116 
00117     sqx = this->x * this->x;
00118     sqy = this->y * this->y;
00119     sqz = this->z * this->z;
00120     sqw = this->w * this->w;
00121 
00122     roll  = atan2(2 * (this->y*this->z + this->w*this->x), sqw - sqx - sqy + sqz);
00123     double sarg = -2 * (this->x*this->z - this->w*this->y);
00124     pitch = sarg <= -1.0 ? -0.5*M_PI : (sarg >= 1.0 ? 0.5*M_PI : asin(sarg));
00125     yaw   = atan2(2 * (this->x*this->y + this->w*this->z), sqw + sqx - sqy - sqz);
00126 
00127   };
00128   void setFromQuaternion(double quat_x,double quat_y,double quat_z,double quat_w)
00129   {
00130     this->x = quat_x;
00131     this->y = quat_y;
00132     this->z = quat_z;
00133     this->w = quat_w;
00134     this->normalize();
00135   };
00136   void setFromRPY(double roll, double pitch, double yaw)
00137   {
00138     double phi, the, psi;
00139 
00140     phi = roll / 2.0;
00141     the = pitch / 2.0;
00142     psi = yaw / 2.0;
00143 
00144     this->x = sin(phi) * cos(the) * cos(psi) - cos(phi) * sin(the) * sin(psi);
00145     this->y = cos(phi) * sin(the) * cos(psi) + sin(phi) * cos(the) * sin(psi);
00146     this->z = cos(phi) * cos(the) * sin(psi) - sin(phi) * sin(the) * cos(psi);
00147     this->w = cos(phi) * cos(the) * cos(psi) + sin(phi) * sin(the) * sin(psi);
00148 
00149     this->normalize();
00150   };
00151 
00152   double x,y,z,w;
00153 
00154   bool init(const std::string &rotation_str)
00155   {
00156     this->clear();
00157 
00158     Vector3 rpy;
00159     
00160     if (!rpy.init(rotation_str))
00161       return false;
00162     else
00163     {
00164       this->setFromRPY(rpy.x,rpy.y,rpy.z);
00165       return true;
00166     }
00167       
00168   };
00169 
00170   void clear() { this->x=this->y=this->z=0.0;this->w=1.0; }
00171 
00172   void normalize()
00173   {
00174     double s = sqrt(this->x * this->x +
00175                     this->y * this->y +
00176                     this->z * this->z +
00177                     this->w * this->w);
00178     if (s == 0.0)
00179     {
00180       this->x = 0.0;
00181       this->y = 0.0;
00182       this->z = 0.0;
00183       this->w = 1.0;
00184     }
00185     else
00186     {
00187       this->x /= s;
00188       this->y /= s;
00189       this->z /= s;
00190       this->w /= s;
00191     }
00192   };
00193 
00194   // Multiplication operator (copied from gazebo)
00195   Rotation operator*( const Rotation &qt ) const
00196   {
00197     Rotation c;
00198 
00199     c.x = this->w * qt.x + this->x * qt.w + this->y * qt.z - this->z * qt.y;
00200     c.y = this->w * qt.y - this->x * qt.z + this->y * qt.w + this->z * qt.x;
00201     c.z = this->w * qt.z + this->x * qt.y - this->y * qt.x + this->z * qt.w;
00202     c.w = this->w * qt.w - this->x * qt.x - this->y * qt.y - this->z * qt.z;
00203 
00204     return c;
00205   };
00207   Vector3 operator*(Vector3 vec) const
00208   {
00209     Rotation tmp;
00210     Vector3 result;
00211 
00212     tmp.w = 0.0;
00213     tmp.x = vec.x;
00214     tmp.y = vec.y;
00215     tmp.z = vec.z;
00216 
00217     tmp = (*this) * (tmp * this->GetInverse());
00218 
00219     result.x = tmp.x;
00220     result.y = tmp.y;
00221     result.z = tmp.z;
00222 
00223     return result;
00224   };
00225   // Get the inverse of this quaternion
00226   Rotation GetInverse() const 
00227   {
00228     Rotation q;
00229 
00230     double norm = this->w*this->w+this->x*this->x+this->y*this->y+this->z*this->z;
00231 
00232     if (norm > 0.0)
00233     {
00234       q.w = this->w / norm;
00235       q.x = -this->x / norm;
00236       q.y = -this->y / norm;
00237       q.z = -this->z / norm;
00238     }
00239 
00240     return q;
00241   };
00242 
00243 
00244 };
00245 
00246 class Pose
00247 {
00248 public:
00249   Pose() { this->clear(); };
00250 
00251   Vector3  position;
00252   Rotation rotation;
00253 
00254   void clear()
00255   {
00256     this->position.clear();
00257     this->rotation.clear();
00258   };
00259   bool initXml(TiXmlElement* xml)
00260   {
00261     this->clear();
00262     if (!xml)
00263     {
00264       ROS_DEBUG("parsing pose: xml empty");
00265       return false;
00266     }
00267     else
00268     {
00269       const char* xyz_str = xml->Attribute("xyz");
00270       if (xyz_str == NULL)
00271       {
00272         ROS_DEBUG("parsing pose: no xyz, using default values.");
00273         return true;
00274       }
00275       else
00276       {
00277         if (!this->position.init(xyz_str))
00278         {
00279           ROS_ERROR("malformed xyz");
00280           this->position.clear();
00281           return false;
00282         }
00283       }
00284 
00285       const char* rpy_str = xml->Attribute("rpy");
00286       if (rpy_str == NULL)
00287       {
00288         ROS_DEBUG("parsing pose: no rpy, using default values.");
00289         return true;
00290       }
00291       else
00292       {
00293         if (!this->rotation.init(rpy_str))
00294         {
00295           ROS_ERROR("malformed rpy");
00296           return false;
00297           this->rotation.clear();
00298         }
00299       }
00300 
00301       return true;
00302     }
00303   };
00304 };
00305 
00306 }
00307 
00308 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


urdf_interface
Author(s): Wim Meeussen, John Hsu
autogenerated on Mon Aug 19 2013 11:02:01