$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/hrl_kinematics/include/hrl_kinematics/Kinematics.h $ 00002 // SVN $Id: Kinematics.h 3069 2012-08-21 14:26:59Z hornunga@informatik.uni-freiburg.de $ 00003 00004 /* 00005 * hrl_kinematics - a kinematics library for humanoid robots based on KDL 00006 * 00007 * Copyright 2011-2012 Armin Hornung, University of Freiburg 00008 * License: BSD 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above copyright 00016 * notice, this list of conditions and the following disclaimer in the 00017 * documentation and/or other materials provided with the distribution. 00018 * * Neither the name of the University of Freiburg nor the names of its 00019 * contributors may be used to endorse or promote products derived from 00020 * this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00023 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00024 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00025 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00026 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00027 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00028 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00029 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00030 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00031 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00035 #ifndef HRL_KINEMATICS_KINEMATICS_H_ 00036 #define HRL_KINEMATICS_KINEMATICS_H_ 00037 00038 #include <string> 00039 #include <map> 00040 #include <exception> 00041 #include <math.h> 00042 00043 #include <ros/ros.h> 00044 #include <tf/transform_listener.h> 00045 #include <tf_conversions/tf_kdl.h> 00046 #include <tf/transform_datatypes.h> 00047 #include <kdl_parser/kdl_parser.hpp> 00048 #include <kdl/jntarray.hpp> 00049 #include <kdl/frames.hpp> 00050 #include <kdl/segment.hpp> 00051 #include <kdl/joint.hpp> 00052 00053 #include <robot_state_publisher/robot_state_publisher.h> 00054 #include <kdl_parser/kdl_parser.hpp> 00055 #include <sensor_msgs/JointState.h> 00056 #include <visualization_msgs/MarkerArray.h> 00057 00058 00059 namespace hrl_kinematics { 00060 typedef std::map<std::string, double> JointMap; 00061 00067 class Kinematics { 00068 public: 00069 enum FootSupport {SUPPORT_DOUBLE, SUPPORT_SINGLE_RIGHT, SUPPORT_SINGLE_LEFT}; 00070 class InitFailed : public std::runtime_error 00071 { 00072 public: 00073 InitFailed(const std::string &what) 00074 : std::runtime_error(what) {} 00075 }; 00076 00077 Kinematics(); 00078 virtual ~Kinematics(); 00079 00090 void computeCOM(const JointMap& joint_positions, tf::Point& com, double& mass, 00091 tf::Transform& tf_right_foot, tf::Transform& tf_left_foot); 00092 00093 00094 protected: 00095 bool loadModel(const std::string xml); 00096 void addChildren(const KDL::SegmentMap::const_iterator segment); 00097 00098 void computeCOMRecurs(const KDL::SegmentMap::const_iterator& currentSeg, const std::map<std::string, double>& joint_positions, 00099 const KDL::Frame& tf, KDL::Frame& tf_right_foot, KDL::Frame& tf_left_foot, double& m, KDL::Vector& cog); 00100 void createCoGMarker(const std::string& ns, const std::string& frame_id, double radius, const KDL::Vector& cog, visualization_msgs::Marker& marker) const; 00101 urdf::Model urdf_model_; 00102 KDL::Tree kdl_tree_; 00103 KDL::Chain kdl_chain_right_; 00104 KDL::Chain kdl_chain_left_; 00105 00106 ros::NodeHandle nh_, nh_private_; 00107 std::string root_link_name_; 00108 std::string rfoot_link_name_; 00109 std::string lfoot_link_name_; 00110 00111 unsigned int num_joints_; 00112 std::map<std::string, robot_state_publisher::SegmentPair> segments_; 00113 }; 00114 00115 } /* namespace hrl_kinematics */ 00116 #endif