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 #ifndef HRL_KINEMATICS_KINEMATICS_H_
00033 #define HRL_KINEMATICS_KINEMATICS_H_
00034
00035 #include <string>
00036 #include <map>
00037 #include <exception>
00038 #include <math.h>
00039
00040 #include <ros/ros.h>
00041 #include <tf/transform_listener.h>
00042 #include <tf_conversions/tf_kdl.h>
00043 #include <tf/transform_datatypes.h>
00044 #include <urdf/model.h>
00045 #include <kdl_parser/kdl_parser.hpp>
00046 #include <kdl/jntarray.hpp>
00047 #include <kdl/frames.hpp>
00048 #include <kdl/segment.hpp>
00049 #include <kdl/joint.hpp>
00050
00051 #include <robot_state_publisher/robot_state_publisher.h>
00052 #include <kdl_parser/kdl_parser.hpp>
00053 #include <sensor_msgs/JointState.h>
00054 #include <visualization_msgs/MarkerArray.h>
00055
00056
00057 namespace hrl_kinematics {
00058 typedef std::map<std::string, double> JointMap;
00059
00065 class Kinematics {
00066 public:
00067 enum FootSupport {SUPPORT_DOUBLE, SUPPORT_SINGLE_RIGHT, SUPPORT_SINGLE_LEFT};
00068 class InitFailed : public std::runtime_error
00069 {
00070 public:
00071 InitFailed(const std::string &what)
00072 : std::runtime_error(what) {}
00073 };
00074
00082 Kinematics(std::string root_link_name = "base_link", std::string rfoot_link_name = "r_sole", std::string lfoot_link_name = "l_sole",
00083 const boost::shared_ptr<const urdf::ModelInterface>& urdf_model = boost::shared_ptr<const urdf::ModelInterface>());
00084
00085 virtual ~Kinematics();
00086 void initialize();
00087
00098 void computeCOM(const JointMap& joint_positions, tf::Point& com, double& mass,
00099 tf::Transform& tf_right_foot, tf::Transform& tf_left_foot);
00100
00101
00102 protected:
00103 bool loadKDLModel();
00104 void addChildren(const KDL::SegmentMap::const_iterator segment);
00105
00106 void computeCOMRecurs(const KDL::SegmentMap::const_iterator& currentSeg, const std::map<std::string, double>& joint_positions,
00107 const KDL::Frame& tf, KDL::Frame& tf_right_foot, KDL::Frame& tf_left_foot, double& m, KDL::Vector& cog);
00108 void createCoGMarker(const std::string& ns, const std::string& frame_id, double radius, const KDL::Vector& cog, visualization_msgs::Marker& marker) const;
00109
00110 boost::shared_ptr<const urdf::ModelInterface> urdf_model_;
00111 KDL::Tree kdl_tree_;
00112 KDL::Chain kdl_chain_right_;
00113 KDL::Chain kdl_chain_left_;
00114
00115 ros::NodeHandle nh_, nh_private_;
00116 std::string root_link_name_;
00117 std::string rfoot_link_name_;
00118 std::string lfoot_link_name_;
00119
00120 unsigned int num_joints_;
00121 std::map<std::string, robot_state_publisher::SegmentPair> segments_;
00122 };
00123
00124 }
00125 #endif