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 #include <hrl_kinematics/Kinematics.h>
00033
00034 using robot_state_publisher::SegmentPair;
00035
00036 namespace hrl_kinematics {
00037
00038 Kinematics::Kinematics(std::string root_link_name, std::string rfoot_link_name, std::string lfoot_link_name,
00039 const boost::shared_ptr<const urdf::ModelInterface>& urdf_model)
00040 : root_link_name_(root_link_name), rfoot_link_name_(rfoot_link_name), lfoot_link_name_(lfoot_link_name),
00041 nh_(), nh_private_ ("~"),
00042 urdf_model_(urdf_model)
00043 {
00044 initialize();
00045 }
00046
00047 Kinematics::~Kinematics() {
00048
00049 }
00050
00051 void Kinematics::initialize()
00052 {
00053
00054 if (urdf_model_ == NULL)
00055 {
00056
00057 std::string urdf_xml, full_urdf_xml;
00058 nh_private_.param("robot_description_name",urdf_xml,std::string("robot_description"));
00059 nh_.searchParam(urdf_xml,full_urdf_xml);
00060
00061 ROS_DEBUG("Reading xml file from parameter server");
00062
00063 std::string urdf_string;
00064
00065 if (!nh_.getParam(full_urdf_xml, urdf_string))
00066 throw Kinematics::InitFailed("Could not load the xml from parameter server: " + urdf_xml);
00067
00068 boost::shared_ptr<urdf::Model> model;
00069 model.reset(new urdf::Model());
00070
00071 if (!model->initString(urdf_string))
00072 {
00073 throw Kinematics::InitFailed("Could not initialize robot model");
00074 }
00075
00076 urdf_model_ = model;
00077 }
00078
00079
00080 if (!loadKDLModel())
00081 throw Kinematics::InitFailed("Could not load KDL model!");
00082
00083 ROS_INFO("Kinematics initialized");
00084 }
00085
00086 bool Kinematics::loadKDLModel()
00087 {
00088
00089 if (!kdl_parser::treeFromUrdfModel(*urdf_model_, kdl_tree_)) {
00090 ROS_ERROR("Could not initialize tree object");
00091 return false;
00092 }
00093
00094
00095
00096 addChildren(kdl_tree_.getRootSegment());
00097
00098
00099 if (!(kdl_tree_.getChain(root_link_name_, rfoot_link_name_, kdl_chain_right_)
00100 && kdl_tree_.getChain(root_link_name_, lfoot_link_name_, kdl_chain_left_))) {
00101 ROS_ERROR("Could not initialize leg chain objects");
00102 return false;
00103 }
00104
00105 return true;
00106 }
00107
00108
00109
00110
00111 void Kinematics::addChildren(const KDL::SegmentMap::const_iterator segment)
00112 {
00113 const std::string& root = segment->second.segment.getName();
00114
00115 const std::vector<KDL::SegmentMap::const_iterator>& children = segment->second.children;
00116 for (unsigned int i=0; i<children.size(); i++){
00117 const KDL::Segment& child = children[i]->second.segment;
00118 SegmentPair s(children[i]->second.segment, root, child.getName());
00119 if (child.getJoint().getType() == KDL::Joint::None){
00120
00121
00122 ROS_DEBUG("Tree initialization: Skipping fixed segment from %s to %s", root.c_str(), child.getName().c_str());
00123 }
00124 else{
00125 segments_.insert(make_pair(child.getJoint().getName(), s));
00126 ROS_DEBUG("Tree initialization: Adding moving segment from %s to %s", root.c_str(), child.getName().c_str());
00127 }
00128 addChildren(children[i]);
00129 }
00130 }
00131
00132
00133 void Kinematics::createCoGMarker(const std::string& ns, const std::string& frame_id, double radius, const KDL::Vector& cog, visualization_msgs::Marker& marker) const{
00134 marker.header.frame_id = frame_id;
00135 marker.ns = ns;
00136 marker.type = visualization_msgs::Marker::SPHERE;
00137 marker.action = visualization_msgs::Marker::ADD;
00138 marker.pose.position.x = cog.x();
00139 marker.pose.position.y = cog.y();
00140 marker.pose.position.z = cog.z();
00141 marker.scale.x = radius;
00142 marker.scale.y = radius;
00143 marker.scale.z = radius;
00144 marker.color.r = 1.0;
00145 marker.color.a = 0.8;
00146 }
00147
00148 void Kinematics::computeCOMRecurs(const KDL::SegmentMap::const_iterator& current_seg, const std::map<std::string, double>& joint_positions,
00149 const KDL::Frame& tf, KDL::Frame& tf_right_foot, KDL::Frame& tf_left_foot, double& m, KDL::Vector& com) {
00150
00151 double jnt_p = 0.0;
00152
00153 if (current_seg->second.segment.getJoint().getType() != KDL::Joint::None){
00154 std::map<std::string, double>::const_iterator jnt = joint_positions.find(current_seg->second.segment.getJoint().getName());
00155
00156 if (jnt == joint_positions.end()){
00157 ROS_WARN("Could not find joint %s of %s in joint positions. Aborting tree branch.", current_seg->second.segment.getJoint().getName().c_str(), current_seg->first.c_str());
00158 return;
00159 }
00160 jnt_p = jnt->second;
00161 }
00162
00163 KDL::Frame current_frame = tf * current_seg->second.segment.pose(jnt_p);
00164 if (current_seg->first == lfoot_link_name_){
00165 tf_left_foot = current_frame;
00166 ROS_DEBUG("Right foot tip transform found");
00167 } else if (current_seg->first == rfoot_link_name_){
00168 tf_right_foot = current_frame;
00169 ROS_DEBUG("Left foot tip transform found");
00170 }
00171
00172
00173 KDL::Vector current_cog = current_seg->second.segment.getInertia().getCOG();
00174 double current_m = current_seg->second.segment.getInertia().getMass();
00175
00176
00177 com = com + current_m * (current_frame*current_cog);
00178
00179 m += current_m;
00180 ROS_DEBUG("At link %s. local: %f / [%f %f %f]; global: %f / [%f %f %f]",current_seg->first.c_str(), current_m, current_cog.x(), current_cog.y(), current_cog.z(),
00181 m, com.x(), com.y(), com.z());
00182
00183
00184
00185
00186
00187
00188
00189
00190 std::vector<KDL::SegmentMap::const_iterator >::const_iterator child_it;
00191 for (child_it = current_seg->second.children.begin(); child_it !=current_seg->second.children.end(); ++child_it){
00192 computeCOMRecurs(*child_it, joint_positions, current_frame, tf_right_foot, tf_left_foot, m, com);
00193 }
00194
00195 }
00196
00197 void Kinematics::computeCOM(const std::map<std::string, double>& joint_positions, tf::Point& COM, double& mass,
00198 tf::Transform& tf_right_foot, tf::Transform& tf_left_foot){
00199 mass = 0.0;
00200 KDL::Vector com;
00201 KDL::Frame ident = KDL::Frame::Identity();
00202 KDL::Frame transform = ident;
00203 KDL::Frame right_foot_tf = ident;
00204 KDL::Frame left_foot_tf = ident;
00205
00206 computeCOMRecurs(kdl_tree_.getRootSegment(), joint_positions, transform, right_foot_tf, left_foot_tf, mass, com);
00207 if (left_foot_tf == ident || right_foot_tf == ident){
00208 ROS_ERROR("Could not obtain left or right foot transforms");
00209 return;
00210 }
00211
00212 if (mass <= 0.0){
00213 ROS_WARN("Total mass is 0, no CoM possible.");
00214 COM.setValue(0,0,0);
00215 return;
00216 }
00217
00218 com = 1.0/mass * com;
00219 ROS_DEBUG("Total mass: %f CoG: (%f %f %f)", mass, com.x(), com.y(), com.z());
00220
00221 COM.setValue(com.x(), com.y(), com.z());
00222 tf::transformKDLToTF(right_foot_tf, tf_right_foot);
00223 tf::transformKDLToTF(left_foot_tf, tf_left_foot);
00224 }
00225
00226
00227
00228 }