Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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 <urdf/model.h>
00048 #include <kdl_parser/kdl_parser.hpp>
00049 #include <kdl/jntarray.hpp>
00050 #include <kdl/frames.hpp>
00051 #include <kdl/segment.hpp>
00052 #include <kdl/joint.hpp>
00053
00054 #include <robot_state_publisher/robot_state_publisher.h>
00055 #include <kdl_parser/kdl_parser.hpp>
00056 #include <sensor_msgs/JointState.h>
00057 #include <visualization_msgs/MarkerArray.h>
00058
00059
00060 namespace hrl_kinematics {
00061 typedef std::map<std::string, double> JointMap;
00062
00068 class Kinematics {
00069 public:
00070 enum FootSupport {SUPPORT_DOUBLE, SUPPORT_SINGLE_RIGHT, SUPPORT_SINGLE_LEFT};
00071 class InitFailed : public std::runtime_error
00072 {
00073 public:
00074 InitFailed(const std::string &what)
00075 : std::runtime_error(what) {}
00076 };
00077
00078 Kinematics();
00079 virtual ~Kinematics();
00080
00091 void computeCOM(const JointMap& joint_positions, tf::Point& com, double& mass,
00092 tf::Transform& tf_right_foot, tf::Transform& tf_left_foot);
00093
00094
00095 protected:
00096 bool loadModel(const std::string xml);
00097 void addChildren(const KDL::SegmentMap::const_iterator segment);
00098
00099 void computeCOMRecurs(const KDL::SegmentMap::const_iterator& currentSeg, const std::map<std::string, double>& joint_positions,
00100 const KDL::Frame& tf, KDL::Frame& tf_right_foot, KDL::Frame& tf_left_foot, double& m, KDL::Vector& cog);
00101 void createCoGMarker(const std::string& ns, const std::string& frame_id, double radius, const KDL::Vector& cog, visualization_msgs::Marker& marker) const;
00102 urdf::Model urdf_model_;
00103 KDL::Tree kdl_tree_;
00104 KDL::Chain kdl_chain_right_;
00105 KDL::Chain kdl_chain_left_;
00106
00107 ros::NodeHandle nh_, nh_private_;
00108 std::string root_link_name_;
00109 std::string rfoot_link_name_;
00110 std::string lfoot_link_name_;
00111
00112 unsigned int num_joints_;
00113 std::map<std::string, robot_state_publisher::SegmentPair> segments_;
00114 };
00115
00116 }
00117 #endif